MainSystem
This is the class which defines a (multibody) system. The MainSystem shall only be created by SC.AddSystem()
, not with exu.MainSystem()
, as the latter one would not be linked to a SystemContainer. In some cases, you may use SC.Append(mbs). In C++, there is a MainSystem (the part which links to Python) and a System (computational part). For that reason, the name is MainSystem on the Python side, but it is often just called ‘system’. For compatibility, it is recommended to denote the variable holding this system as mbs, the multibody dynamics system. It can be created, visualized and computed. Use the following functions for system manipulation.
import exudyn as exu
SC = exu.SystemContainer()
mbs = SC.AddSystem()
The class MainSystem has the following functions and structures:
- Assemble():assemble items (nodes, bodies, markers, loads, …) of multibody system; Calls CheckSystemIntegrity(…), AssembleCoordinates(), AssembleLTGLists(), AssembleInitializeSystemCoordinates(), and AssembleSystemInitialize()
- AssembleCoordinates():assemble coordinates: assign computational coordinates to nodes and constraints (algebraic variables)
- AssembleLTGLists():build LTG coordinate lists for objects (used to build global ODE2RHS, MassMatrix, etc. vectors and matrices) and store special object lists (body, connector, constraint, …)
- AssembleInitializeSystemCoordinates():initialize all system-wide coordinates based on initial values given in nodes
- AssembleSystemInitialize():initialize some system data, e.g., generalContact objects (searchTree, etc.)
- Reset():reset all lists of items (nodes, bodies, markers, loads, …) and temporary vectors; deallocate memory
- GetSystemContainer():return the systemContainer where the mainSystem (mbs) was created
- WaitForUserToContinue(printMessage = True):interrupt further computation until user input –> ‘pause’ function; this command runs a loop in the background to have active response of the render window, e.g., to open the visualization dialog or use the right-mouse-button; behaves similar as SC.WaitForRenderEngineStopFlagthis()
- SendRedrawSignal():this function is used to send a signal to the renderer that the scene shall be redrawn because the visualization state has been updated
- GetRenderEngineStopFlag():get the current stop simulation flag; True=user wants to stop simulation
- SetRenderEngineStopFlag(stopFlag):set the current stop simulation flag; set to False, in order to continue a previously user-interrupted simulation
- ActivateRendering(flag = True):activate (flag=True) or deactivate (flag=False) rendering for this system
- SetPreStepUserFunction(value):Sets a user function PreStepUserFunction(mbs, t) executed at beginning of every computation step; in normal case return True; return False to stop simulation after current step; set to 0 (integer) in order to erase user function. Note that the time returned is already the end of the step, which allows to compute forces consistently with trapezoidal integrators; for higher order Runge-Kutta methods, step time will be available only in object-user functions.Example:
def PreStepUserFunction(mbs, t): print(mbs.systemData.NumberOfNodes()) if(t>1): return False return True mbs.SetPreStepUserFunction(PreStepUserFunction)
- GetPreStepUserFunction(asDict = False):Returns the preStepUserFunction.
- SetPostStepUserFunction(value):Sets a user function PostStepUserFunction(mbs, t) executed at beginning of every computation step; in normal case return True; return False to stop simulation after current step; set to 0 (integer) in order to erase user function.Example:
def PostStepUserFunction(mbs, t): print(mbs.systemData.NumberOfNodes()) if(t>1): return False return True mbs.SetPostStepUserFunction(PostStepUserFunction)
- GetPostStepUserFunction(asDict = False):Returns the postStepUserFunction.
- SetPostNewtonUserFunction(value):Sets a user function PostNewtonUserFunction(mbs, t) executed after successful Newton iteration in implicit or static solvers and after step update of explicit solvers, but BEFORE PostNewton functions are called by the solver; function returns list [discontinuousError, recommendedStepSize], containing a error of the PostNewtonStep, which is compared to [solver].discontinuous.iterationTolerance. The recommendedStepSize shall be negative, if no recommendation is given, 0 in order to enforce minimum step size or a specific value to which the current step size will be reduced and the step will be repeated; use this function, e.g., to reduce step size after impact or change of data variables; set to 0 (integer) in order to erase user function. Similar described by Flores and Ambrosio, https://doi.org/10.1007/s11044-010-9209-8Example:
def PostNewtonUserFunction(mbs, t): if(t>1): return [0, 1e-6] return [0,0] mbs.SetPostNewtonUserFunction(PostNewtonUserFunction)
- GetPostNewtonUserFunction(asDict = False):Returns the postNewtonUserFunction.
- AddGeneralContact():add a new general contact, used to enable efficient contact computation between objects (nodes or markers)
- GetGeneralContact(generalContactNumber):get read/write access to GeneralContact with index generalContactNumber stored in mbs; Examples shows how to access the GeneralContact object added with last AddGeneralContact() command:Example:
gc=mbs.GetGeneralContact(mbs.NumberOfGeneralContacts()-1)
- DeleteGeneralContact(generalContactNumber):delete GeneralContact with index generalContactNumber in mbs; other general contacts are resorted (index changes!)
- NumberOfGeneralContacts():Return number of GeneralContact objects in mbs
- GetAvailableFactoryItems():get all available items to be added (nodes, objects, etc.); this is useful in particular in case of additional user elements to check if they are available; the available items are returned as dictionary, containing lists of strings for Node, Object, etc.
- GetDictionary():[UNDER DEVELOPMENT]: return the dictionary of the system data (todo: and state), e.g., to copy the system or for pickling
- SetDictionary(systemDict):[UNDER DEVELOPMENT]: set system data (todo: and state) from given dictionary; used for pickling
- __repr__():return the representation of the system, which can be, e.g., printedExample:
print(mbs)
- systemIsConsistent:this flag is used by solvers to decide, whether the system is in a solvable state; this flag is set to False as long as Assemble() has not been called; any modification to the system, such as Add…(), Modify…(), etc. will set the flag to False again; this flag can be modified (set to True), if a change of e.g.~an object (change of stiffness) or load (change of force) keeps the system consistent, but would normally lead to systemIsConsistent=False
- interactiveMode:set this flag to True in order to invoke a Assemble() command in every system modification, e.g. AddNode, AddObject, ModifyNode, …; this helps that the system can be visualized in interactive mode.
- variables:this dictionary may be used by the user to store model-specific data, in order to avoid global Python variables in complex models; mbs.variables[“myvar”] = 42
- sys:this dictionary is used by exudyn Python libraries, e.g., solvers, to avoid global Python variables
- solverSignalJacobianUpdate:this flag is used by solvers to decide, whether the jacobian should be updated; at beginning of simulation and after jacobian computation, this flag is set automatically to False; use this flag to indicate system changes, e.g. during time integration
- systemData:Access to SystemData structure; enables access to number of nodes, objects, … and to (current, initial, reference, …) state variables (ODE2, AE, Data,…)
MainSystem extensions (create)
This section represents extensions to MainSystem, which are direct calls to Python functions; the ‘create’ extensions to simplify the creation of multibody systems, such as CreateMassPoint(…); these extensions allow a more intuitive interaction with the MainSystem class, see the following example. For activation, import exudyn.mainSystemExtensions
or exudyn.utilities
1import exudyn as exu
2from exudyn.utilities import *
3#alternative: import exudyn.mainSystemExtensions
4SC = exu.SystemContainer()
5mbs = SC.AddSystem()
6#
7#create rigid body
8b1=mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[0.1,0.1,1]),
9 referencePosition = [1,0,0],
10 gravity = [0,0,-9.81])
Function: CreateGround
CreateGround(name = ''
, referencePosition = [0.,0.,0.]
, referenceRotationMatrix = np.eye(3)
, graphicsDataList = []
, graphicsDataUserFunction = 0
, show = True
)
- function description:helper function to create a ground object, using arguments of ObjectGround; this function is mainly added for consistency with other mainSystemExtensions- NOTE that this function is added to MainSystem via Python function MainSystemCreateGround.
- input:
name
: name string for objectreferencePosition
: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass)referenceRotationMatrix
: reference rotation matrix for rigid body node (always 3D matrix, no matter if 2D or 3D body)graphicsDataList
: list of GraphicsData for optional ground visualizationgraphicsDataUserFunction
: a user function graphicsDataUserFunction(mbs, itemNumber)->BodyGraphicsData (list of GraphicsData), which can be used to draw user-defined graphics; this is much slower than regular GraphicsDatacolor
: color of nodeshow
: True: show ground object; - output:ObjectIndex; returns ground object index
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
ground=mbs.CreateGround(referencePosition = [2,0,0],
graphicsDataList = [exu.graphics.CheckerBoard(point=[0,0,0], normal=[0,1,0],size=4)])
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
basicTutorial2024.py (Ex), beamTutorial.py (Ex), bicycleIftommBenchmark.py (Ex), bungeeJump.py (Ex), cartesianSpringDamper.py (Ex), ConvexContactTest.py (TM), rigidBodySpringDamperIntrinsic.py (TM), sliderCrank3Dbenchmark.py (TM)
Function: CreateMassPoint
CreateMassPoint(name = ''
, referencePosition = [0.,0.,0.]
, initialDisplacement = [0.,0.,0.]
, initialVelocity = [0.,0.,0.]
, physicsMass = 0
, gravity = [0.,0.,0.]
, graphicsDataList = []
, drawSize = -1
, color = [-1.,-1.,-1.,-1.]
, show = True
, create2D = False
, returnDict = False
)
- function description:helper function to create 2D or 3D mass point object and node, using arguments as in NodePoint and MassPoint- NOTE that this function is added to MainSystem via Python function MainSystemCreateMassPoint.
- input:
name
: name string for object, node is ‘Node:’+namereferencePosition
: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass)initialDisplacement
: initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass)initialVelocity
: initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass)physicsMass
: mass of mass pointgravity
: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass)graphicsDataList
: list of GraphicsData for optional mass visualizationdrawSize
: general drawing size of nodecolor
: color of nodeshow
: True: if graphicsData list is empty, node is shown, otherwise body is shown; otherwise, nothing is showncreate2D
: if True, create NodePoint2D and MassPoint2DreturnDict
: if False, returns object index; if True, returns dict of all information on created object and node - output:Union[dict, ObjectIndex]; returns mass point object index or dict with all data on request (if returnDict=True)
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0=mbs.CreateMassPoint(referencePosition = [0,0,0],
initialVelocity = [2,5,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=exu.graphics.color.blue)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
basicTutorial2024.py (Ex), cartesianSpringDamper.py (Ex), cartesianSpringDamperUserFunction.py (Ex), chatGPTupdate.py (Ex), springDamperTutorialNew.py (Ex), mainSystemExtensionsTests.py (TM), symbolicUserFunctionTest.py (TM), taskmanagerTest.py (TM)
Function: CreateRigidBody
CreateRigidBody(name = ''
, referencePosition = [0.,0.,0.]
, referenceRotationMatrix = np.eye(3)
, initialVelocity = [0.,0.,0.]
, initialAngularVelocity = [0.,0.,0.]
, initialDisplacement = None
, initialRotationMatrix = None
, inertia = None
, gravity = [0.,0.,0.]
, nodeType = exudyn.NodeType.RotationEulerParameters
, graphicsDataList = []
, graphicsDataUserFunction = 0
, drawSize = -1
, color = [-1.,-1.,-1.,-1.]
, show = True
, create2D = False
, returnDict = False
)
- function description:helper function to create 3D (or 2D) rigid body object and node; all quantities are global (angular velocity, etc.)- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBody.
- input:
name
: name string for object, node is ‘Node:’+namereferencePosition
: reference position vector for rigid body node (always a 3D vector, no matter if 2D or 3D body)referenceRotationMatrix
: reference rotation matrix for rigid body node (always 3D matrix, no matter if 2D or 3D body)initialVelocity
: initial translational velocity vector for node (always a 3D vector, no matter if 2D or 3D body)initialAngularVelocity
: initial angular velocity vector for node (always a 3D vector, no matter if 2D or 3D body)initialDisplacement
: initial translational displacement vector for node (always a 3D vector, no matter if 2D or 3D body); these displacements are deviations from reference position, e.g. for a finite element node [None: unused]initialRotationMatrix
: initial rotation provided as matrix (always a 3D matrix, no matter if 2D or 3D body); this rotation is superimposed to reference rotation [None: unused]inertia
: an instance of class RigidBodyInertia, see rigidBodyUtilities; may also be from derived class (InertiaCuboid, InertiaMassPoint, InertiaCylinder, …)gravity
: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass)graphicsDataList
: list of GraphicsData for rigid body visualization; use exudyn.graphics functions to create GraphicsData for basic solidsgraphicsDataUserFunction
: a user function graphicsDataUserFunction(mbs, itemNumber)->BodyGraphicsData (list of GraphicsData), which can be used to draw user-defined graphics; this is much slower than regular GraphicsDatadrawSize
: general drawing size of nodecolor
: color of nodeshow
: True: if graphicsData list is empty, node is shown, otherwise body is shown; False: nothing is showncreate2D
: if True, create NodeRigidBody2D and ObjectRigidBody2DreturnDict
: if False, returns object index; if True, returns dict of all information on created object and node - output:Union[dict, ObjectIndex]; returns rigid body object index (or dict with ‘nodeNumber’, ‘objectNumber’ and possibly ‘loadNumber’ and ‘markerBodyMass’ if returnDict=True)
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [1,0,0],
initialVelocity = [2,5,0],
initialAngularVelocity = [5,0.5,0.7],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.red)])
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addPrismaticJoint.py (Ex), addRevoluteJoint.py (Ex), ANCFrotatingCable2D.py (Ex), bicycleIftommBenchmark.py (Ex), bungeeJump.py (Ex), bricardMechanism.py (TM), carRollingDiscTest.py (TM), complexEigenvaluesTest.py (TM)
Function: CreateSpringDamper
CreateSpringDamper(name = ''
, bodyNumbers = [None, None]
, localPosition0 = [0.,0.,0.]
, localPosition1 = [0.,0.,0.]
, referenceLength = None
, stiffness = 0.
, damping = 0.
, force = 0.
, velocityOffset = 0.
, springForceUserFunction = 0
, bodyOrNodeList = [None, None]
, bodyList = [None, None]
, show = True
, drawSize = -1
, color = exudyn.graphics.color.default
)
- function description:helper function to create SpringDamper connector, using arguments from ObjectConnectorSpringDamper; similar interface as CreateDistanceConstraint(…), see there for for further information- NOTE that this function is added to MainSystem via Python function MainSystemCreateSpringDamper.
- input:
name
: name string for connector; markers get Marker0:name and Marker1:namebodyNumbers
: a list of two body numbers (ObjectIndex) to be connectedlocalPosition0
: local position (as 3D list or numpy array) on body0, if not a node numberlocalPosition1
: local position (as 3D list or numpy array) on body1, if not a node numberreferenceLength
: if None, length is computed from reference position of bodies or nodes; if not None, this scalar reference length is used for springstiffness
: scalar stiffness coefficientdamping
: scalar damping coefficientforce
: scalar additional force appliedvelocityOffset
: scalar offset: if referenceLength is changed over time, the velocityOffset may be changed accordingly to emulate a reference motionspringForceUserFunction
: a user function springForceUserFunction(mbs, t, itemNumber, deltaL, deltaL_t, stiffness, damping, force)->float ; this function replaces the internal connector force compuationbodyOrNodeList
: alternative to bodyNumbers; a list of object numbers (with specific localPosition0/1) or node numbers; may alse be mixed types; to use this case, set bodyNumbers = [None,None]show
: if True, connector visualization is drawndrawSize
: general drawing size of connectorcolor
: color of connector - output:ObjectIndex; returns index of newly created object
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateMassPoint(referencePosition = [2,0,0],
initialVelocity = [2,5,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=exu.graphics.color.blue)
oGround = mbs.AddObject(ObjectGround())
#add vertical spring
oSD = mbs.CreateSpringDamper(bodyNumbers=[oGround, b0],
localPosition0=[2,1,0],
localPosition1=[0,0,0],
stiffness=1e4, damping=1e2,
drawSize=0.2)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
SC.visualizationSettings.nodes.drawNodesAsPoint=False
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
basicTutorial2024.py (Ex), chatGPTupdate.py (Ex), springDamperTutorialNew.py (Ex), springMassFriction.py (Ex), symbolicUserFunctionMasses.py (Ex), mainSystemExtensionsTests.py (TM), symbolicUserFunctionTest.py (TM), taskmanagerTest.py (TM)
Function: CreateCartesianSpringDamper
CreateCartesianSpringDamper(name = ''
, bodyNumbers = [None, None]
, localPosition0 = [0.,0.,0.]
, localPosition1 = [0.,0.,0.]
, stiffness = [0.,0.,0.]
, damping = [0.,0.,0.]
, offset = [0.,0.,0.]
, springForceUserFunction = 0
, bodyOrNodeList = [None, None]
, bodyList = [None, None]
, show = True
, drawSize = -1
, color = exudyn.graphics.color.default
)
- function description:helper function to create CartesianSpringDamper connector, using arguments from ObjectConnectorCartesianSpringDamper- NOTE that this function is added to MainSystem via Python function MainSystemCreateCartesianSpringDamper.
- input:
name
: name string for connector; markers get Marker0:name and Marker1:namebodyNumbers
: a list of two body numbers (ObjectIndex) to be connectedlocalPosition0
: local position (as 3D list or numpy array) on body0, if not a node numberlocalPosition1
: local position (as 3D list or numpy array) on body1, if not a node numberstiffness
: stiffness coefficients (as 3D list or numpy array)damping
: damping coefficients (as 3D list or numpy array)offset
: offset vector (as 3D list or numpy array)springForceUserFunction
: a user function springForceUserFunction(mbs, t, itemNumber, displacement, velocity, stiffness, damping, offset)->[float,float,float] ; this function replaces the internal connector force compuationbodyOrNodeList
: alternative to bodyNumbers; a list of object numbers (with specific localPosition0/1) or node numbers; may alse be mixed types; to use this case, set bodyNumbers = [None,None]show
: if True, connector visualization is drawndrawSize
: general drawing size of connectorcolor
: color of connector - output:ObjectIndex; returns index of newly created object
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateMassPoint(referencePosition = [7,0,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=exu.graphics.color.blue)
oGround = mbs.AddObject(ObjectGround())
oSD = mbs.CreateCartesianSpringDamper(bodyNumbers=[oGround, b0],
localPosition0=[7.5,1,0],
localPosition1=[0,0,0],
stiffness=[200,2000,0], damping=[2,20,0],
drawSize=0.2)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
SC.visualizationSettings.nodes.drawNodesAsPoint=False
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
cartesianSpringDamper.py (Ex), cartesianSpringDamperUserFunction.py (Ex), chatGPTupdate.py (Ex), complexEigenvaluesTest.py (TM), computeODE2AEeigenvaluesTest.py (TM), mainSystemExtensionsTests.py (TM)
Function: CreateRigidBodySpringDamper
CreateRigidBodySpringDamper(name = ''
, bodyNumbers = [None, None]
, localPosition0 = [0.,0.,0.]
, localPosition1 = [0.,0.,0.]
, stiffness = np.zeros((6,6))
, damping = np.zeros((6,6))
, offset = [0.,0.,0.,0.,0.,0.]
, rotationMatrixJoint = np.eye(3)
, useGlobalFrame = True
, intrinsicFormulation = True
, springForceTorqueUserFunction = 0
, postNewtonStepUserFunction = 0
, bodyOrNodeList = [None, None]
, bodyList = [None, None]
, show = True
, drawSize = -1
, color = exudyn.graphics.color.default
)
- function description:helper function to create RigidBodySpringDamper connector, using arguments from ObjectConnectorRigidBodySpringDamper, see there for the full documentation- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBodySpringDamper.
- input:
name
: name string for connector; markers get Marker0:name and Marker1:namebodyNumbers
: a list of two body numbers (ObjectIndex) to be connectedlocalPosition0
: local position (as 3D list or numpy array) on body0, if not a node numberlocalPosition1
: local position (as 3D list or numpy array) on body1, if not a node numberstiffness
: stiffness coefficients (as 6D matrix or numpy array)damping
: damping coefficients (as 6D matrix or numpy array)offset
: offset vector (as 6D list or numpy array)rotationMatrixJoint
: additional rotation matrix; in case useGlobalFrame=False, it transforms body0/node0 local frame to joint frame; if useGlobalFrame=True, it transforms global frame to joint frameuseGlobalFrame
: if False, the rotationMatrixJoint is defined in the local coordinate system of body0intrinsicFormulation
: if True, uses intrinsic formulation of Maserati and Morandini, which uses matrix logarithm and is independent of order of markers (preferred formulation); otherwise, Tait-Bryan angles are used for computation of torque, see documentationspringForceTorqueUserFunction
: a user function springForceTorqueUserFunction(mbs, t, itemNumber, displacement, rotation, velocity, angularVelocity, stiffness, damping, rotJ0, rotJ1, offset)->[float,float,float, float,float,float] ; this function replaces the internal connector force / torque compuationpostNewtonStepUserFunction
: a special user function postNewtonStepUserFunction(mbs, t, Index itemIndex, dataCoordinates, displacement, rotation, velocity, angularVelocity, stiffness, damping, rotJ0, rotJ1, offset)->[PNerror, recommendedStepSize, data[0], data[1], …] ; for details, see RigidBodySpringDamper for full docubodyOrNodeList
: alternative to bodyNumbers; a list of object numbers (with specific localPosition0/1) or node numbers; may alse be mixed types; to use this case, set bodyNumbers = [None,None]show
: if True, connector visualization is drawndrawSize
: general drawing size of connectorcolor
: color of connector - output:ObjectIndex; returns index of newly created object
- example:
#coming later
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: CreateRevoluteJoint
CreateRevoluteJoint(name = ''
, bodyNumbers = [None, None]
, position = []
, axis = []
, useGlobalFrame = True
, show = True
, axisRadius = 0.1
, axisLength = 0.4
, color = exudyn.graphics.color.default
)
- function description:Create revolute joint between two bodies; definition of joint position and axis in global coordinates (alternatively in body0 local coordinates) for reference configuration of bodies; all markers, markerRotation and other quantities are automatically computed- NOTE that this function is added to MainSystem via Python function MainSystemCreateRevoluteJoint.
- input:
name
: name string for joint; markers get Marker0:name and Marker1:namebodyNumbers
: a list of object numbers for body0 and body1; must be rigid body or ground objectposition
: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global position of the joint in reference configuration; else: local position in body0axis
: a 3D vector as list or np.array containing the joint axis either in local body0 coordinates (useGlobalFrame=False), or in global reference configuration (useGlobalFrame=True)useGlobalFrame
: if False, the position and axis vectors are defined in the local coordinate system of body0, otherwise in global (reference) coordinatesshow
: if True, connector visualization is drawnaxisRadius
: radius of axis for connector graphical representationaxisLength
: length of axis for connector graphical representationcolor
: color of connector - output:[ObjectIndex, MarkerIndex, MarkerIndex]; returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [3,0,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.steelblue)])
oGround = mbs.AddObject(ObjectGround())
mbs.CreateRevoluteJoint(bodyNumbers=[oGround, b0], position=[2.5,0,0], axis=[0,0,1],
useGlobalFrame=True, axisRadius=0.02, axisLength=0.14)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addRevoluteJoint.py (Ex), bicycleIftommBenchmark.py (Ex), chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), multiMbsTest.py (Ex), bricardMechanism.py (TM), mainSystemExtensionsTests.py (TM), perf3DRigidBodies.py (TM)
Function: CreatePrismaticJoint
CreatePrismaticJoint(name = ''
, bodyNumbers = [None, None]
, position = []
, axis = []
, useGlobalFrame = True
, show = True
, axisRadius = 0.1
, axisLength = 0.4
, color = exudyn.graphics.color.default
)
- function description:Create prismatic joint between two bodies; definition of joint position and axis in global coordinates (alternatively in body0 local coordinates) for reference configuration of bodies; all markers, markerRotation and other quantities are automatically computed- NOTE that this function is added to MainSystem via Python function MainSystemCreatePrismaticJoint.
- input:
name
: name string for joint; markers get Marker0:name and Marker1:namebodyNumbers
: a list of object numbers for body0 and body1; must be rigid body or ground objectposition
: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global position of the joint in reference configuration; else: local position in body0axis
: a 3D vector as list or np.array containing the joint axis either in local body0 coordinates (useGlobalFrame=False), or in global reference configuration (useGlobalFrame=True)useGlobalFrame
: if False, the position and axis vectors are defined in the local coordinate system of body0, otherwise in global (reference) coordinatesshow
: if True, connector visualization is drawnaxisRadius
: radius of axis for connector graphical representationaxisLength
: length of axis for connector graphical representationcolor
: color of connector - output:[ObjectIndex, MarkerIndex, MarkerIndex]; returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [4,0,0],
initialVelocity = [0,4,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.steelblue)])
oGround = mbs.AddObject(ObjectGround())
mbs.CreatePrismaticJoint(bodyNumbers=[oGround, b0], position=[3.5,0,0], axis=[0,1,0],
useGlobalFrame=True, axisRadius=0.02, axisLength=1)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addPrismaticJoint.py (Ex), chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), mainSystemExtensionsTests.py (TM)
Function: CreateSphericalJoint
CreateSphericalJoint(name = ''
, bodyNumbers = [None, None]
, position = []
, constrainedAxes = [1,1,1]
, useGlobalFrame = True
, show = True
, jointRadius = 0.1
, color = exudyn.graphics.color.default
)
- function description:Create spherical joint between two bodies; definition of joint position in global coordinates (alternatively in body0 local coordinates) for reference configuration of bodies; all markers are automatically computed- NOTE that this function is added to MainSystem via Python function MainSystemCreateSphericalJoint.
- input:
name
: name string for joint; markers get Marker0:name and Marker1:namebodyNumbers
: a list of object numbers for body0 and body1; must be mass point, rigid body or ground objectposition
: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global position of the joint in reference configuration; else: local position in body0constrainedAxes
: flags, which determines which (global) translation axes are constrained; each entry may only be 0 (=free) axis or 1 (=constrained axis)useGlobalFrame
: if False, the point and axis vectors are defined in the local coordinate system of body0show
: if True, connector visualization is drawnjointRadius
: radius of sphere for connector graphical representationcolor
: color of connector - output:[ObjectIndex, MarkerIndex, MarkerIndex]; returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [5,0,0],
initialAngularVelocity = [5,0,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.orange)])
oGround = mbs.AddObject(ObjectGround())
mbs.CreateSphericalJoint(bodyNumbers=[oGround, b0], position=[5.5,0,0],
useGlobalFrame=True, jointRadius=0.06)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
driveTrainTest.py (TM), mainSystemExtensionsTests.py (TM)
Function: CreateGenericJoint
CreateGenericJoint(name = ''
, bodyNumbers = [None, None]
, position = []
, rotationMatrixAxes = np.eye(3)
, constrainedAxes = [1,1,1, 1,1,1]
, useGlobalFrame = True
, offsetUserFunction = 0
, offsetUserFunction_t = 0
, show = True
, axesRadius = 0.1
, axesLength = 0.4
, color = exudyn.graphics.color.default
)
- function description:Create generic joint between two bodies; definition of joint position (position) and axes (rotationMatrixAxes) in global coordinates (useGlobalFrame=True) or in local coordinates of body0 (useGlobalFrame=False), where rotationMatrixAxes is an additional rotation to body0; all markers, markerRotation and other quantities are automatically computed- NOTE that this function is added to MainSystem via Python function MainSystemCreateGenericJoint.
- input:
name
: name string for joint; markers get Marker0:name and Marker1:namebodyNumber0
: a object number for body0, must be rigid body or ground objectbodyNumber1
: a object number for body1, must be rigid body or ground objectposition
: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global position of the joint in reference configuration; else: local position in body0rotationMatrixAxes
: rotation matrix which defines orientation of constrainedAxes; if useGlobalFrame, this rotation matrix is global, else the rotation matrix is post-multiplied with the rotation of body0, identical with rotationMarker0 in the jointconstrainedAxes
: flag, which determines which translation (0,1,2) and rotation (3,4,5) axes are constrained; each entry may only be 0 (=free) axis or 1 (=constrained axis); ALL constrained Axes are defined relative to reference rotation of body0 times rotation0useGlobalFrame
: if False, the position is defined in the local coordinate system of body0, otherwise it is defined in global coordinatesoffsetUserFunction
: a user function offsetUserFunction(mbs, t, itemNumber, offsetUserFunctionParameters)->float ; this function replaces the internal (constant) by a user-defined offset. This allows to realize rheonomic joints and allows kinematic simulationoffsetUserFunction_t
: a user function offsetUserFunction_t(mbs, t, itemNumber, offsetUserFunctionParameters)->float ; this function replaces the internal (constant) by a user-defined offset velocity; this function is used instead of offsetUserFunction, if velocityLevel (index2) time integrationshow
: if True, connector visualization is drawnaxesRadius
: radius of axes for connector graphical representationaxesLength
: length of axes for connector graphical representationcolor
: color of connector - output:[ObjectIndex, MarkerIndex, MarkerIndex]; returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [6,0,0],
initialAngularVelocity = [0,8,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.orange)])
oGround = mbs.AddObject(ObjectGround())
mbs.CreateGenericJoint(bodyNumbers=[oGround, b0], position=[5.5,0,0],
constrainedAxes=[1,1,1, 1,0,0],
rotationMatrixAxes=RotationMatrixX(0.125*pi), #tilt axes
useGlobalFrame=True, axesRadius=0.02, axesLength=0.2)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
bungeeJump.py (Ex), pistonEngine.py (Ex), universalJoint.py (Ex), bricardMechanism.py (TM), complexEigenvaluesTest.py (TM), computeODE2AEeigenvaluesTest.py (TM), driveTrainTest.py (TM), generalContactImplicit2.py (TM)
Function: CreateDistanceConstraint
CreateDistanceConstraint(name = ''
, bodyNumbers = [None, None]
, localPosition0 = [0.,0.,0.]
, localPosition1 = [0.,0.,0.]
, distance = None
, bodyOrNodeList = [None, None]
, bodyList = [None, None]
, show = True
, drawSize = -1.
, color = exudyn.graphics.color.default
)
- function description:Create distance joint between two bodies; definition of joint positions in local coordinates of bodies or nodes; if distance=None, it is computed automatically from reference length; all markers are automatically computed- NOTE that this function is added to MainSystem via Python function MainSystemCreateDistanceConstraint.
- input:
name
: name string for joint; markers get Marker0:name and Marker1:namebodyNumbers
: a list of two body numbers (ObjectIndex) to be constrainedlocalPosition0
: local position (as 3D list or numpy array) on body0, if not a node numberlocalPosition1
: local position (as 3D list or numpy array) on body1, if not a node numberdistance
: if None, distance is computed from reference position of bodies or nodes; if not None, this distance is prescribed between the two positions; if distance = 0, it will create a SphericalJoint as this case is not possible with a DistanceConstraintbodyOrNodeList
: alternative to bodyNumbers; a list of object numbers (with specific localPosition0/1) or node numbers; may alse be mixed types; to use this case, set bodyNumbers = [None,None]show
: if True, connector visualization is drawndrawSize
: general drawing size of nodecolor
: color of connector - output:[ObjectIndex, MarkerIndex, MarkerIndex]; returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [6,0,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.orange)])
m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0],
physicsMass=1, drawSize = 0.2)
n1 = mbs.GetObject(m1)['nodeNumber']
oGround = mbs.AddObject(ObjectGround())
mbs.CreateDistanceConstraint(bodyNumbers=[oGround, b0],
localPosition0 = [6.5,1,0],
localPosition1 = [0.5,0,0],
distance=None, #automatically computed
drawSize=0.06)
mbs.CreateDistanceConstraint(bodyOrNodeList=[b0, n1],
localPosition0 = [-0.5,0,0],
localPosition1 = [0.,0.,0.], #must be [0,0,0] for Node
distance=None, #automatically computed
drawSize=0.06)
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), mainSystemExtensionsTests.py (TM), taskmanagerTest.py (TM)
Function: CreateForce
CreateForce(name = ''
, bodyNumber = None
, loadVector = [0.,0.,0.]
, localPosition = [0.,0.,0.]
, bodyFixed = False
, loadVectorUserFunction = 0
, show = True
)
- function description:helper function to create force applied to given body- NOTE that this function is added to MainSystem via Python function MainSystemCreateForce.
- input:
name
: name string for objectbodyNumber
: body number (ObjectIndex) at which the force is applied toloadVector
: force vector (as 3D list or numpy array)localPosition
: local position (as 3D list or numpy array) where force is appliedbodyFixed
: if True, the force is corotated with the body; else, the force is globalloadVectorUserFunction
: A Python function f(mbs, t, load)->loadVector which defines the time-dependent load and replaces loadVector in every time step; the arg load is the static loadVectorshow
: if True, load is drawn - output:LoadIndex; returns load index
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0=mbs.CreateMassPoint(referencePosition = [0,0,0],
initialVelocity = [2,5,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=exu.graphics.color.blue)
f0=mbs.CreateForce(bodyNumber=b0, loadVector=[100,0,0],
localPosition=[0,0,0])
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
cartesianSpringDamper.py (Ex), cartesianSpringDamperUserFunction.py (Ex), chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), rigidBodyTutorial3.py (Ex), mainSystemExtensionsTests.py (TM), taskmanagerTest.py (TM)
Function: CreateTorque
CreateTorque(name = ''
, bodyNumber = None
, loadVector = [0.,0.,0.]
, localPosition = [0.,0.,0.]
, bodyFixed = False
, loadVectorUserFunction = 0
, show = True
)
- function description:helper function to create torque applied to given body- NOTE that this function is added to MainSystem via Python function MainSystemCreateTorque.
- input:
name
: name string for objectbodyNumber
: body number (ObjectIndex) at which the torque is applied toloadVector
: torque vector (as 3D list or numpy array)localPosition
: local position (as 3D list or numpy array) where torque is appliedbodyFixed
: if True, the torque is corotated with the body; else, the torque is globalloadVectorUserFunction
: A Python function f(mbs, t, load)->loadVector which defines the time-dependent load and replaces loadVector in every time step; the arg load is the static loadVectorshow
: if True, load is drawn - output:LoadIndex; returns load index
- example:
import exudyn as exu
from exudyn.utilities import * #includes itemInterface and rigidBodyUtilities
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [1,3,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=exu.graphics.color.red)])
f0=mbs.CreateTorque(bodyNumber=b0, loadVector=[0,100,0])
mbs.Assemble()
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
simulationSettings.timeIntegration.numberOfSteps = 1000
simulationSettings.timeIntegration.endTime = 2
mbs.SolveDynamic(simulationSettings = simulationSettings)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
chatGPTupdate.py (Ex), chatGPTupdate2.py (Ex), rigidBodyTutorial3.py (Ex), mainSystemExtensionsTests.py (TM)
MainSystem extensions (general)
This section represents general extensions to MainSystem, which are direct calls to Python functions, such as PlotSensor or SolveDynamic; these extensions allow a more intuitive interaction with the MainSystem class, see the following example. For activation, import exudyn.mainSystemExtensions
or exudyn.utilities
1#this example sketches the usage
2#for complete examples see Examples/ or TestModels/ folders
3#create some multibody system (mbs) first:
4# ...
5#
6#compute system degree of freedom:
7mbs.ComputeSystemDegreeOfFreedom(verbose=True)
8#
9#call solver function directly from mbs:
10mbs.SolveDynamic(exu.SimulationSettings())
11#
12#plot sensor directly from mbs:
13mbs.PlotSensor(...)
Function: SolutionViewer
SolutionViewer(solution = None
, rowIncrement = 1
, timeout = 0.04
, runOnStart = True
, runMode = 2
, fontSize = 12
, title = ''
, checkRenderEngineStopFlag = True
)
- function description:open interactive dialog and visulation (animate) solution loaded with LoadSolutionFile(…); Change slider ‘Increment’ to change the automatic increment of time frames; Change mode between continuous run, one cycle (fits perfect for animation recording) or ‘Static’ (to change Solution steps manually with the mouse); update period also lets you change the speed of animation; Press Run / Stop button to start/stop interactive mode (updating of grpahics)- NOTE that this function is added to MainSystem via Python function SolutionViewer.
- input:
solution
: solution dictionary previously loaded with exudyn.utilities.LoadSolutionFile(…); will be played from first to last row; if solution==None, it tries to load the file coordinatesSolutionFileName as stored in mbs.sys[‘simulationSettings’], which are the simulationSettings of the previous simulationrowIncrement
: can be set larger than 1 in order to skip solution frames: e.g. rowIncrement=10 visualizes every 10th row (frame)timeout
: in seconds is used between frames in order to limit the speed of animation; e.g. use timeout=0.04 to achieve approximately 25 frames per secondrunOnStart
: immediately go into ‘Run’ moderunMode
: 0=continuous run, 1=one cycle, 2=static (use slider/mouse to vary time steps)fontSize
: define font size for labels in InteractiveDialogtitle
: if empty, it uses default; otherwise define specific titlecheckRenderEngineStopFlag
: if True, stopping renderer (pressing Q or Escape) also causes stopping the interactive dialog - output:None; updates current visualization state, renders the scene continuously (after pressing button ‘Run’)
- example:
#HERE, mbs must contain same model as solution stored in coordinatesSolution.txt
#adjust autoFitScence, otherwise it may lead to unwanted fit to scene
SC.visualizationSettings.general.autoFitScene = False
from exudyn.interactive import SolutionViewer #import function
sol = LoadSolutionFile('coordinatesSolution.txt') #load solution: adjust to your file name
mbs.SolutionViewer(sol) #call via MainSystem
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
addPrismaticJoint.py (Ex), addRevoluteJoint.py (Ex), ANCFcableCantilevered.py (Ex), ANCFrotatingCable2D.py (Ex), basicTutorial2024.py (Ex), ACFtest.py (TM), ANCFbeltDrive.py (TM), ANCFgeneralContactCircle.py (TM)
Function: PlotSensor
PlotSensor(sensorNumbers = []
, components = 0
, xLabel = 'time (s)'
, yLabel = None
, labels = []
, colorCodeOffset = 0
, newFigure = True
, closeAll = False
, componentsX = []
, title = ''
, figureName = ''
, fontSize = 16
, colors = []
, lineStyles = []
, lineWidths = []
, markerStyles = []
, markerSizes = []
, markerDensity = 0.08
, rangeX = []
, rangeY = []
, majorTicksX = 10
, majorTicksY = 10
, offsets = []
, factors = []
, subPlot = []
, sizeInches = [6.4,4.8]
, fileName = ''
, useXYZcomponents = True
, **kwargs
)
- function description:Helper function for direct and easy visualization of sensor outputs, without need for loading text files, etc.; PlotSensor can be used to simply plot, e.g., the measured x-Position over time in a figure. PlotSensor provides an interface to matplotlib (which needs to be installed). Default values of many function arguments can be changed using the exudyn.plot function PlotSensorDefaults(), see there for usage.- NOTE that this function is added to MainSystem via Python function PlotSensor.
- input:
sensorNumbers
: consists of one or a list of sensor numbers (type SensorIndex or int) as returned by the mbs function AddSensor(…); sensors need to set writeToFile=True and/or storeInternal=True for PlotSensor to work; alternatively, it may contain FILENAMES (incl. path) to stored sensor or solution files OR a numpy array instead of sensor numbers; the format of data (file or numpy array) must contain per row the time and according solution values in columns; if components is a list and sensorNumbers is a scalar, sensorNumbers is adjusted automatically to the componentscomponents
: consists of one or a list of components according to the component of the sensor to be plotted at y-axis; if components is a list and sensorNumbers is a scalar, sensorNumbers is adjusted automatically to the components; as always, components are zero-based, meaning 0=X, 1=Y, etc.; for regular sensor files, time will be component=-1; to show the norm (e.g., of a force vector), use component=[plot.componentNorm] for according sensors; norm will consider all values of sensor except time (for 3D force, it will be \(\sqrt{f_0^2+f_1^2+f_2^2}\)); offsets and factors are mapped on norm (plot value=factor*(norm(values) + offset) ), not on component valuescomponentsX
: default componentsX=[] uses time in files; otherwise provide componentsX as list of components (or scalar) representing x components of sensors in plotted curves; DON’T forget to change xLabel accordingly!Using componentsX=[…] with a list of column indices specifies the respective columns used for the x-coordinates in all sensors; by default, values are plotted against the first column in the files, which is time; according to counting in PlotSensor, this represents componentX=-1;plotting y over x in a position sensor thus reads: components=[1], componentsX=[0];plotting time over x reads: components=[-1], componentsX=[0];the default value reads componentsX=[-1,-1,…]xLabel
: string for text at x-axisyLabel
: string for text at y-axis (default: None==> label is automatically computed from sensor value types)labels
: string (for one sensor) or list of strings (according to number of sensors resp. components) representing the labels used in legend; if labels=[], automatically generated legend is usedrangeX
: default rangeX=[]: computes range automatically; otherwise use rangeX to set range (limits) for x-axis provided as sorted list of two floats, e.g., rangeX=[0,4]rangeY
: default rangeY=[]: computes range automatically; otherwise use rangeY to set range (limits) for y-axis provided as sorted list of two floats, e.g., rangeY=[-1,1]figureName
: optional name for figure, if newFigure=TruefontSize
: change general fontsize of axis, labels, etc. (matplotlib default is 12, default in PlotSensor: 16)title
: optional string representing plot titleoffsets
: provide as scalar, list of scalars (per sensor) or list of 2D numpy.arrays (per sensor, having same rows/columns as sensor data; in this case it will also influence x-axis if componentsX is different from -1) to add offset to each sensor output; for an original value fOrig, the new value reads fNew = factor*(fOrig+offset); for offset provided as numpy array (with same time values), the ‘time’ column is ignored in the offset computation; can be used to compute difference of sensors; if offsets=[], no offset is usedfactors
: provide as scalar or list (per sensor) to add factor to each sensor output; for an original value fOrig, the new value reads fNew = factor*(fOrig+offset); if factor=[], no factor is usedmajorTicksX
: number of major ticks on x-axis; default: 10majorTicksY
: number of major ticks on y-axis; default: 10colorCodeOffset
: int offset for color code, color codes going from 0 to 27 (see PlotLineCode(…)); automatic line/color codes are used if no colors and lineStyles are usedcolors
: color is automatically selected from colorCodeOffset if colors=[]; otherwise chose from ‘b’, ‘g’, ‘r’, ‘c’, ‘m’, ‘y’, ‘k’ and many other colors see https://matplotlib.org/stable/gallery/color/named_colors.htmllineStyles
: line style is automatically selected from colorCodeOffset if lineStyles=[]; otherwise define for all lines with string or with list of strings, chosing from ‘-’, ‘–’, ‘-.’, ‘:’, or ‘’lineWidths
: float to define line width by float (default=1); either use single float for all sensors or list of floats with length >= number of sensorsmarkerStyles
: if different from [], marker styles are defined as list of marker style strings or single string for one sensor; chose from ‘.’, ‘o’, ‘x’, ‘+’ … check listMarkerStylesFilled and listMarkerStyles in exudyn.plot and see https://matplotlib.org/stable/api/markers_api.html ; ADD a space to markers to make them empty (transparent), e.g. ‘o ‘ will create an empty circlemarkerSizes
: float to define marker size by float (default=6); either use single float for all sensors or list of floats with length >= number of sensorsmarkerDensity
: if int, it defines approx. the total number of markers used along each graph; if float, this defines the distance of markers relative to the diagonal of the plot (default=0.08); if None, it adds a marker to every data point if marker style is specified for sensornewFigure
: if True, a new matplotlib.pyplot figure is created; otherwise, existing figures are overwrittensubPlot
: given as list [nx, ny, position] with nx, ny being the number of subplots in x and y direction (nx=cols, ny=rows), and position in [1,…, nx*ny] gives the position in the subplots; use the same structure for first PlotSensor (with newFigure=True) and all subsequent PlotSensor calls with newFigure=False, which creates the according subplots; default=[](no subplots)sizeInches
: given as list [sizeX, sizeY] with the sizes per (sub)plot given in inches; default: [6.4, 4.8]; in case of sub plots, the total size of the figure is computed from nx*sizeInches[0] and ny*sizeInches[1]fileName
: if this string is non-empty, figure will be saved to given path and filename (use figName.pdf to safe as PDF or figName.png to save as PNG image); use matplotlib.use(‘Agg’) in order not to open figures if you just want to save themuseXYZcomponents
: of True, it will use X, Y and Z for sensor components, e.g., measuring Position, Velocity, etc. wherever possiblecloseAll
: if True, close all figures before opening new one (do this only in first PlotSensor command!)[*kwargs]
:minorTicksXon
: if True, turn minor ticks for x-axis onminorTicksYon
: if True, turn minor ticks for y-axis onlogScaleX
: use log scale for x-axislogScaleY
: use log scale for y-axisfileCommentChar
: if exists, defines the comment character in files (#,fileDelimiterChar
: if exists, defines the character indicating the columns for data (‘,’, ‘ ‘, ‘;’, …) - output:[Any, Any, Any, Any]; plots the sensor data; returns [plt, fig, ax, line] in which plt is matplotlib.pyplot, fig is the figure (or None), ax is the axis (or None) and line is the return value of plt.plot (or None) which could be changed hereafter
- notes:adjust default values by modifying the variables exudyn.plot.plotSensorDefault…, e.g., exudyn.plot.plotSensorDefaultFontSize
- example:
#assume to have some position-based nodes 0 and 1:
s0=mbs.AddSensor(SensorNode(nodeNumber=0, fileName='s0.txt',
outputVariableType=exu.OutputVariableType.Position))
s1=mbs.AddSensor(SensorNode(nodeNumber=1, fileName='s1.txt',
outputVariableType=exu.OutputVariableType.Position))
mbs.PlotSensor(s0, 0) #plot x-coordinate
#plot x for s0 and z for s1:
mbs.PlotSensor(sensorNumbers=[s0,s1], components=[0,2], yLabel='this is the position in meter')
mbs.PlotSensor(sensorNumbers=s0, components=plot.componentNorm) #norm of position
mbs.PlotSensor(sensorNumbers=s0, components=[0,1,2], factors=1000., title='Answers to the big questions')
mbs.PlotSensor(sensorNumbers=s0, components=[0,1,2,3],
yLabel='Coordantes with offset 1\nand scaled with $\\frac{1}{1000}$',
factors=1e-3, offsets=1,fontSize=12, closeAll=True)
#assume to have body sensor sBody, marker sensor sMarker:
mbs.PlotSensor(sensorNumbers=[sBody]*3+[sMarker]*3, components=[0,1,2,0,1,2],
colorCodeOffset=3, newFigure=False, fontSize=10,
yLabel='Rotation $\\alpha, \\beta, \\gamma$ and\n Position $x,y,z$',
title='compare marker and body sensor')
#assume having file plotSensorNode.txt:
mbs.PlotSensor(sensorNumbers=[s0]*3+ [filedir+'plotSensorNode.txt']*3,
components=[0,1,2]*2)
#plot y over x:
mbs.PlotSensor(sensorNumbers=s0, componentsX=[0], components=[1], xLabel='x-Position', yLabel='y-Position')
#for further examples, see also Examples/plotSensorExamples.py
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFALEtest.py (Ex), beltDriveALE.py (Ex), beltDriveReevingSystem.py (Ex), beltDrivesComparison.py (Ex), bicycleIftommBenchmark.py (Ex), ACFtest.py (TM), ANCFbeltDrive.py (TM), ANCFgeneralContactCircle.py (TM)
Function: SolveStatic
SolveStatic(simulationSettings = exudyn.SimulationSettings()
, updateInitialValues = False
, storeSolver = True
, showHints = False
, showCausingItems = True
)
- function description:solves the static mbs problem using simulationSettings; check theDoc.pdf for MainSolverStatic for further details of the static solver; this function is also available in exudyn (using exudyn.SolveStatic(…))- NOTE that this function is added to MainSystem via Python function SolveStatic.
- input:
simulationSettings
: specific simulation settings out of exu.SimulationSettings(), as described in Section SolutionSettings; use options for newton, discontinuous settings, etc., from staticSolver sub-itemsupdateInitialValues
: if True, the results are written to initial values, such at a consecutive simulation uses the results of this simulation as the initial values of the next simulationstoreSolver
: if True, the staticSolver object is stored in the mbs.sys dictionary as mbs.sys[‘staticSolver’], and simulationSettings are stored as mbs.sys[‘simulationSettings’] - output:bool; returns True, if successful, False if fails; if storeSolver = True, mbs.sys contains staticSolver, which allows to investigate solver problems (check theDoc.pdf Section Solver substructures and the items described in Section MainSolverStatic)
- example:
import exudyn as exu
from exudyn.itemInterface import *
SC = exu.SystemContainer()
mbs = SC.AddSystem()
#create simple system:
ground = mbs.AddObject(ObjectGround())
mbs.AddNode(NodePoint())
body = mbs.AddObject(MassPoint(physicsMass=1, nodeNumber=0))
m0 = mbs.AddMarker(MarkerBodyPosition(bodyNumber=ground))
m1 = mbs.AddMarker(MarkerBodyPosition(bodyNumber=body))
mbs.AddObject(CartesianSpringDamper(markerNumbers=[m0,m1], stiffness=[100,100,100]))
mbs.AddLoad(LoadForceVector(markerNumber=m1, loadVector=[10,10,10]))
mbs.Assemble()
simulationSettings = exu.SimulationSettings()
simulationSettings.timeIntegration.endTime = 10
success = mbs.SolveStatic(simulationSettings, storeSolver = True)
print("success =", success)
print("iterations = ", mbs.sys['staticSolver'].it)
print("pos=", mbs.GetObjectOutputBody(body,localPosition=[0,0,0],
variableType=exu.OutputVariableType.Position))
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
3SpringsDistance.py (Ex), ALEANCFpipe.py (Ex), ANCFALEtest.py (Ex), ANCFcantileverTest.py (Ex), ANCFcontactCircle.py (Ex), ANCFBeamTest.py (TM), ANCFbeltDrive.py (TM), ANCFcontactCircleTest.py (TM)
Function: SolveDynamic
SolveDynamic(simulationSettings = exudyn.SimulationSettings()
, solverType = exudyn.DynamicSolverType.GeneralizedAlpha
, updateInitialValues = False
, storeSolver = True
, showHints = False
, showCausingItems = True
)
- function description:solves the dynamic mbs problem using simulationSettings and solver type; check theDoc.pdf for MainSolverImplicitSecondOrder for further details of the dynamic solver; this function is also available in exudyn (using exudyn.SolveDynamic(…))- NOTE that this function is added to MainSystem via Python function SolveDynamic.
- input:
simulationSettings
: specific simulation settings out of exu.SimulationSettings(), as described in Section SolutionSettings; use options for newton, discontinuous settings, etc., from timeIntegration; therein, implicit second order solvers use settings from generalizedAlpha and explict solvers from explicitIntegration; be careful with settings, as the influence accuracy (step size!), convergence and performance (see special Section Performance and ways to speed up computations)solverType
: use exudyn.DynamicSolverType to set specific solver (default=generalized alpha)updateInitialValues
: if True, the results are written to initial values, such at a consecutive simulation uses the results of this simulation as the initial values of the next simulationstoreSolver
: if True, the staticSolver object is stored in the mbs.sys dictionary as mbs.sys[‘staticSolver’], and simulationSettings are stored as mbs.sys[‘simulationSettings’]showHints
: show additional hints, if solver failsshowCausingItems
: if linear solver fails, this option helps to identify objects, etc. which are related to a singularity in the linearized system matrix - output:bool; returns True, if successful, False if fails; if storeSolver = True, mbs.sys contains staticSolver, which allows to investigate solver problems (check theDoc.pdf Section Solver substructures and the items described in Section MainSolverStatic)
- example:
import exudyn as exu
from exudyn.itemInterface import *
SC = exu.SystemContainer()
mbs = SC.AddSystem()
#create simple system:
ground = mbs.AddObject(ObjectGround())
mbs.AddNode(NodePoint())
body = mbs.AddObject(MassPoint(physicsMass=1, nodeNumber=0))
m0 = mbs.AddMarker(MarkerBodyPosition(bodyNumber=ground))
m1 = mbs.AddMarker(MarkerBodyPosition(bodyNumber=body))
mbs.AddObject(CartesianSpringDamper(markerNumbers=[m0,m1], stiffness=[100,100,100]))
mbs.AddLoad(LoadForceVector(markerNumber=m1, loadVector=[10,10,10]))
#
mbs.Assemble()
simulationSettings = exu.SimulationSettings()
simulationSettings.timeIntegration.endTime = 10
success = mbs.SolveDynamic(simulationSettings, storeSolver = True)
print("success =", success)
print("iterations = ", mbs.sys['dynamicSolver'].it)
print("pos=", mbs.GetObjectOutputBody(body,localPosition=[0,0,0],
variableType=exu.OutputVariableType.Position))
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
3SpringsDistance.py (Ex), addPrismaticJoint.py (Ex), addRevoluteJoint.py (Ex), ALEANCFpipe.py (Ex), ANCFALEtest.py (Ex), abaqusImportTest.py (TM), ACFtest.py (TM), ANCFBeamEigTest.py (TM)
Function: ComputeLinearizedSystem
ComputeLinearizedSystem(simulationSettings = exudyn.SimulationSettings()
, projectIntoConstraintNullspace = False
, singularValuesTolerance = 1e-12
, returnConstraintJacobian = False
, returnConstraintNullspace = False
)
- function description:compute linearized system of equations for ODE2 part of mbs, not considering the effects of algebraic constraints; for computation of eigenvalues and advanced computation with constrained systems, see ComputeODE2Eigenvalues; the current implementation is also able to project into the constrained space, however, this currently does not generally work with non-holonomic systems- NOTE that this function is added to MainSystem via Python function ComputeLinearizedSystem.
- input:
simulationSettings
: specific simulation settings used for computation of jacobian (e.g., sparse mode in static solver enables sparse computation)projectIntoConstraintNullspace
: if False, algebraic equations (and constraint jacobian) are not considered for the linearized system; if True, the equations are projected into the nullspace of the constraints in the current configuration, using singular value decomposition; in the latter case, the returned list contains [M, K, D, C, N] where C is the constraint jacobian and N is the nullspace matrix (C and N may be an empty list, depending on the following flags)singularValuesTolerance
: tolerance used to distinguish between zero and nonzero singular values for algebraic constraints projectionreturnConstraintJacobian
: if True, the returned list contains [M, K, D, C, N] where C is the constraint jacobian and N is the nullspace matrix (may be empty)returnConstraintNullspace
: if True, the returned list contains [M, K, D, C, N] where C is the constraint jacobian (may be empty) and N is the nullspace matrix - output:[ArrayLike, ArrayLike, ArrayLike]; [M, K, D]; list containing numpy mass matrix M, stiffness matrix K and damping matrix D; for constraints, see options with arguments above, return values may change to [M, K, D, C, N]
- notes:consider paper of Agundez, Vallejo, Freire, Mikkola, “The dependent coordinates in the linearization of constrained multibody systems: Handling and elimination”, https://www.sciencedirect.com/science/article/pii/S0020740324000791
- example:
import exudyn as exu
from exudyn.utilities import *
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
#
b0 = mbs.CreateMassPoint(referencePosition = [2,0,0],
initialVelocity = [2*0,5,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=graphics.color.blue)
#
oGround = mbs.AddObject(ObjectGround())
#add vertical spring
oSD = mbs.CreateSpringDamper(bodyOrNodeList=[oGround, b0],
localPosition0=[2,1,0],
localPosition1=[0,0,0],
stiffness=1e4, damping=1e2,
drawSize=0.2)
#
mbs.Assemble()
[M,K,D] = mbs.ComputeLinearizedSystem()
exu.Print('M=\n',M,'\nK=\n',K,'\nD=\n',D)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
ANCFBeamEigTest.py (TM), ANCFBeamTest.py (TM), geometricallyExactBeamTest.py (TM), mainSystemExtensionsTests.py (TM)
Function: ComputeODE2Eigenvalues
ComputeODE2Eigenvalues(simulationSettings = exudyn.SimulationSettings()
, useSparseSolver = False
, numberOfEigenvalues = 0
, constrainedCoordinates = []
, convert2Frequencies = False
, useAbsoluteValues = True
, computeComplexEigenvalues = False
, ignoreAlgebraicEquations = False
, singularValuesTolerance = 1e-12
)
- function description:compute eigenvalues for unconstrained ODE2 part of mbs, which represent the square of the eigenfrequencies (in radiant) of the undamped system; the computation may include constraints in case that ignoreAlgebraicEquations=False (however, this currently does not generally work with non-holonomic systems); for algebraic constraints, however, a dense singular value decomposition of the constraint jacobian is used for the nullspace projection; the computation is done for the initial values of the mbs, independently of previous computations. If you would like to use the current state for the eigenvalue computation, you need to copy the current state to the initial state (using GetSystemState, SetSystemState, see Section SystemData); note that mass and stiffness matrices are computed in dense mode so far, while eigenvalues are computed according to useSparseSolver.- NOTE that this function is added to MainSystem via Python function ComputeODE2Eigenvalues.
- input:
simulationSettings
: specific simulation settings used for computation of jacobian (e.g., sparse mode in static solver enables sparse computation)useSparseSolver
: if False (only for small systems), all eigenvalues are computed in dense mode (slow for large systems!); if True, only the numberOfEigenvalues are computed (numberOfEigenvalues must be set!); Currently, the matrices are exported only in DENSE MODE from mbs, which means that intermediate matrices may become huge for more than 5000 coordinates! NOTE that the sparsesolver accuracy is much less than the dense solvernumberOfEigenvalues
: number of eigenvalues and eivenvectors to be computed; if numberOfEigenvalues==0, all eigenvalues will be computed (may be impossible for larger or sparse problems!)constrainedCoordinates
: if this list is non-empty (and there are no algebraic equations or ignoreAlgebraicEquations=True), the integer indices represent constrained coordinates of the system, which are fixed during eigenvalue/vector computation; according rows/columns of mass and stiffness matrices are erased; in this case, algebraic equations of the system are ignoredconvert2Frequencies
: if True, the square root is computed for eigenvalues, they are converted into frequencies (Hz), and the output is [eigenFrequencies, eigenVectors]useAbsoluteValues
: if True, abs(eigenvalues) is used, which avoids problems for small (close to zero) eigenvalues; needed, when converting to frequenciescomputeComplexEigenvalues
: if True, the system is converted into a system of first order differential equations, including damping terms; returned eigenvalues are complex and contain the ‘damping’ (=real) part and the eigenfrequency (=complex) part; for this case, set useAbsoluteValues=False (otherwise you will not get the complex values; values are unsorted, however!); also, convert2Frequencies must be False in this case! only implemented for dense solverignoreAlgebraicEquations
: if True, algebraic equations (and constraint jacobian) are not considered for eigenvalue computation; otherwise, the solver tries to automatically project the system into the nullspace kernel of the constraint jacobian using a SVD; this gives eigenvalues of the constrained system; eigenvectors are not computedsingularValuesTolerance
: tolerance used to distinguish between zero and nonzero singular values for algebraic constraints projection - output:[ArrayLike, ArrayLike]; [eigenValues, eigenVectors]; eigenValues being a numpy array of eigen values (\(\omega_i^2\), being the squared eigen frequencies in (\(\omega_i\) in rad/s)!), eigenVectors a numpy array containing the eigenvectors in every column
- author:Johannes Gerstmayr, Michael Pieber
- example:
#take any example from the Examples or TestModels folder, e.g., 'cartesianSpringDamper.py' and run it
#specific example:
import exudyn as exu
from exudyn.utilities import *
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
#
b0 = mbs.CreateMassPoint(referencePosition = [2,0,0],
physicsMass = 1, gravity = [0,-9.81,0],
drawSize = 0.5, color=graphics.color.blue)
#
oGround = mbs.AddObject(ObjectGround())
#add vertical spring
oSD = mbs.CreateSpringDamper(bodyOrNodeList=[oGround, b0],
localPosition0=[2,1,0],
localPosition1=[0,0,0],
stiffness=1e4, damping=1e2,
drawSize=0.2)
#
mbs.Assemble()
#
[eigenvalues, eigenvectors] = mbs.ComputeODE2Eigenvalues()
#==>eigenvalues contain the eigenvalues of the ODE2 part of the system in the current configuration
#
#compute eigenfrequencies in Hz (analytical: 100/2/pi Hz for y-direction):
[eigenvaluesHz, ev] = mbs.ComputeODE2Eigenvalues(convert2Frequencies=True)
#
#compute complex eigenvalues:
[eigenvaluesComplex, ev] = mbs.ComputeODE2Eigenvalues(computeComplexEigenvalues=True,
useAbsoluteValues=False)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
nMassOscillator.py (Ex), nMassOscillatorEigenmodes.py (Ex), nMassOscillatorInteractive.py (Ex), ANCFBeamEigTest.py (TM), ANCFBeamTest.py (TM), bricardMechanism.py (TM), complexEigenvaluesTest.py (TM), computeODE2AEeigenvaluesTest.py (TM)
Function: ComputeSystemDegreeOfFreedom
ComputeSystemDegreeOfFreedom(simulationSettings = exudyn.SimulationSettings()
, threshold = 1e-12
, verbose = False
, useSVD = False
)
- function description:compute system DOF numerically, considering Grübler-Kutzbach formula as well as redundant constraints; uses numpy matrix rank or singular value decomposition of scipy (useSVD=True)- NOTE that this function is added to MainSystem via Python function ComputeSystemDegreeOfFreedom.
- input:
simulationSettings
: used e.g. for settings regarding numerical differentiation; default settings may be used in most casesthreshold
: threshold factor for singular values which estimate the redundant constraintsuseSVD
: use singular value decomposition directly, also showing SVD values if verbose=Trueverbose
: if True, it will show the singular values and one may decide if the threshold shall be adapted - output:dict; returns dictionary with key words ‘degreeOfFreedom’, ‘redundantConstraints’, ‘nODE2’, ‘nODE1’, ‘nAE’, ‘nPureAE’, where: degreeOfFreedom = the system degree of freedom computed numerically, redundantConstraints=the number of redundant constraints, nODE2=number of ODE2 coordinates, nODE1=number of ODE1 coordinates, nAE=total number of constraints, nPureAE=number of constraints on algebraic variables (e.g., lambda=0) that are not coupled to ODE2 coordinates
- notes:this approach could possibly fail with special constraints! Currently only works with dense matrices, thus it will be slow for larger systems
- example:
import exudyn as exu
from exudyn.utilities import *
import numpy as np
SC = exu.SystemContainer()
mbs = SC.AddSystem()
#
b0 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000,
sideLengths=[1,0.1,0.1]),
referencePosition = [6,0,0],
initialAngularVelocity = [0,8,0],
gravity = [0,-9.81,0],
graphicsDataList = [exu.graphics.Brick(size=[1,0.1,0.1],
color=graphics.color.orange)])
oGround = mbs.AddObject(ObjectGround())
mbs.CreateGenericJoint(bodyNumbers=[oGround, b0], position=[5.5,0,0],
constrainedAxes=[1,1,1, 1,0,0],
rotationMatrixAxes=RotationMatrixX(0.125*pi), #tilt axes
useGlobalFrame=True, axesRadius=0.02, axesLength=0.2)
#
mbs.Assemble()
dof = mbs.ComputeSystemDegreeOfFreedom(verbose=1)['degreeOfFreedom'] #print out details
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
fourBarMechanism3D.py (Ex), rigidBodyTutorial3.py (Ex), bricardMechanism.py (TM), mainSystemExtensionsTests.py (TM)
Function: CreateDistanceSensorGeometry
CreateDistanceSensorGeometry(meshPoints
, meshTrigs
, rigidBodyMarkerIndex
, searchTreeCellSize = [8,8,8]
)
- function description:Add geometry for distance sensor given by points and triangles (point indices) to mbs; use a rigid body marker where the geometry is put on;Creates a GeneralContact for efficient search on background. If you have several sets of points and trigs, first merge them or add them manually to the contact- NOTE that this function is added to MainSystem via Python function CreateDistanceSensorGeometry.
- input:
meshPoints
: list of points (3D), as returned by graphics.ToPointsAndTrigs()meshTrigs
: list of trigs (3 node indices each), as returned by graphics.ToPointsAndTrigs()rigidBodyMarkerIndex
: rigid body marker to which the triangles are fixed on (ground or moving object)searchTreeCellSize
: size of search tree (X,Y,Z); use larger values in directions where more triangles are located - output:int; returns ngc, which is the number of GeneralContact in mbs, to be used in CreateDistanceSensor(…); keep the gContact as deletion may corrupt data
- notes:should be used by CreateDistanceSensor(…) and AddLidar(…) for simple initialization of GeneralContact; old name: DistanceSensorSetupGeometry(…)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
Function: CreateDistanceSensor
CreateDistanceSensor(generalContactIndex
, positionOrMarker
, dirSensor
, minDistance = -1e7
, maxDistance = 1e7
, cylinderRadius = 0
, selectedTypeIndex = exudyn.ContactTypeIndex.IndexEndOfEnumList
, storeInternal = False
, fileName = ''
, measureVelocity = False
, addGraphicsObject = False
, drawDisplaced = True
, color = exudyn.graphics.color.red
)
- function description:Function to create distance sensor based on GeneralContact in mbs; sensor can be either placed on absolute position or attached to rigid body marker; in case of marker, dirSensor is relative to the marker- NOTE that this function is added to MainSystem via Python function CreateDistanceSensor.
- input:
generalContactIndex
: the number of the GeneralContact object in mbs; the index of the GeneralContact object which has been added with last AddGeneralContact(…) command is generalContactIndex=mbs.NumberOfGeneralContacts()-1positionOrMarker
: either a 3D position as list or np.array, or a MarkerIndex with according rigid body markerdirSensor
: the direction (no need to normalize) along which the distance is measured (must not be normalized); in case of marker, the direction is relative to marker orientation if marker contains orientation (BodyRigid, NodeRigid)minDistance
: the minimum distance which is accepted; smaller distance will be ignoredmaxDistance
: the maximum distance which is accepted; items being at maxDistance or futher are ignored; if no items are found, the function returns maxDistancecylinderRadius
: in case of spheres (selectedTypeIndex=ContactTypeIndex.IndexSpheresMarkerBased), a cylinder can be used which measures the shortest distance at a certain radius (geometrically interpreted as cylinder)selectedTypeIndex
: either this type has default value, meaning that all items in GeneralContact are measured, or there is a specific type index, which is the only type that is considered during measurementstoreInternal
: like with any SensorUserFunction, setting to True stores sensor data internallyfileName
: if defined, recorded data of SensorUserFunction is written to specified filemeasureVelocity
: if True, the sensor measures additionally the velocity (component 0=distance, component 1=velocity); velocity is the velocity in direction ‘dirSensor’ and does not account for changes in geometry, thus it may be different from the time derivative of the distance!addGraphicsObject
: if True, the distance sensor is also visualized graphically in a simplified manner with a red line having the length of dirSensor; NOTE that updates are ONLY performed during computation, not in visualization; for this reason, solutionSettings.sensorsWritePeriod should be accordingly smalldrawDisplaced
: if True, the red line is drawn backwards such that it moves along the measured surface; if False, the beam is fixed to marker or positioncolor
: optional color for ‘laser beam’ to be drawn - output:SensorIndex; creates sensor and returns according sensor number of SensorUserFunction
- notes:use generalContactIndex = CreateDistanceSensorGeometry(…) before to create GeneralContact module containing geometry; old name: AddDistanceSensor(…)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
distanceSensor.py (TM), laserScannerTest.py (TM)
Function: DrawSystemGraph
DrawSystemGraph(showLoads = True
, showSensors = True
, useItemNames = False
, useItemTypes = False
, addItemTypeNames = True
, multiLine = True
, fontSizeFactor = 1.
, layoutDistanceFactor = 3.
, layoutIterations = 100
, showLegend = True
, tightLayout = True
)
- function description:helper function which draws system graph of a MainSystem (mbs); several options let adjust the appearance of the graph; the graph visualization uses randomizer, which results in different graphs after every run!- NOTE that this function is added to MainSystem via Python function DrawSystemGraph.
- input:
showLoads
: toggle appearance of loads in mbsshowSensors
: toggle appearance of sensors in mbsuseItemNames
: if True, object names are shown instead of basic object types (Node, Load, …)useItemTypes
: if True, object type names (MassPoint, JointRevolute, …) are shown instead of basic object types (Node, Load, …); Note that Node, Object, is omitted at the beginning of itemName (as compared to theDoc.pdf); item classes become clear from the legendaddItemTypeNames
: if True, type nymes (Node, Load, etc.) are addedmultiLine
: if True, labels are multiline, improving readabilityfontSizeFactor
: use this factor to scale fonts, allowing to fit larger graphs on the screen with values < 1showLegend
: shows legend for different item typeslayoutDistanceFactor
: this factor influences the arrangement of labels; larger distance values lead to circle-like resultslayoutIterations
: more iterations lead to better arrangement of the layout, but need more time for larger systems (use 1000-10000 to get good results)tightLayout
: if True, uses matplotlib plt.tight_layout() which may raise warning - output:[Any, Any, Any]; returns [networkx, G, items] with nx being networkx, G the graph and item what is returned by nx.draw_networkx_labels(…)
Relevant Examples (Ex) and TestModels (TM) with weblink to github:
fourBarMechanism3D.py (Ex), rigidBodyTutorial3.py (Ex), rigidBodyTutorial3withMarkers.py (Ex), mainSystemExtensionsTests.py (TM)
MainSystem: Node
This section provides functions for adding, reading and modifying nodes. Nodes are used to define coordinates (unknowns to the static system and degrees of freedom if constraints are not present). Nodes can provide various types of coordinates for second/first order differential equations (ODE2/ODE1), algebraic equations (AE) and for data (history) variables – which are not providing unknowns in the nonlinear solver but will be solved in an additional nonlinear iteration for e.g. contact, friction or plasticity.
1import exudyn as exu #EXUDYN package including C++ core part
2from exudyn.itemInterface import * #conversion of data to exudyn dictionaries
3SC = exu.SystemContainer() #container of systems
4mbs = SC.AddSystem() #add a new system to work with
5nMP = mbs.AddNode(NodePoint2D(referenceCoordinates=[0,0]))
The class MainSystem has the following functions and structures regarding nodes:
- AddNode(pyObject):add a node with nodeDefinition from Python node class; returns (global) node index (type NodeIndex) of newly added node; use int(nodeIndex) to convert to int, if needed (but not recommended in order not to mix up index types of nodes, objects, markers, …)Example:
item = Rigid2D( referenceCoordinates= [1,0.5,0], initialVelocities= [10,0,0]) mbs.AddNode(item) nodeDict = {'nodeType': 'Point', 'referenceCoordinates': [1.0, 0.0, 0.0], 'initialCoordinates': [0.0, 2.0, 0.0], 'name': 'example node'} mbs.AddNode(nodeDict)
- GetNodeNumber(nodeName):get node’s number by name (string)Example:
n = mbs.GetNodeNumber('example node')
- GetNode(nodeNumber):get node’s dictionary by node number (type NodeIndex)Example:
nodeDict = mbs.GetNode(0)
- ModifyNode(nodeNumber, nodeDict):modify node’s dictionary by node number (type NodeIndex)Example:
mbs.ModifyNode(nodeNumber, nodeDict)
- GetNodeDefaults(typeName):get node’s default values for a certain nodeType as (dictionary)Example:
nodeType = 'Point' nodeDict = mbs.GetNodeDefaults(nodeType)
- GetNodeOutput(nodeNumber, variableType, configuration = exu.ConfigurationType.Current):get the ouput of the node specified with the OutputVariableType; output may be scalar or array (e.g. displacement vector)Example:
mbs.GetNodeOutput(nodeNumber=0, variableType=exu.OutputVariableType.Displacement)
- GetNodeODE2Index(nodeNumber):get index in the global ODE2 coordinate vector for the first node coordinate of the specified nodeExample:
mbs.GetNodeODE2Index(nodeNumber=0)
- GetNodeODE1Index(nodeNumber):get index in the global ODE1 coordinate vector for the first node coordinate of the specified nodeExample:
mbs.GetNodeODE1Index(nodeNumber=0)
- GetNodeAEIndex(nodeNumber):get index in the global AE coordinate vector for the first node coordinate of the specified nodeExample:
mbs.GetNodeAEIndex(nodeNumber=0)
- GetNodeParameter(nodeNumber, parameterName):get nodes’s parameter from node number (type NodeIndex) and parameterName; parameter names can be found for the specific items in the reference manual; for visualization parameters, use a ‘V’ as a prefixExample:
mbs.GetNodeParameter(0, 'referenceCoordinates')
- SetNodeParameter(nodeNumber, parameterName, value):set parameter ‘parameterName’ of node with node number (type NodeIndex) to value; parameter names can be found for the specific items in the reference manual; for visualization parameters, use a ‘V’ as a prefixExample:
mbs.SetNodeParameter(0, 'Vshow', True)
MainSystem: Object
This section provides functions for adding, reading and modifying objects, which can be bodies (mass point, rigid body, finite element, …), connectors (spring-damper or joint) or general objects. Objects provided terms to the residual of equations resulting from every coordinate given by the nodes. Single-noded objects (e.g.~mass point) provides exactly residual terms for its nodal coordinates. Connectors constrain or penalize two markers, which can be, e.g., position, rigid or coordinate markers. Thus, the dependence of objects is either on the coordinates of the marker-objects/nodes or on nodes which the objects possess themselves.
1import exudyn as exu #EXUDYN package including C++ core part
2from exudyn.itemInterface import * #conversion of data to exudyn dictionaries
3SC = exu.SystemContainer() #container of systems
4mbs = SC.AddSystem() #add a new system to work with
5nMP = mbs.AddNode(NodePoint2D(referenceCoordinates=[0,0]))
6mbs.AddObject(ObjectMassPoint2D(physicsMass=10, nodeNumber=nMP ))
The class MainSystem has the following functions and structures regarding objects:
- AddObject(pyObject):add an object with objectDefinition from Python object class; returns (global) object number (type ObjectIndex) of newly added objectExample:
item = MassPoint(name='heavy object', nodeNumber=0, physicsMass=100) mbs.AddObject(item) objectDict = {'objectType': 'MassPoint', 'physicsMass': 10, 'nodeNumber': 0, 'name': 'example object'} mbs.AddObject(objectDict)
- GetObjectNumber(objectName):get object’s number by name (string)Example:
n = mbs.GetObjectNumber('heavy object')
- GetObject(objectNumber, addGraphicsData = False):get object’s dictionary by object number (type ObjectIndex); NOTE: visualization parameters have a prefix ‘V’; in order to also get graphicsData written, use addGraphicsData=True (which is by default False, as it would spoil the information)Example:
objectDict = mbs.GetObject(0)
- ModifyObject(objectNumber, objectDict):modify object’s dictionary by object number (type ObjectIndex); NOTE: visualization parameters have a prefix ‘V’Example:
mbs.ModifyObject(objectNumber, objectDict)
- GetObjectDefaults(typeName):get object’s default values for a certain objectType as (dictionary)Example:
objectType = 'MassPoint' objectDict = mbs.GetObjectDefaults(objectType)
- GetObjectOutput(objectNumber, variableType, configuration = exu.ConfigurationType.Current):get object’s current output variable from object number (type ObjectIndex) and OutputVariableType; for connectors, it can only be computed for exu.ConfigurationType.Current configuration!
- GetObjectOutputBody(objectNumber, variableType, localPosition = [0,0,0], configuration = exu.ConfigurationType.Current):get body’s output variable from object number (type ObjectIndex) and OutputVariableType, using the localPosition as defined in the body, and as used in MarkerBody and SensorBodyExample:
u = mbs.GetObjectOutputBody(objectNumber = 1, variableType = exu.OutputVariableType.Position, localPosition=[1,0,0], configuration = exu.ConfigurationType.Initial)
- GetObjectOutputSuperElement(objectNumber, variableType, meshNodeNumber, configuration = exu.ConfigurationType.Current):get output variable from mesh node number of object with type SuperElement (GenericODE2, FFRF, FFRFreduced - CMS) with specific OutputVariableType; the meshNodeNumber is the object’s local node number, not the global node number!Example:
u = mbs.GetObjectOutputSuperElement(objectNumber = 1, variableType = exu.OutputVariableType.Position, meshNodeNumber = 12, configuration = exu.ConfigurationType.Initial)
- GetObjectParameter(objectNumber, parameterName):get objects’s parameter from object number (type ObjectIndex) and parameterName; parameter names can be found for the specific items in the reference manual; for visualization parameters, use a ‘V’ as a prefix; NOTE that BodyGraphicsData cannot be get or set, use dictionary access insteadExample:
mbs.GetObjectParameter(objectNumber = 0, parameterName = 'nodeNumber')
- SetObjectParameter(objectNumber, parameterName, value):set parameter ‘parameterName’ of object with object number (type ObjectIndex) to value;; parameter names can be found for the specific items in the reference manual; for visualization parameters, use a ‘V’ as a prefix; NOTE that BodyGraphicsData cannot be get or set, use dictionary access insteadExample:
mbs.SetObjectParameter(objectNumber = 0, parameterName = 'Vshow', value=True)
MainSystem: Marker
This section provides functions for adding, reading and modifying markers. Markers define how to measure primal kinematical quantities on objects or nodes (e.g., position, orientation or coordinates themselves), and how to act on the quantities which are dual to the kinematical quantities (e.g., force, torque and generalized forces). Markers provide unique interfaces for loads, sensors and constraints in order to address these quantities independently of the structure of the object or node (e.g., rigid or flexible body).
1import exudyn as exu #EXUDYN package including C++ core part
2from exudyn.itemInterface import * #conversion of data to exudyn dictionaries
3SC = exu.SystemContainer() #container of systems
4mbs = SC.AddSystem() #add a new system to work with
5nMP = mbs.AddNode(NodePoint2D(referenceCoordinates=[0,0]))
6mbs.AddObject(ObjectMassPoint2D(physicsMass=10, nodeNumber=nMP ))
7mMP = mbs.AddMarker(MarkerNodePosition(nodeNumber = nMP))
The class MainSystem has the following functions and structures regarding markers:
- AddMarker(pyObject):add a marker with markerDefinition from Python marker class; returns (global) marker number (type MarkerIndex) of newly added markerExample:
item = MarkerNodePosition(name='my marker',nodeNumber=1) mbs.AddMarker(item) markerDict = {'markerType': 'NodePosition', 'nodeNumber': 0, 'name': 'position0'} mbs.AddMarker(markerDict)
- GetMarkerNumber(markerName):get marker’s number by name (string)Example:
n = mbs.GetMarkerNumber('my marker')
- GetMarker(markerNumber):get marker’s dictionary by indexExample:
markerDict = mbs.GetMarker(0)
- ModifyMarker(markerNumber, markerDict):modify marker’s dictionary by indexExample:
mbs.ModifyMarker(markerNumber, markerDict)
- GetMarkerDefaults(typeName):get marker’s default values for a certain markerType as (dictionary)Example:
markerType = 'NodePosition' markerDict = mbs.GetMarkerDefaults(markerType)
- GetMarkerParameter(markerNumber, parameterName):get markers’s parameter from markerNumber and parameterName; parameter names can be found for the specific items in the reference manual
- SetMarkerParameter(markerNumber, parameterName, value):set parameter ‘parameterName’ of marker with markerNumber to value; parameter names can be found for the specific items in the reference manual
- GetMarkerOutput(markerNumber, variableType, configuration = exu.ConfigurationType.Current):get the ouput of the marker specified with the OutputVariableType; currently only provides Displacement, Position and Velocity for position based markers, and RotationMatrix, Rotation and AngularVelocity(Local) for markers providing orientation; Coordinates and Coordinates_t available for coordinate markersExample:
mbs.GetMarkerOutput(markerNumber=0, variableType=exu.OutputVariableType.Position)
MainSystem: Load
This section provides functions for adding, reading and modifying operating loads. Loads are used to act on the quantities which are dual to the primal kinematic quantities, such as displacement and rotation. Loads represent, e.g., forces, torques or generalized forces.
1import exudyn as exu #EXUDYN package including C++ core part
2from exudyn.itemInterface import * #conversion of data to exudyn dictionaries
3SC = exu.SystemContainer() #container of systems
4mbs = SC.AddSystem() #add a new system to work with
5nMP = mbs.AddNode(NodePoint2D(referenceCoordinates=[0,0]))
6mbs.AddObject(ObjectMassPoint2D(physicsMass=10, nodeNumber=nMP ))
7mMP = mbs.AddMarker(MarkerNodePosition(nodeNumber = nMP))
8mbs.AddLoad(Force(markerNumber = mMP, loadVector=[0.001,0,0]))
The class MainSystem has the following functions and structures regarding loads:
- AddLoad(pyObject):add a load with loadDefinition from Python load class; returns (global) load number (type LoadIndex) of newly added loadExample:
item = mbs.AddLoad(LoadForceVector(loadVector=[1,0,0], markerNumber=0, name='heavy load')) mbs.AddLoad(item) loadDict = {'loadType': 'ForceVector', 'markerNumber': 0, 'loadVector': [1.0, 0.0, 0.0], 'name': 'heavy load'} mbs.AddLoad(loadDict)
- GetLoadNumber(loadName):get load’s number by name (string)Example:
n = mbs.GetLoadNumber('heavy load')
- GetLoad(loadNumber):get load’s dictionary by indexExample:
loadDict = mbs.GetLoad(0)
- ModifyLoad(loadNumber, loadDict):modify load’s dictionary by indexExample:
mbs.ModifyLoad(loadNumber, loadDict)
- GetLoadDefaults(typeName):get load’s default values for a certain loadType as (dictionary)Example:
loadType = 'ForceVector' loadDict = mbs.GetLoadDefaults(loadType)
- GetLoadValues(loadNumber):Get current load values, specifically if user-defined loads are used; can be scalar or vector-valued return value
- GetLoadParameter(loadNumber, parameterName):get loads’s parameter from loadNumber and parameterName; parameter names can be found for the specific items in the reference manual
- SetLoadParameter(loadNumber, parameterName, value):set parameter ‘parameterName’ of load with loadNumber to value; parameter names can be found for the specific items in the reference manual
MainSystem: Sensor
This section provides functions for adding, reading and modifying operating sensors. Sensors are used to measure information in nodes, objects, markers, and loads for output in a file.
1import exudyn as exu #EXUDYN package including C++ core part
2from exudyn.itemInterface import * #conversion of data to exudyn dictionaries
3SC = exu.SystemContainer() #container of systems
4mbs = SC.AddSystem() #add a new system to work with
5nMP = mbs.AddNode(NodePoint(referenceCoordinates=[0,0,0]))
6mbs.AddObject(ObjectMassPoint(physicsMass=10, nodeNumber=nMP ))
7mMP = mbs.AddMarker(MarkerNodePosition(nodeNumber = nMP))
8mbs.AddLoad(Force(markerNumber = mMP, loadVector=[2,0,5]))
9sMP = mbs.AddSensor(SensorNode(nodeNumber=nMP, storeInternal=True,
10 outputVariableType=exu.OutputVariableType.Position))
11mbs.Assemble()
12exu.SolveDynamic(mbs, exu.SimulationSettings())
13from exudyn.plot import PlotSensor
14PlotSensor(mbs, sMP, components=[0,1,2])
The class MainSystem has the following functions and structures regarding sensors:
- AddSensor(pyObject):add a sensor with sensor definition from Python sensor class; returns (global) sensor number (type SensorIndex) of newly added sensorExample:
item = mbs.AddSensor(SensorNode(sensorType= exu.SensorType.Node, nodeNumber=0, name='test sensor')) mbs.AddSensor(item) sensorDict = {'sensorType': 'Node', 'nodeNumber': 0, 'fileName': 'sensor.txt', 'name': 'test sensor'} mbs.AddSensor(sensorDict)
- GetSensorNumber(sensorName):get sensor’s number by name (string)Example:
n = mbs.GetSensorNumber('test sensor')
- GetSensor(sensorNumber):get sensor’s dictionary by indexExample:
sensorDict = mbs.GetSensor(0)
- ModifySensor(sensorNumber, sensorDict):modify sensor’s dictionary by indexExample:
mbs.ModifySensor(sensorNumber, sensorDict)
- GetSensorDefaults(typeName):get sensor’s default values for a certain sensorType as (dictionary)Example:
sensorType = 'Node' sensorDict = mbs.GetSensorDefaults(sensorType)
- GetSensorValues(sensorNumber, configuration = exu.ConfigurationType.Current):get sensors’s values for configuration; can be a scalar or vector-valued return value!
- GetSensorStoredData(sensorNumber):get sensors’s internally stored data as matrix (all time points stored); rows are containing time and sensor values as obtained by sensor (e.g., time, and x, y, and z value of position)
- GetSensorParameter(sensorNumber, parameterName):get sensors’s parameter from sensorNumber and parameterName; parameter names can be found for the specific items in the reference manual
- SetSensorParameter(sensorNumber, parameterName, value):set parameter ‘parameterName’ of sensor with sensorNumber to value; parameter names can be found for the specific items in the reference manual