bicycleIftommBenchmark.py

You can view and download this file on Github: bicycleIftommBenchmark.py

  1#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
  2# This is an EXUDYN example
  3#
  4# Details:  bicycle Iftomm benchmark example
  5#           https://www.iftomm-multibody.org/benchmark/problem/Uncontrolled_bicycle/
  6#
  7# Author:   Johannes Gerstmayr
  8# Date:     2021-06-22
  9#
 10# Copyright:This file is part of Exudyn. Exudyn is free software. You can redistribute it and/or modify it under the terms of the Exudyn license. See 'LICENSE.txt' for more details.
 11#
 12#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
 13
 14
 15import exudyn as exu
 16from exudyn.itemInterface import *
 17from exudyn.utilities import *
 18from exudyn.graphicsDataUtilities import *
 19
 20from math import sin, cos, pi
 21import numpy as np
 22
 23SC = exu.SystemContainer()
 24mbs = SC.AddSystem()
 25
 26
 27#%%++++++++++++++++++++++++++++++++++++++++++++++++
 28#coordinate system according to IFToMM:
 29#note: here, wheels are rotated as local wheel axis=x, z points upwards in EXUDYN model
 30#                            ox P2
 31#                        oooo  o
 32#                    oooo       o
 33#      +++       oooo            o +++
 34#     +   +   ooo                 o   +
 35#    +   oooo                    + o   +
 36#    +  xP1+                     +  xP3+
 37#    +     +                     +     +
 38#     +   +                       +   +
 39#      +++                         +++
 40#       x---------------------------x----------------------> x
 41#       |         <- w ->
 42#       v  z
 43
 44
 45#parameters
 46sZ = -1         #switch z coordinate compared to IFToMM description
 47w = 1.02        #wheel base (distance of wheel centers)
 48c = 0.08        #trail
 49lam = pi/10     #steer axis tilt (rad)
 50g = [0,0,9.81*sZ]     #gravity in m/s^2
 51
 52#rear wheel R:
 53rR = 0.3            #rear wheel radius
 54mR = 2              #rear wheel mass
 55IRxx = 0.0603       #rear wheel inertia xx = zz ; but in EXUDYN, x=rotation axis!
 56IRyy = 0.12         #rear wheel inertia yy (around wheel axis)
 57inertiaR = RigidBodyInertia(mass=mR, inertiaTensor=np.array([[IRyy,0,0],[0,IRxx,0],[0,0,IRxx]]))
 58
 59#front wheel F:
 60rF = 0.35           #rear wheel radius
 61mF = 3              #rear wheel mass
 62IFxx = 0.1405       #rear wheel inertia xx = zz ; but in EXUDYN, x=rotation axis!
 63IFyy = 0.28         #rear wheel inertia yy (around wheel axis)
 64inertiaF = RigidBodyInertia(mass=mF, inertiaTensor=np.array([[IFyy,0,0],[0,IFxx,0],[0,0,IFxx]]))
 65
 66#rear body B:
 67xB = 0.3            #COM x
 68zB = -0.9*sZ        #COM z
 69bCOM = np.array([xB, 0, zB])
 70mB = 85             #rear body (and driver) mass
 71zz=-1
 72inertiaB = RigidBodyInertia(mass=mB,
 73                            inertiaTensor=np.array([[9.2,0,2.4*zz],[0,11,0],[2.4*zz,0,2.8]]),
 74                            # inertiaTensor=np.diag([1,1,1]),
 75                            com=np.zeros(3)) #reference position = COM for this body
 76                            # com=bCOM)
 77
 78#front Handlebar H:
 79xH = 0.9            #COM x
 80zH = -0.7*sZ        #COM z
 81hCOM = np.array([xH, 0, zH])
 82mH = 4              #handle bar mass
 83inertiaH = RigidBodyInertia(mass=mH,
 84                            inertiaTensor=np.array([[0.05892, 0, -0.00756*zz],[0,0.06,0],[-0.00756*zz, 0, 0.00708]]),
 85                            # inertiaTensor=np.diag([1,1,1]),
 86                            com=np.zeros(3)) #reference position = COM for this body
 87                            # com=hCOM)
 88
 89#geometrical parameters for joints
 90P1 = np.array([0,0,-0.3*sZ])
 91P2 = np.array([0.82188470506, 0, -0.85595086466*sZ])
 92P3 = np.array([w, 0, -0.35*sZ])
 93
 94
 95#stable velocity limits according to linear theory:
 96vMin = 4.29238253634111
 97vMax = 6.02426201538837
 98
 99maneuver = 'M1'
100if maneuver == 'M1':
101    vX0 = 4.                #initial forward velocity in x-direction
102    omegaX0 = 0.05          #initial roll velocity around x axis
103elif maneuver == 'M2':
104    vX0 = 4.6               #initial forward velocity in x-direction
105    omegaX0 = 0.5           #initial roll velocity around x axis
106elif maneuver == 'M3':
107    vX0 = 8                 #initial forward velocity in x-direction
108    omegaX0 = 0.05          #initial roll velocity around x axis
109
110omegaRy0 = -vX0/rR*sZ   #initial angular velocity of rear wheel
111omegaFy0 = -vX0/rF*sZ   #initial angular velocity of front wheel
112
113#%%++++++++++++++++++++++++++++++++++++++++++++++++
114#visualization:
115dY = 0.02
116#graphicsFrame = GraphicsDataOrthoCubePoint(centerPoint=[0,0,0],size=[dFoot*1.1,0.7*rFoot,0.7*rFoot], color=color4lightred)
117graphicsR = GraphicsDataCylinder(pAxis=[-1*dY,0,0], vAxis=[dY*2,0,0], radius=rR, color=color4steelblue, nTiles=4)
118graphicsF = GraphicsDataCylinder(pAxis=[-1*dY,0,0], vAxis=[dY*2,0,0], radius=rF, color=color4steelblue, nTiles=4)
119graphicsB = GraphicsDataCylinder(pAxis=P1-bCOM, vAxis=P2-P1, radius=dY*1.5, color=color4lightred)
120graphicsB2 = GraphicsDataSphere(point=[0,0,0], radius=3*dY, color=color4lightgrey)
121graphicsH = GraphicsDataCylinder(pAxis=P3-hCOM, vAxis=P2-P3, radius=dY*1.3, color=color4lightgreen)
122
123#option to track motion of bicycle
124if True:
125    #add user function to track bicycle frame
126    def UFgraphics(mbs, objectNum):
127        n = mbs.variables['nTrackNode']
128        p = mbs.GetNodeOutput(n,exu.OutputVariableType.Position,
129                              configuration=exu.ConfigurationType.Visualization)
130        rs=SC.GetRenderState()
131        A = np.array(rs['modelRotation'])
132        p = A.T @ p
133        rs['centerPoint']=[p[0],p[1],p[2]]
134        SC.SetRenderState(rs)
135        return []
136
137    #add object with graphics user function
138    oGround2 = mbs.AddObject(ObjectGround(visualization=
139                                          VObjectGround(graphicsDataUserFunction=UFgraphics)))
140#add rigid bodies
141#rear wheel
142[nR,bR]=AddRigidBody(mainSys = mbs,
143                     inertia = inertiaR,
144                     rotationMatrix = RotationMatrixZ(pi*0.5), #rotate 90° around z
145                     nodeType = exu.NodeType.RotationEulerParameters,
146                     position = P1,
147                     velocity=[vX0,omegaX0*P1[2]*sZ,0],
148                     # velocity=[0,0,0],
149                     angularVelocity=[omegaX0,omegaRy0,0], #local rotation axis is now x
150                     gravity = g,
151                     graphicsDataList = [graphicsR])
152
153mbs.variables['nTrackNode'] = nR #node to be tracked
154
155#front wheel
156[nF,bF]=AddRigidBody(mainSys = mbs,
157                     inertia = inertiaF,
158                     rotationMatrix = RotationMatrixZ(pi*0.5),
159                     nodeType = exu.NodeType.RotationEulerParameters,
160                     position = P3,
161                     velocity=[vX0,omegaX0*P3[2]*sZ,0],
162                     # velocity=[0,0,0],
163                     angularVelocity=[omegaX0 ,omegaFy0,0],
164                     gravity = g,
165                     graphicsDataList = [graphicsF])
166
167#read body
168[nB,bB]=AddRigidBody(mainSys = mbs,
169                     inertia = inertiaB,
170                     nodeType = exu.NodeType.RotationEulerParameters,
171                     position = bCOM,
172                     velocity=[vX0,omegaX0*bCOM[2]*sZ,0],
173                     # velocity=[0,0,0],
174                     angularVelocity=[omegaX0,0,0],
175                     gravity = g,
176                     graphicsDataList = [graphicsB,graphicsB2])
177
178#handle
179[nH,bH]=AddRigidBody(mainSys = mbs,
180                     inertia = inertiaH,
181                     nodeType = exu.NodeType.RotationEulerParameters,
182                     position = hCOM,
183                     velocity=[vX0,omegaX0*hCOM[2]*sZ,0],
184                     # velocity=[0,0,0],
185                     angularVelocity=[omegaX0,0,0],
186                     gravity = g,
187                     graphicsDataList = [graphicsH])
188
189
190#%%++++++++++++++++++++++++++++++++++++++++++++++++
191#ground body and marker
192gGround = GraphicsDataCheckerBoard(point=[0,0,0], size=200, nTiles=64)
193oGround = mbs.AddObject(ObjectGround(visualization=VObjectGround(graphicsData=[gGround])))
194markerGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=oGround, localPosition=[0,0,0]))
195
196markerR = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bR, localPosition=[0,0,0]))
197markerF = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bF, localPosition=[0,0,0]))
198
199markerB1 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P1-bCOM))
200markerB2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bB, localPosition=P2-bCOM))
201
202markerH3 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P3-hCOM))
203markerH2 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bH, localPosition=P2-hCOM))
204
205
206sMarkerR = mbs.AddSensor(SensorMarker(markerNumber=markerR, outputVariableType=exu.OutputVariableType.Position))
207sMarkerB1= mbs.AddSensor(SensorMarker(markerNumber=markerB1,outputVariableType=exu.OutputVariableType.Position))
208
209#%%++++++++++++++++++++++++++++++++++++++++++++++++
210#add joints:
211useJoints = True
212if useJoints:
213    oJointRW = mbs.AddObject(GenericJoint(markerNumbers=[markerR, markerB1],
214                                          constrainedAxes=[1,1,1,1,0,1],
215                                          rotationMarker0=RotationMatrixZ(pi*0.5),
216                                          visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
217
218    oJointFW = mbs.AddObject(GenericJoint(markerNumbers=[markerF, markerH3],
219                                          constrainedAxes=[1,1,1,1,0,1],
220                                          rotationMarker0=RotationMatrixZ(pi*0.5),
221                                          visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=5*dY)))
222
223    oJointSteer = mbs.AddObject(GenericJoint(markerNumbers=[markerB2, markerH2],
224                                          constrainedAxes=[1,1,1,1,1,0],
225                                          rotationMarker0=RotationMatrixY(-lam),
226                                          rotationMarker1=RotationMatrixY(-lam),
227                                          visualization=VGenericJoint(axesRadius=0.5*dY, axesLength=3*5*dY)))
228#%%++++++++++++++++++++++++++++++++++++++++++++++++
229#add 'rolling disc' for wheels:
230cStiffness = 5e4*10 #spring stiffness: 50N==>F/k = u = 0.001m (penetration)
231cDamping = cStiffness*0.05*0.1 #think on a one-mass spring damper
232nGenericR = mbs.AddNode(NodeGenericData(initialCoordinates=[0,0,0], numberOfDataCoordinates=3))
233if False:
234    oRollingR=mbs.AddObject(ObjectConnectorRollingDiscPenalty(markerNumbers=[markerGround, markerR],
235                                                              nodeNumber = nGenericR,
236                                                              discRadius=rR,
237                                                              planeNormal=[0,0,1],
238                                                              dryFriction=[0.8,0.8],
239                                                              dryFrictionProportionalZone=1e-2,
240                                                              rollingFrictionViscous=0.,
241                                                              contactStiffness=cStiffness,
242                                                              contactDamping=cDamping,
243                                                              #activeConnector = False, #set to false to deactivated
244                                                              visualization=VObjectConnectorRollingDiscPenalty(show=True,
245                                                                                                               discWidth=dY, color=color4blue)))
246
247    nGenericF = mbs.AddNode(NodeGenericData(initialCoordinates=[0,0,0], numberOfDataCoordinates=3))
248    oRollingF=mbs.AddObject(ObjectConnectorRollingDiscPenalty(markerNumbers=[markerGround, markerF],
249                                                              nodeNumber = nGenericF,
250                                                              discRadius=rF,
251                                                              planeNormal=[0,0,1],
252                                                              dryFriction=[0.8,0.8],
253                                                              dryFrictionProportionalZone=1e-2,
254                                                              rollingFrictionViscous=0.,
255                                                              contactStiffness=cStiffness,
256                                                              contactDamping=cDamping,
257                                                              #activeConnector = False, #set to false to deactivated
258                                                              visualization=VObjectConnectorRollingDiscPenalty(show=True, discWidth=dY, color=color4blue)))
259else:
260    if True:
261        oRollingR=mbs.AddObject(ObjectJointRollingDisc(markerNumbers=[markerGround, markerR],
262                                                        discRadius=rR,
263                                                        visualization=VObjectJointRollingDisc(show=True, discWidth=dY, color=color4blue)))
264
265        oRollingF=mbs.AddObject(ObjectJointRollingDisc(markerNumbers=[markerGround, markerF],
266                                                        discRadius=rF,
267                                                        visualization=VObjectJointRollingDisc(show=True, discWidth=dY, color=color4blue)))
268
269
270
271#%%++++++++++++++++++++++++++++++++++++++++++++++++
272#add sensors
273addSensors = True
274if addSensors:
275    sForwardVel = mbs.AddSensor(SensorBody(bodyNumber=bB, fileName='solution/bicycleBvelLocal.txt',
276                                          localPosition=P1-bCOM,
277                                          outputVariableType=exu.OutputVariableType.VelocityLocal))
278
279    sBAngVelLocal = mbs.AddSensor(SensorBody(bodyNumber=bB, fileName='solution/bicycleBangVelLocal.txt',
280                                                outputVariableType=exu.OutputVariableType.AngularVelocityLocal))
281    sBrot = mbs.AddSensor(SensorBody(bodyNumber=bB, fileName='solution/bicycleBrot.txt',
282                                                outputVariableType=exu.OutputVariableType.Rotation))
283
284
285    bodies = [bB, bH, bR, bF]
286    massBodies = [mB, mH, mR, mF]
287    inertiaBodies = [inertiaB.inertiaTensor,
288                     inertiaH.inertiaTensor,
289                     inertiaR.inertiaTensor,
290                     inertiaF.inertiaTensor]
291
292    nBodies = len(bodies)
293    sList = []
294    for b in bodies:
295        sPosCOM = mbs.AddSensor(SensorBody(bodyNumber=b, writeToFile=False,
296                                                    outputVariableType=exu.OutputVariableType.Position))
297        sVelCOM = mbs.AddSensor(SensorBody(bodyNumber=b, writeToFile=False,
298                                                    outputVariableType=exu.OutputVariableType.Velocity))
299        sAngVelLocal = mbs.AddSensor(SensorBody(bodyNumber=b, writeToFile=False,
300                                                    outputVariableType=exu.OutputVariableType.AngularVelocityLocal))
301
302        sList += [sPosCOM,sVelCOM,sAngVelLocal]
303
304    if useJoints:
305        sSteerAngle = mbs.AddSensor(SensorObject(objectNumber=oJointSteer, fileName='solution/bicycleSteerAngle.txt',
306                                                    outputVariableType=exu.OutputVariableType.Rotation))
307        sSteerVel = mbs.AddSensor(SensorObject(objectNumber=oJointSteer, fileName='solution/bicycleSteerVelocity.txt',
308                                                    outputVariableType=exu.OutputVariableType.AngularVelocityLocal))
309
310
311    #create user joint for kinetic and potential energy
312    def UFsensorEnergy(mbs, t, sensorNumbers, factors, configuration):
313        E = 0
314        P = 0
315        for i in range(nBodies):
316            pos = mbs.GetSensorValues(sensorNumbers[i*3+0])
317            vel = mbs.GetSensorValues(sensorNumbers[i*3+1]) #vel
318            omega = mbs.GetSensorValues(sensorNumbers[i*3+2]) #ang vel local
319            E += 0.5 * NormL2(vel)**2 * massBodies[i]
320            E += 0.5 * np.array(omega) @ inertiaBodies[i] @ omega
321
322            P -= np.dot(g,pos)*massBodies[i]
323        return [P, E, E+P] #return potential, kinetic and total mechanical energy
324
325    sEnergy = mbs.AddSensor(SensorUserFunction(sensorNumbers=sList, #factors=[180/pi],
326                                             fileName='solution/sensorKineticPotentialEnergy.txt',
327                                             sensorUserFunction=UFsensorEnergy))
328
329    def UFsensorResults(mbs, t, sensorNumbers, factors, configuration):
330        energy =        mbs.GetSensorValues(sensorNumbers[0])
331        forwardVel =    mbs.GetSensorValues(sensorNumbers[1])
332        angVelLocalB =  mbs.GetSensorValues(sensorNumbers[2])
333        rotB =          mbs.GetSensorValues(sensorNumbers[3])
334        steerAngle =    mbs.GetSensorValues(sensorNumbers[4])
335        steerVel =      mbs.GetSensorValues(sensorNumbers[5])
336        return [rotB[0], angVelLocalB[0], forwardVel[0], energy[0], energy[1], energy[2], -steerAngle[2], -steerVel[2]] #return kinetic, potential and total mechanical energy
337
338    # 1=roll angle, 2=roll angular velocity, 3=forward speed, 4=potential energy, 5=kinetic energy, 6=mechanical energy, 7=steer angle, and 8=steer velocity
339    sResults = mbs.AddSensor(SensorUserFunction(sensorNumbers=[sEnergy,sForwardVel,sBAngVelLocal,sBrot, sSteerAngle, sSteerVel],
340                                             fileName='solution/sensorResults'+maneuver+'.txt',
341                                             sensorUserFunction=UFsensorResults))
342
343#%%++++++++++++++++++++++++++++++++++++++++++++++++
344#simulate:
345mbs.Assemble()
346
347pR = mbs.GetSensorValues(sMarkerR)
348pB1 = mbs.GetSensorValues(sMarkerB1)
349print("pR=",pR)
350print("pB1=",pB1)
351simulationSettings = exu.SimulationSettings() #takes currently set values or default values
352
353tEnd = 5*4
354h=0.001  #use small step size to detext contact switching
355
356simulationSettings.timeIntegration.numberOfSteps = int(tEnd/h)
357simulationSettings.timeIntegration.endTime = tEnd
358simulationSettings.solutionSettings.writeSolutionToFile= False #set False for CPU performance measurement
359simulationSettings.solutionSettings.sensorsWritePeriod = 0.01
360simulationSettings.solutionSettings.outputPrecision = 16
361
362simulationSettings.timeIntegration.verboseMode = 1
363#simulationSettings.linearSolverSettings.ignoreSingularJacobian = True
364
365# simulationSettings.timeIntegration.generalizedAlpha.useIndex2Constraints = True
366# simulationSettings.timeIntegration.generalizedAlpha.useNewmark = True
367simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.7
368simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations=True
369simulationSettings.timeIntegration.newton.useModifiedNewton = True
370
371SC.visualizationSettings.nodes.show = True
372SC.visualizationSettings.nodes.drawNodesAsPoint  = False
373SC.visualizationSettings.nodes.showBasis = True
374SC.visualizationSettings.nodes.basisSize = 0.015
375
376if False: #record animation frames:
377    SC.visualizationSettings.exportImages.saveImageFileName = "animation/frame"
378    SC.visualizationSettings.window.renderWindowSize=[1600,1024]
379    SC.visualizationSettings.openGL.multiSampling = 4
380    simulationSettings.solutionSettings.recordImagesInterval = 0.02
381
382SC.visualizationSettings.general.autoFitScene = False #use loaded render state
383useGraphics = True
384if useGraphics:
385    exu.StartRenderer()
386    if 'renderState' in exu.sys:
387        SC.SetRenderState(exu.sys[ 'renderState' ])
388    mbs.WaitForUserToContinue()
389
390mbs.SolveDynamic(simulationSettings, solverType=exu.DynamicSolverType.TrapezoidalIndex2)
391#mbs.SolveDynamic(simulationSettings, showHints=True)
392
393
394#%%+++++++++++++++++++++++++++++
395if useGraphics:
396    SC.WaitForRenderEngineStopFlag()
397    exu.StopRenderer() #safely close rendering window!
398
399#%%++++++++++++++++++++++++++++++++++++++++++++++q+++++++
400if addSensors:
401    #plot results
402
403
404
405    import matplotlib.pyplot as plt
406    import matplotlib.ticker as ticker
407    plt.close('all')
408
409
410    # mbs.PlotSensor(sensorNumbers=[sBpos,sBpos,sBpos], components=[0,1,2])
411    #plt.figure('lateral position')
412    #mbs.PlotSensor(sensorNumbers=[sBpos], components=[1])
413
414    plt.figure('forward velocity')
415    mbs.PlotSensor(sensorNumbers=[sForwardVel], components=[0])
416    # mbs.PlotSensor(sensorNumbers=[sBvelLocal,sBvelLocal,sBvelLocal], components=[0,1,2])
417
418    # plt.figure('local ang velocities')
419    # mbs.PlotSensor(sensorNumbers=[sBAngVelLocal,sBAngVelLocal,sBAngVelLocal], components=[0,1,2])
420    # if False:
421    #     import matplotlib.pyplot as plt
422    #     import matplotlib.ticker as ticker
423
424    # 1=roll angle, 2=roll angular velocity, 3=forward speed, 4=potential energy, 5=kinetic energy, 6=mechanical energy, 7=steer angle, and 8=steer velocity
425    data = np.loadtxt('solution/uncontrolledBicycleGonzalez.txt')#, comments='#', delimiter='')
426    plt.plot(data[:,0], data[:,9], 'b:',label='')
427
428    data2 = np.loadtxt('solution/uncontrolledBicycleSanjurjo.txt')#, comments='#', delimiter='')
429    plt.plot(data2[:,0], data2[:,3+8], 'g:',label='')
430
431    plt.figure('steer vel')
432    mbs.PlotSensor(sensorNumbers=[sSteerVel], components=[2])
433    plt.plot(data2[:,0], -data2[:,8+8], 'g:',label='')
434
435    plt.figure('steer ang')
436    mbs.PlotSensor(sensorNumbers=[sSteerAngle], components=[2])
437    plt.plot(data2[:,0], -data2[:,7+8], 'g:',label='')
438
439    plt.figure('roll')
440    mbs.PlotSensor(sensorNumbers=[sBrot], components=[0])
441    plt.plot(data2[:,0], data2[:,1+8], 'g:',label='')
442
443    plt.figure('roll ang vel')
444    mbs.PlotSensor(sensorNumbers=[sBAngVelLocal], components=[0])
445    plt.plot(data2[:,0], data2[:,2+8], 'g:',label='')
446
447
448    plt.figure('potential energy')
449    mbs.PlotSensor(sensorNumbers=[sEnergy], components=[0])
450    plt.plot(data2[:,0], data2[:,4+8], 'g:',label='')
451
452    plt.figure('kinetic energy')
453    mbs.PlotSensor(sensorNumbers=[sEnergy], components=[1])
454    plt.plot(data2[:,0], data2[:,5+8], 'g:',label='')
455
456    plt.figure('total energy')
457    mbs.PlotSensor(sensorNumbers=[sEnergy], components=[2])
458
459    dataE = np.loadtxt('solution/sensorKineticPotentialEnergy.txt', comments='#', delimiter=',')
460    performance = 100*(max(dataE[:,3]) - min(dataE[:,3])) / dataE[0,3]
461    print("performance = ", performance, "(must by < 1e-3)")
462
463    #CPU performance with 20 seconds simulation time, maneuver 2
464    #performance = 0.000915 < 0.001: max h=0.014; CPU time = 0.596 seconds on Intel Core i9
465    #reference solution computed with:
466    #  performance = 6.423e-06: max h=0.001; CPU time = 5.5935 seconds on Intel Core i9
467
468
469#%%+++++++++++++++++
470#merge result files for IFToMM
471if True:
472    dataM1 = np.loadtxt('solution/sensorResultsM1.txt', comments='#', delimiter=',')
473    dataM2 = np.loadtxt('solution/sensorResultsM2.txt', comments='#', delimiter=',')
474    dataM3 = np.loadtxt('solution/sensorResultsM3.txt', comments='#', delimiter=',')
475
476    data = np.hstack((dataM1,dataM2[:,1:],dataM3[:,1:]))
477    np.savetxt('solution/bicycleResultsIFToMM.txt', data, fmt='%1.15e')
478
479# benchmark results:
480# 6.423e-06
481# 5.5935
482# Intel(R) Core(TM) i9-7940X CPU @ 3.10GHz
483# Simulated using C++/Python library EXUDYN, see https://github.com/jgerstmayr/EXUDYN.
484# Solved using implicit trapezoidal rule (energy conserving) with Index 2 constraint reduction, using redundant coordinate formulation. Rigid bodies are modeled with Euler parameters.
485# With a larger step size of 0.014 we still obtain a performance <0.001, but have CPU time of 0.596 seconds.