Skip to content

Commit 3dae8e8

Browse files
committed
commit for version 1.9; adapt MatrixContainer and FEM module to scipy csr_matrix; add verlet integrator; fix issues and bugs - see issues list in docu
1 parent b1bc20d commit 3dae8e8

File tree

158 files changed

+2702
-1657
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

158 files changed

+2702
-1657
lines changed

README.rst

+5-3
Original file line numberDiff line numberDiff line change
@@ -39,14 +39,14 @@ Exudyn
3939

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

42-
Exudyn version = 1.8.52.dev1 (Jones)
42+
Exudyn version = 1.9.0 (Krall)
4343

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

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

49-
+ **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``
49+
+ **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!
5050

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

7474
|pic1| |pic2| |pic3| |pic4| |pic5| |pic6|
7575

76-
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>`_
76+
How to cite:
77+
78+
+ 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>`_
7779

7880
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.
7981

conf.py

+1
Original file line numberDiff line numberDiff line change
@@ -186,6 +186,7 @@ def ProcessTokens(self,text):
186186
'tkappa': r'{\boldsymbol{\kappa}}',
187187
'tkappaDot': r'{\boldsymbol{\dot \kappa}}',
188188
'tphi': r'{\boldsymbol{\phi}}',
189+
'boldVarPhi': r'{\boldsymbol{\varphi}}',
189190
'tPhi': r'{\boldsymbol{\Phi}}',
190191
'ttheta': r'{\boldsymbol{\theta}}',
191192
'tTheta': r'{\boldsymbol{\Theta}}',

docs/RST/Examples/ROSMobileManipulator.rst

+2-2
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,7 @@ You can view and download this file on Github: `ROSMobileManipulator.py <https:/
203203
}
204204
205205
#################### Build mobile robot and add it to existing mbs
206-
mobileRobotBackDic = mobile.mobileRobot2MBS(mbs, mobileRobot, markerGround)
206+
mobileRobotBackDic = mobile.MobileRobot2MBS(mbs, mobileRobot, markerGround)
207207
mbs.variables['mobileRobotBackDic'] = mobileRobotBackDic # to be able to use all variables in all functions (make it global useable)
208208
# add mbs.variable for ROS sensor
209209
mbs.variables['nodeNumber'] = mobileRobotBackDic['nPlatformList'][0] # just needed if nodeNumber is used for sensor information
@@ -461,7 +461,7 @@ You can view and download this file on Github: `ROSMobileManipulator.py <https:/
461461
print('finished Statemachine. ')
462462
463463
# platform kinematics calculation
464-
w = platformKinematics.getWheelVelocities(vel)
464+
w = platformKinematics.GetWheelVelocities(vel)
465465
466466
if TArm != None:
467467
lastTraj = mbs.variables['trajectory'][-1]

docs/RST/Examples/basicTutorial2024.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@ You can view and download this file on Github: `basicTutorial2024.py <https://gi
3333
drawSize=0.2,
3434
color=graphics.color.red)
3535
36-
oSD = mbs.CreateSpringDamper(bodyList=[oGround, oMass],
36+
oSD = mbs.CreateSpringDamper(bodyNumbers=[oGround, oMass],
3737
stiffness=500,
3838
damping=10,
3939
drawSize=0.1)

docs/RST/Examples/bicycleIftommBenchmark.rst

+56-62
Original file line numberDiff line numberDiff line change
@@ -152,69 +152,70 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
152152
VObjectGround(graphicsDataUserFunction=UFgraphics)))
153153
#add rigid bodies
154154
#rear wheel
155-
[nR,bR]=AddRigidBody(mainSys = mbs,
156-
inertia = inertiaR,
157-
rotationMatrix = RotationMatrixZ(pi*0.5), #rotate 90° around z
158-
nodeType = exu.NodeType.RotationEulerParameters,
159-
position = P1,
160-
velocity=[vX0,omegaX0*P1[2]*sZ,0],
161-
# velocity=[0,0,0],
162-
angularVelocity=[omegaX0,omegaRy0,0], #local rotation axis is now x
163-
gravity = g,
164-
graphicsDataList = [graphicsR])
155+
resultR = mbs.CreateRigidBody(
156+
referencePosition = P1,
157+
referenceRotationMatrix = RotationMatrixZ(np.pi*0.5),
158+
initialVelocity = [vX0, omegaX0*P1[2]*sZ, 0],
159+
initialAngularVelocity = [omegaX0, omegaRy0, 0],
160+
inertia = inertiaR,
161+
gravity = g,
162+
graphicsDataList = [graphicsR],
163+
returnDict = True)
164+
165+
nR, bR = resultR['nodeNumber'], resultR['bodyNumber']
165166
166167
mbs.variables['nTrackNode'] = nR #node to be tracked
167168
168169
#front wheel
169-
[nF,bF]=AddRigidBody(mainSys = mbs,
170-
inertia = inertiaF,
171-
rotationMatrix = RotationMatrixZ(pi*0.5),
172-
nodeType = exu.NodeType.RotationEulerParameters,
173-
position = P3,
174-
velocity=[vX0,omegaX0*P3[2]*sZ,0],
175-
# velocity=[0,0,0],
176-
angularVelocity=[omegaX0 ,omegaFy0,0],
177-
gravity = g,
178-
graphicsDataList = [graphicsF])
170+
resultF = mbs.CreateRigidBody(
171+
referencePosition = P3,
172+
referenceRotationMatrix = RotationMatrixZ(pi*0.5),
173+
initialVelocity = [vX0, omegaX0*P3[2]*sZ, 0],
174+
initialAngularVelocity = [omegaX0, omegaFy0, 0],
175+
inertia = inertiaF,
176+
gravity = g,
177+
nodeType = exu.NodeType.RotationEulerParameters,
178+
graphicsDataList = [graphicsF],
179+
returnDict = True
180+
)
181+
nF, bF = resultF['nodeNumber'], resultF['bodyNumber']
179182
180183
#read body
181-
[nB,bB]=AddRigidBody(mainSys = mbs,
182-
inertia = inertiaB,
183-
nodeType = exu.NodeType.RotationEulerParameters,
184-
position = bCOM,
185-
velocity=[vX0,omegaX0*bCOM[2]*sZ,0],
186-
# velocity=[0,0,0],
187-
angularVelocity=[omegaX0,0,0],
188-
gravity = g,
189-
graphicsDataList = [graphicsB,graphicsB2])
184+
resultB = mbs.CreateRigidBody(
185+
referencePosition = bCOM,
186+
initialVelocity = [vX0, omegaX0*bCOM[2]*sZ, 0],
187+
initialAngularVelocity = [omegaX0, 0, 0],
188+
inertia = inertiaB,
189+
gravity = g,
190+
nodeType = exu.NodeType.RotationEulerParameters,
191+
graphicsDataList = [graphicsB, graphicsB2],
192+
returnDict = True
193+
)
194+
nB, bB = resultB['nodeNumber'], resultB['bodyNumber']
190195
191196
#handle
192-
[nH,bH]=AddRigidBody(mainSys = mbs,
193-
inertia = inertiaH,
194-
nodeType = exu.NodeType.RotationEulerParameters,
195-
position = hCOM,
196-
velocity=[vX0,omegaX0*hCOM[2]*sZ,0],
197-
# velocity=[0,0,0],
198-
angularVelocity=[omegaX0,0,0],
199-
gravity = g,
200-
graphicsDataList = [graphicsH])
197+
resultH = mbs.CreateRigidBody(
198+
referencePosition = hCOM,
199+
initialVelocity = [vX0, omegaX0*hCOM[2]*sZ, 0],
200+
initialAngularVelocity = [omegaX0, 0, 0],
201+
inertia = inertiaH,
202+
gravity = g,
203+
nodeType = exu.NodeType.RotationEulerParameters,
204+
graphicsDataList = [graphicsH],
205+
returnDict = True
206+
)
207+
nH, bH = resultH['nodeNumber'], resultH['bodyNumber']
201208
202209
203210
#%%++++++++++++++++++++++++++++++++++++++++++++++++
204211
#ground body and marker
205-
gGround = graphics.CheckerBoard(point=[0,0,0], size=200, nTiles=64)
206-
oGround = mbs.AddObject(ObjectGround(visualization=VObjectGround(graphicsData=[gGround])))
212+
gGround = graphics.CheckerBoard(point=[0,0,0], size=50, nTiles=64)
213+
oGround = mbs.CreateGround(graphicsDataList=[gGround])
207214
markerGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=[0,0,0]))
208215
209216
markerR = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bR, localPosition=[0,0,0]))
210217
markerF = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bF, localPosition=[0,0,0]))
211-
212218
markerB1 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P1-bCOM))
213-
markerB2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P2-bCOM))
214-
215-
markerH3 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P3-hCOM))
216-
markerH2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P2-hCOM))
217-
218219
219220
sMarkerR = mbs.AddSensor(SensorMarker(markerNumber=markerR, outputVariableType=exu.OutputVariableType.Position))
220221
sMarkerB1= mbs.AddSensor(SensorMarker(markerNumber=markerB1,outputVariableType=exu.OutputVariableType.Position))
@@ -223,21 +224,14 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
223224
#add joints:
224225
useJoints = True
225226
if useJoints:
226-
oJointRW = mbs.AddObject(GenericJoint(markerNumbers=[markerR, markerB1],
227-
constrainedAxes=[1,1,1,1,0,1],
228-
rotationMarker0=RotationMatrixZ(pi*0.5),
229-
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
230-
231-
oJointFW = mbs.AddObject(GenericJoint(markerNumbers=[markerF, markerH3],
232-
constrainedAxes=[1,1,1,1,0,1],
233-
rotationMarker0=RotationMatrixZ(pi*0.5),
234-
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
235-
236-
oJointSteer = mbs.AddObject(GenericJoint(markerNumbers=[markerB2, markerH2],
237-
constrainedAxes=[1,1,1,1,1,0],
238-
rotationMarker0=RotationMatrixY(-lam),
239-
rotationMarker1=RotationMatrixY(-lam),
240-
visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=3*5*dY)))
227+
oJointRW = mbs.CreateRevoluteJoint(bodyNumbers=[bR, bB], position=P1, axis=[0,1,0],
228+
axisRadius=0.5*dY, axisLength=5*dY)
229+
oJointFW = mbs.CreateRevoluteJoint(bodyNumbers=[bF, bH], position=P3, axis=[0,1,0],
230+
axisRadius=0.5*dY, axisLength=5*dY)
231+
oJointSteer = mbs.CreateRevoluteJoint(bodyNumbers=[bB, bH],
232+
position=P2-bCOM, useGlobalFrame=False,
233+
axis=RotationMatrixY(-lam) @ [0,0,1],
234+
axisRadius=0.5*dY, axisLength=5*dY)[0]
241235
#%%++++++++++++++++++++++++++++++++++++++++++++++++
242236
#add 'rolling disc' for wheels:
243237
cStiffness = 5e4*10 #spring stiffness: 50N==>F/k = u = 0.001m (penetration)
@@ -363,7 +357,7 @@ You can view and download this file on Github: `bicycleIftommBenchmark.py <https
363357
print("pB1=",pB1)
364358
simulationSettings = exu.SimulationSettings() #takes currently set values or default values
365359
366-
tEnd = 5*4
360+
tEnd = 5
367361
h=0.001 #use small step size to detext contact switching
368362
369363
simulationSettings.timeIntegration.numberOfSteps = int(tEnd/h)

docs/RST/Examples/cartesianSpringDamper.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ You can view and download this file on Github: `cartesianSpringDamper.py <https:
5858
physicsMass=mass)
5959
6060
## create spring damper between objectGround and massPoint
61-
mbs.CreateCartesianSpringDamper(bodyList=[objectGround, massPoint],
61+
mbs.CreateCartesianSpringDamper(bodyNumbers=[objectGround, massPoint],
6262
stiffness = [k,k,k],
6363
damping = [d,0,0],
6464
offset = [L,0,0])

docs/RST/Examples/cartesianSpringDamperUserFunction.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,7 @@ You can view and download this file on Github: `cartesianSpringDamperUserFunctio
5858
physicsMass=mass)
5959
6060
## create spring damper between ground and mass point
61-
csd = mbs.CreateCartesianSpringDamper(bodyList=[objectGround, massPoint],
61+
csd = mbs.CreateCartesianSpringDamper(bodyNumbers=[objectGround, massPoint],
6262
stiffness = [k,k,k],
6363
damping = [d,0,0],
6464
offset = [L,0,0])

docs/RST/Examples/gyroStability.rst

+14-16
Original file line numberDiff line numberDiff line change
@@ -63,32 +63,30 @@ You can view and download this file on Github: `gyroStability.py <https://github
6363
iCylSum = iCyl1.Translated([0,0.5*L,0]) + iCyl0
6464
com = iCylSum.COM()
6565
iCylSum = iCylSum.Translated(-com)
66-
67-
# print(iCyl0)
68-
# print(iCyl1)
69-
# print(iCylSum)
7066
7167
#graphics for body
68+
color = [graphics.color.red, graphics.color.lawngreen, graphics.color.steelblue][i]
7269
gCyl0 = graphics.SolidOfRevolution(pAxis=[0,0,0]-com, vAxis=[2*L,0,0],
7370
contour = [[-L,-r],[L,-r],[L,-0.5*r],[-L,-0.5*r],],
74-
color= graphics.color.steelblue, nTiles= 32, smoothContour=False)
75-
gCyl1 = graphics.Cylinder(pAxis=[-L,0,0]-com, vAxis=[2*L,0,0],radius=0.5*w, color=graphics.color.steelblue, nTiles=32)
76-
gCyl2 = graphics.Cylinder(pAxis=[0,0,0]-com, vAxis=[0,L,0],radius=0.5*w, color=graphics.color.steelblue, nTiles=32)
71+
color= color, nTiles= 32, smoothContour=False)
72+
gCyl1 = graphics.Cylinder(pAxis=[-L,0,0]-com, vAxis=[2*L,0,0],radius=0.5*w, color=color, nTiles=32)
73+
gCyl2 = graphics.Cylinder(pAxis=[0,0,0]-com, vAxis=[0,L,0],radius=0.5*w, color=color, nTiles=32)
7774
gCOM = graphics.Basis(origin=[0,0,0],length = 1.25*L)
7875
7976
nodeType = exu.NodeType.RotationRotationVector
8077
if doImplicit:
8178
nodeType = exu.NodeType.RotationEulerParameters
8279
83-
[n0,b0]=AddRigidBody(mainSys = mbs,
84-
inertia = iCylSum, #includes COM
85-
nodeType = nodeType,
86-
position = p0,
87-
rotationMatrix = np.diag([1,1,1]),
88-
angularVelocity = omega0,
89-
gravity = g,
90-
graphicsDataList = [gCyl1, gCyl2, gCOM])
91-
80+
result0 = mbs.CreateRigidBody(
81+
referencePosition = p0,
82+
initialAngularVelocity = omega0,
83+
inertia = iCylSum,
84+
gravity = g,
85+
nodeType = nodeType,
86+
graphicsDataList = [gCyl1, gCyl2, gCOM],
87+
returnDict = True
88+
)
89+
n0, b0 = result0['nodeNumber'], result0['bodyNumber']
9290
sAngVel = mbs.AddSensor(SensorNode(nodeNumber=n0, fileName='solution/gyroAngVel'+str(i)+'.txt',
9391
outputVariableType=exu.OutputVariableType.AngularVelocityLocal))
9492
sAngle = mbs.AddSensor(SensorNode(nodeNumber=n0, fileName='solution/gyroAngle'+str(i)+'.txt',

docs/RST/Examples/multiMbsTest.rst

+9-19
Original file line numberDiff line numberDiff line change
@@ -48,26 +48,16 @@ You can view and download this file on Github: `multiMbsTest.py <https://github.
4848
axis0=[0,0,1], axis1=[0,0,0*1], radius=[0.05,0.05],
4949
thickness = 0.1, width = [0.12,0.12], color=color0)
5050
51-
[n0,b0]=AddRigidBody(mainSys = mbs,
52-
inertia = iCube0,
53-
nodeType = str(exu.NodeType.RotationEulerParameters),
54-
position = pMid0,
55-
rotationMatrix = np.diag([1,1,1]),
56-
angularVelocity = [0,0,0],
57-
gravity = g,
58-
graphicsDataList = [graphicsBody0])
59-
51+
b0 = mbs.CreateRigidBody(referencePosition = pMid0,
52+
inertia = iCube0,
53+
gravity = g,
54+
graphicsDataList = [graphicsBody0])
55+
6056
#ground body and marker
61-
oGround = mbs.AddObject(ObjectGround())
62-
markerGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=p0))
63-
64-
#markers for rigid body:
65-
markerBody0J0 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=b0, localPosition=[-0.5*bodyDim[0],0,0]))
66-
67-
#revolute joint (free z-axis)
68-
mbs.AddObject(GenericJoint(markerNumbers=[markerGround, markerBody0J0],
69-
constrainedAxes=[1,1,1,1,1,0],
70-
visualization=VObjectJointGeneric(axesRadius=0.01, axesLength=0.1)))
57+
oGround = mbs.CreateGround()
58+
mbs.CreateRevoluteJoint(bodyNumbers=[oGround, b0],
59+
position=p0, axis=[0,0,1],
60+
axisRadius=0.01, axisLength=0.1)
7161
mbs.Assemble()
7262
7363
def Simulate(SC, mbs):

docs/RST/Examples/openAIgymNLinkContinuous.rst

+10-6
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,7 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
133133
masscart = 1.
134134
massarm = 0.1
135135
total_mass = massarm + masscart
136-
armInertia = self.length**2*0.5*massarm
136+
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
137137
138138
# environment variables and force magnitudes and are taken from the
139139
# paper "Reliability evaluation of reinforcement learning methods for
@@ -145,9 +145,9 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
145145
if self.nLinks == 3:
146146
self.force_mag = self.force_mag*1.5
147147
thresholdFactor = 2
148-
if self.nLinks == 4:
149-
self.force_mag = self.force_mag*3
150-
thresholdFactor = 5
148+
if self.nLinks >= 4:
149+
self.force_mag = self.force_mag*2.5
150+
thresholdFactor = 2.5
151151
152152
if self.flagContinuous:
153153
self.force_mag *= 2 #continuous controller can have larger max value
@@ -331,6 +331,10 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
331331
reward = 1 - 0.5 * abs(self.state[0])/self.x_threshold
332332
for i in range(self.nLinks):
333333
reward -= 0.5 * abs(self.state[i+1]) / (self.theta_threshold_radians*self.nLinks)
334+
335+
if self.nLinks > 2: #larger weight on last link!
336+
reward -= 5. * 0.5 * abs(self.state[self.nTotalLinks-1]) / self.theta_threshold_radians
337+
334338
if reward < 0: reward = 0
335339
336340
return reward
@@ -506,9 +510,9 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
506510
#only load and test
507511
if False:
508512
if flagContinuous and modelType == 'A2C':
509-
model = SAC.load("solution/" + modelName)
510-
else:
511513
model = A2C.load("solution/" + modelName)
514+
else:
515+
model = SAC.load("solution/" + modelName)
512516
513517
env = InvertedNPendulumEnv(thresholdFactor=5) #larger threshold for testing
514518
solutionFile='solution/learningCoordinates.txt'

0 commit comments

Comments
 (0)