Skip to content

Commit

Permalink
commit for version 1.9; adapt MatrixContainer and FEM module to scipy…
Browse files Browse the repository at this point in the history
… csr_matrix; add verlet integrator; fix issues and bugs - see issues list in docu
  • Loading branch information
jgerstmayr committed Oct 9, 2024
1 parent b1bc20d commit 3dae8e8
Show file tree
Hide file tree
Showing 158 changed files with 2,702 additions and 1,657 deletions.
8 changes: 5 additions & 3 deletions README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -39,14 +39,14 @@ Exudyn

**A flexible multibody dynamics systems simulation code with Python and C++**

Exudyn version = 1.8.52.dev1 (Jones)
Exudyn version = 1.9.0 (Krall)

+ **University of Innsbruck**, Department of Mechatronics, Innsbruck, Austria

If you like using Exudyn, please add a *star* on github and follow us on
`Twitter @RExudyn <https://twitter.com/RExudyn>`_ !

+ **Update on Exudyn V1.8.52**: newer examples use ``exudyn.graphics`` instead of ``GraphicsData`` functions. The old models are backwards-compatible, but the updated examples and test models require version 1.8.52 or newer! Install with ``pip install exudyn --pre -U``
+ **Update on Exudyn V1.9.0**: newer examples use ``exudyn.graphics`` instead of ``GraphicsData`` functions. The old models are backwards-compatible, but the new updated examples and test models require version 1.8.52 or newer! FEM now uses internally in mass and stiffness matrices the scipy sparse csr matrices, check also your models for that!

+ **NOTE**: for pure installation, use **pip install exudyn** (see further description below)
+ *free, open source* and with plenty of *documentation* and *examples*
Expand All @@ -73,7 +73,9 @@ If you like using Exudyn, please add a *star* on github and follow us on

|pic1| |pic2| |pic3| |pic4| |pic5| |pic6|

Johannes Gerstmayr. Exudyn -- A C++ based Python package for flexible multibody systems. Multibody System Dynamics, 2023. `https://doi.org/10.1007/s11044-023-09937-1 <https://doi.org/10.1007/s11044-023-09937-1>`_
How to cite:

+ Johannes Gerstmayr. Exudyn -- A C++ based Python package for flexible multibody systems. Multibody System Dynamics, Vol. 60, pp. 533-561, 2024. `https://doi.org/10.1007/s11044-023-09937-1 <https://doi.org/10.1007/s11044-023-09937-1>`_

Due to limitations for complex formulas, images and references in .rst files, some (small) details are only available in theDoc.pdf, see the `github page of Exudyn <https://github.com/jgerstmayr/EXUDYN/blob/master/docs/theDoc/theDoc.pdf>`_! There may also be some conversion errors in the auto-generated html pages.

Expand Down
1 change: 1 addition & 0 deletions conf.py
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,7 @@ def ProcessTokens(self,text):
'tkappa': r'{\boldsymbol{\kappa}}',
'tkappaDot': r'{\boldsymbol{\dot \kappa}}',
'tphi': r'{\boldsymbol{\phi}}',
'boldVarPhi': r'{\boldsymbol{\varphi}}',
'tPhi': r'{\boldsymbol{\Phi}}',
'ttheta': r'{\boldsymbol{\theta}}',
'tTheta': r'{\boldsymbol{\Theta}}',
Expand Down
4 changes: 2 additions & 2 deletions docs/RST/Examples/ROSMobileManipulator.rst
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ You can view and download this file on Github: `ROSMobileManipulator.py <https:/
}
#################### Build mobile robot and add it to existing mbs
mobileRobotBackDic = mobile.mobileRobot2MBS(mbs, mobileRobot, markerGround)
mobileRobotBackDic = mobile.MobileRobot2MBS(mbs, mobileRobot, markerGround)
mbs.variables['mobileRobotBackDic'] = mobileRobotBackDic # to be able to use all variables in all functions (make it global useable)
# add mbs.variable for ROS sensor
mbs.variables['nodeNumber'] = mobileRobotBackDic['nPlatformList'][0] # just needed if nodeNumber is used for sensor information
Expand Down Expand Up @@ -461,7 +461,7 @@ You can view and download this file on Github: `ROSMobileManipulator.py <https:/
print('finished Statemachine. ')
# platform kinematics calculation
w = platformKinematics.getWheelVelocities(vel)
w = platformKinematics.GetWheelVelocities(vel)
if TArm != None:
lastTraj = mbs.variables['trajectory'][-1]
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/Examples/basicTutorial2024.rst
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ You can view and download this file on Github: `basicTutorial2024.py <https://gi
drawSize=0.2,
color=graphics.color.red)
oSD = mbs.CreateSpringDamper(bodyList=[oGround, oMass],
oSD = mbs.CreateSpringDamper(bodyNumbers=[oGround, oMass],
stiffness=500,
damping=10,
drawSize=0.1)
Expand Down
118 changes: 56 additions & 62 deletions docs/RST/Examples/bicycleIftommBenchmark.rst
Original file line number Diff line number Diff line change
Expand Up @@ -152,69 +152,70 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
VObjectGround(graphicsDataUserFunction=UFgraphics)))
#add rigid bodies
#rear wheel
[nR,bR]=AddRigidBody(mainSys = mbs,
inertia = inertiaR,
rotationMatrix = RotationMatrixZ(pi*0.5), #rotate 90° around z
nodeType = exu.NodeType.RotationEulerParameters,
position = P1,
velocity=[vX0,omegaX0*P1[2]*sZ,0],
# velocity=[0,0,0],
angularVelocity=[omegaX0,omegaRy0,0], #local rotation axis is now x
gravity = g,
graphicsDataList = [graphicsR])
resultR = mbs.CreateRigidBody(
referencePosition = P1,
referenceRotationMatrix = RotationMatrixZ(np.pi*0.5),
initialVelocity = [vX0, omegaX0*P1[2]*sZ, 0],
initialAngularVelocity = [omegaX0, omegaRy0, 0],
inertia = inertiaR,
gravity = g,
graphicsDataList = [graphicsR],
returnDict = True)
nR, bR = resultR['nodeNumber'], resultR['bodyNumber']
mbs.variables['nTrackNode'] = nR #node to be tracked
#front wheel
[nF,bF]=AddRigidBody(mainSys = mbs,
inertia = inertiaF,
rotationMatrix = RotationMatrixZ(pi*0.5),
nodeType = exu.NodeType.RotationEulerParameters,
position = P3,
velocity=[vX0,omegaX0*P3[2]*sZ,0],
# velocity=[0,0,0],
angularVelocity=[omegaX0 ,omegaFy0,0],
gravity = g,
graphicsDataList = [graphicsF])
resultF = mbs.CreateRigidBody(
referencePosition = P3,
referenceRotationMatrix = RotationMatrixZ(pi*0.5),
initialVelocity = [vX0, omegaX0*P3[2]*sZ, 0],
initialAngularVelocity = [omegaX0, omegaFy0, 0],
inertia = inertiaF,
gravity = g,
nodeType = exu.NodeType.RotationEulerParameters,
graphicsDataList = [graphicsF],
returnDict = True
)
nF, bF = resultF['nodeNumber'], resultF['bodyNumber']
#read body
[nB,bB]=AddRigidBody(mainSys = mbs,
inertia = inertiaB,
nodeType = exu.NodeType.RotationEulerParameters,
position = bCOM,
velocity=[vX0,omegaX0*bCOM[2]*sZ,0],
# velocity=[0,0,0],
angularVelocity=[omegaX0,0,0],
gravity = g,
graphicsDataList = [graphicsB,graphicsB2])
resultB = mbs.CreateRigidBody(
referencePosition = bCOM,
initialVelocity = [vX0, omegaX0*bCOM[2]*sZ, 0],
initialAngularVelocity = [omegaX0, 0, 0],
inertia = inertiaB,
gravity = g,
nodeType = exu.NodeType.RotationEulerParameters,
graphicsDataList = [graphicsB, graphicsB2],
returnDict = True
)
nB, bB = resultB['nodeNumber'], resultB['bodyNumber']
#handle
[nH,bH]=AddRigidBody(mainSys = mbs,
inertia = inertiaH,
nodeType = exu.NodeType.RotationEulerParameters,
position = hCOM,
velocity=[vX0,omegaX0*hCOM[2]*sZ,0],
# velocity=[0,0,0],
angularVelocity=[omegaX0,0,0],
gravity = g,
graphicsDataList = [graphicsH])
resultH = mbs.CreateRigidBody(
referencePosition = hCOM,
initialVelocity = [vX0, omegaX0*hCOM[2]*sZ, 0],
initialAngularVelocity = [omegaX0, 0, 0],
inertia = inertiaH,
gravity = g,
nodeType = exu.NodeType.RotationEulerParameters,
graphicsDataList = [graphicsH],
returnDict = True
)
nH, bH = resultH['nodeNumber'], resultH['bodyNumber']
#%%++++++++++++++++++++++++++++++++++++++++++++++++
#ground body and marker
gGround = graphics.CheckerBoard(point=[0,0,0], size=200, nTiles=64)
oGround = mbs.AddObject(ObjectGround(visualization=VObjectGround(graphicsData=[gGround])))
gGround = graphics.CheckerBoard(point=[0,0,0], size=50, nTiles=64)
oGround = mbs.CreateGround(graphicsDataList=[gGround])
markerGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=[0,0,0]))
markerR = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bR, localPosition=[0,0,0]))
markerF = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bF, localPosition=[0,0,0]))
markerB1 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P1-bCOM))
markerB2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P2-bCOM))
markerH3 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P3-hCOM))
markerH2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P2-hCOM))
sMarkerR = mbs.AddSensor(SensorMarker(markerNumber=markerR, outputVariableType=exu.OutputVariableType.Position))
sMarkerB1= mbs.AddSensor(SensorMarker(markerNumber=markerB1,outputVariableType=exu.OutputVariableType.Position))
Expand All @@ -223,21 +224,14 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
#add joints:
useJoints = True
if useJoints:
oJointRW = mbs.AddObject(GenericJoint(markerNumbers=[markerR, markerB1],
constrainedAxes=[1,1,1,1,0,1],
rotationMarker0=RotationMatrixZ(pi*0.5),
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
oJointFW = mbs.AddObject(GenericJoint(markerNumbers=[markerF, markerH3],
constrainedAxes=[1,1,1,1,0,1],
rotationMarker0=RotationMatrixZ(pi*0.5),
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
oJointSteer = mbs.AddObject(GenericJoint(markerNumbers=[markerB2, markerH2],
constrainedAxes=[1,1,1,1,1,0],
rotationMarker0=RotationMatrixY(-lam),
rotationMarker1=RotationMatrixY(-lam),
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=3*5*dY)))
oJointRW = mbs.CreateRevoluteJoint(bodyNumbers=[bR, bB], position=P1, axis=[0,1,0],
axisRadius=0.5*dY, axisLength=5*dY)
oJointFW = mbs.CreateRevoluteJoint(bodyNumbers=[bF, bH], position=P3, axis=[0,1,0],
axisRadius=0.5*dY, axisLength=5*dY)
oJointSteer = mbs.CreateRevoluteJoint(bodyNumbers=[bB, bH],
position=P2-bCOM, useGlobalFrame=False,
axis=RotationMatrixY(-lam) @ [0,0,1],
axisRadius=0.5*dY, axisLength=5*dY)[0]
#%%++++++++++++++++++++++++++++++++++++++++++++++++
#add 'rolling disc' for wheels:
cStiffness = 5e4*10 #spring stiffness: 50N==>F/k = u = 0.001m (penetration)
Expand Down Expand Up @@ -363,7 +357,7 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
print("pB1=",pB1)
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
tEnd = 5*4
tEnd = 5
h=0.001 #use small step size to detext contact switching
simulationSettings.timeIntegration.numberOfSteps = int(tEnd/h)
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/Examples/cartesianSpringDamper.rst
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ You can view and download this file on Github: `cartesianSpringDamper.py <https:
physicsMass=mass)
## create spring damper between objectGround and massPoint
mbs.CreateCartesianSpringDamper(bodyList=[objectGround, massPoint],
mbs.CreateCartesianSpringDamper(bodyNumbers=[objectGround, massPoint],
stiffness = [k,k,k],
damping = [d,0,0],
offset = [L,0,0])
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/Examples/cartesianSpringDamperUserFunction.rst
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ You can view and download this file on Github: `cartesianSpringDamperUserFunctio
physicsMass=mass)
## create spring damper between ground and mass point
csd = mbs.CreateCartesianSpringDamper(bodyList=[objectGround, massPoint],
csd = mbs.CreateCartesianSpringDamper(bodyNumbers=[objectGround, massPoint],
stiffness = [k,k,k],
damping = [d,0,0],
offset = [L,0,0])
Expand Down
30 changes: 14 additions & 16 deletions docs/RST/Examples/gyroStability.rst
Original file line number Diff line number Diff line change
Expand Up @@ -63,32 +63,30 @@ You can view and download this file on Github: `gyroStability.py <https://github
iCylSum = iCyl1.Translated([0,0.5*L,0]) + iCyl0
com = iCylSum.COM()
iCylSum = iCylSum.Translated(-com)
# print(iCyl0)
# print(iCyl1)
# print(iCylSum)
#graphics for body
color = [graphics.color.red, graphics.color.lawngreen, graphics.color.steelblue][i]
gCyl0 = graphics.SolidOfRevolution(pAxis=[0,0,0]-com, vAxis=[2*L,0,0],
contour = [[-L,-r],[L,-r],[L,-0.5*r],[-L,-0.5*r],],
color= graphics.color.steelblue, nTiles= 32, smoothContour=False)
gCyl1 = graphics.Cylinder(pAxis=[-L,0,0]-com, vAxis=[2*L,0,0],radius=0.5*w, color=graphics.color.steelblue, nTiles=32)
gCyl2 = graphics.Cylinder(pAxis=[0,0,0]-com, vAxis=[0,L,0],radius=0.5*w, color=graphics.color.steelblue, nTiles=32)
color= color, nTiles= 32, smoothContour=False)
gCyl1 = graphics.Cylinder(pAxis=[-L,0,0]-com, vAxis=[2*L,0,0],radius=0.5*w, color=color, nTiles=32)
gCyl2 = graphics.Cylinder(pAxis=[0,0,0]-com, vAxis=[0,L,0],radius=0.5*w, color=color, nTiles=32)
gCOM = graphics.Basis(origin=[0,0,0],length = 1.25*L)
nodeType = exu.NodeType.RotationRotationVector
if doImplicit:
nodeType = exu.NodeType.RotationEulerParameters
[n0,b0]=AddRigidBody(mainSys = mbs,
inertia = iCylSum, #includes COM
nodeType = nodeType,
position = p0,
rotationMatrix = np.diag([1,1,1]),
angularVelocity = omega0,
gravity = g,
graphicsDataList = [gCyl1, gCyl2, gCOM])
result0 = mbs.CreateRigidBody(
referencePosition = p0,
initialAngularVelocity = omega0,
inertia = iCylSum,
gravity = g,
nodeType = nodeType,
graphicsDataList = [gCyl1, gCyl2, gCOM],
returnDict = True
)
n0, b0 = result0['nodeNumber'], result0['bodyNumber']
sAngVel = mbs.AddSensor(SensorNode(nodeNumber=n0, fileName='solution/gyroAngVel'+str(i)+'.txt',
outputVariableType=exu.OutputVariableType.AngularVelocityLocal))
sAngle = mbs.AddSensor(SensorNode(nodeNumber=n0, fileName='solution/gyroAngle'+str(i)+'.txt',
Expand Down
28 changes: 9 additions & 19 deletions docs/RST/Examples/multiMbsTest.rst
Original file line number Diff line number Diff line change
Expand Up @@ -48,26 +48,16 @@ You can view and download this file on Github: `multiMbsTest.py <https://github.
axis0=[0,0,1], axis1=[0,0,0*1], radius=[0.05,0.05],
thickness = 0.1, width = [0.12,0.12], color=color0)
[n0,b0]=AddRigidBody(mainSys = mbs,
inertia = iCube0,
nodeType = str(exu.NodeType.RotationEulerParameters),
position = pMid0,
rotationMatrix = np.diag([1,1,1]),
angularVelocity = [0,0,0],
gravity = g,
graphicsDataList = [graphicsBody0])
b0 = mbs.CreateRigidBody(referencePosition = pMid0,
inertia = iCube0,
gravity = g,
graphicsDataList = [graphicsBody0])
#ground body and marker
oGround = mbs.AddObject(ObjectGround())
markerGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=p0))
#markers for rigid body:
markerBody0J0 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=b0, localPosition=[-0.5*bodyDim[0],0,0]))
#revolute joint (free z-axis)
mbs.AddObject(GenericJoint(markerNumbers=[markerGround, markerBody0J0],
constrainedAxes=[1,1,1,1,1,0],
visualization=VObjectJointGeneric(axesRadius=0.01, axesLength=0.1)))
oGround = mbs.CreateGround()
mbs.CreateRevoluteJoint(bodyNumbers=[oGround, b0],
position=p0, axis=[0,0,1],
axisRadius=0.01, axisLength=0.1)
mbs.Assemble()
def Simulate(SC, mbs):
Expand Down
16 changes: 10 additions & 6 deletions docs/RST/Examples/openAIgymNLinkContinuous.rst
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,7 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
masscart = 1.
massarm = 0.1
total_mass = massarm + masscart
armInertia = self.length**2*0.5*massarm
armInertia = self.length**2*0.5*massarm #for a rod with equally distributed mass, correctly, it would read self.length**2*massarm/3; using here the values of previous research
# environment variables and force magnitudes and are taken from the
# paper "Reliability evaluation of reinforcement learning methods for
Expand All @@ -145,9 +145,9 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
if self.nLinks == 3:
self.force_mag = self.force_mag*1.5
thresholdFactor = 2
if self.nLinks == 4:
self.force_mag = self.force_mag*3
thresholdFactor = 5
if self.nLinks >= 4:
self.force_mag = self.force_mag*2.5
thresholdFactor = 2.5
if self.flagContinuous:
self.force_mag *= 2 #continuous controller can have larger max value
Expand Down Expand Up @@ -331,6 +331,10 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
reward = 1 - 0.5 * abs(self.state[0])/self.x_threshold
for i in range(self.nLinks):
reward -= 0.5 * abs(self.state[i+1]) / (self.theta_threshold_radians*self.nLinks)
if self.nLinks > 2: #larger weight on last link!
reward -= 5. * 0.5 * abs(self.state[self.nTotalLinks-1]) / self.theta_threshold_radians
if reward < 0: reward = 0
return reward
Expand Down Expand Up @@ -506,9 +510,9 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
#only load and test
if False:
if flagContinuous and modelType == 'A2C':
model = SAC.load("solution/" + modelName)
else:
model = A2C.load("solution/" + modelName)
else:
model = SAC.load("solution/" + modelName)
env = InvertedNPendulumEnv(thresholdFactor=5) #larger threshold for testing
solutionFile='solution/learningCoordinates.txt'
Expand Down
Loading

0 comments on commit 3dae8e8

Please sign in to comment.