diff --git a/README.rst b/README.rst index 4b939ec8..e951ca8f 100644 --- a/README.rst +++ b/README.rst @@ -37,7 +37,7 @@ Exudyn **A flexible multibody dynamics systems simulation code with Python and C++** -Exudyn version = 1.6.164.dev1 (Gillespie) +Exudyn version = 1.7.0 (Hall) + **University of Innsbruck**, Department of Mechatronics, Innsbruck, Austria diff --git a/docs/RST/Abbreviations.rst b/docs/RST/Abbreviations.rst index 17f8d98a..5df5beca 100644 --- a/docs/RST/Abbreviations.rst +++ b/docs/RST/Abbreviations.rst @@ -114,7 +114,7 @@ see also :ref:`Section Notation `\ . .. _T66: -\ **T66**\ : Pl"ucker transformation +\ **T66**\ : Plücker transformation .. _trig: diff --git a/docs/RST/Examples/ROSExampleMassPoint.rst b/docs/RST/Examples/ROSExampleMassPoint.rst new file mode 100644 index 00000000..cee7d344 --- /dev/null +++ b/docs/RST/Examples/ROSExampleMassPoint.rst @@ -0,0 +1,226 @@ + +.. _examples-rosexamplemasspoint: + +********************** +ROSExampleMassPoint.py +********************** + +You can view and download this file on Github: `ROSExampleMassPoint.py `_ + +.. code-block:: python + :linenos: + + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + # This is an EXUDYN python example how to use ROS and EXUDYN + # + # Details: This example shows how to communicate between an exudyn simulation + # and ROS publisher and subscriber from bash + # To make use of this example, you need to + # install ROS (ROS1 noetic) including rospy (see rosInterface.py) + # prerequisits to use: + # use a bash terminal to start the roscore with: + # roscore + # send force command to add load to the mass point form bash file with: + # rostopic pub -r 100 /cmd_wrench geometry_msgs/WrenchStamped "..." + # Author: Martin Sereinig, Peter Manzl + # Date: 2023-05-31 (created) + # + # 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. + # + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + import numpy as np + import exudyn as exu + from exudyn.utilities import * + + # import needed ROS modules and messages + import rospy + from geometry_msgs.msg import WrenchStamped, Twist + from std_msgs.msg import String + + # import new exudyn ROS interface class + import rosInterface as exuROS + + # here build inherited class and using within a simple exudyn simulation of one mass spring-damper + class MyExudynROSInterface(exuROS.ROSInterface): + def __init__(self): + # use initialisation of super class + # this initialize a rosnode with name + super().__init__(name='exuROSexample3Dmass') + # initialization of all standard publisher done by super class + # self.exuPosePublisher + # self.exuStringPublisher + # self.exuSystemstatePublisher + # self.exuTimePublisher + # self.exuTwistPublisher + + # use standard publisher functions form super class! + # self.PublishPoseUpdate + # self.PublishTwistUpdate + # self.PublishSystemStateUpdate + + # initialize all subscriber + # suitable callback function is auto generated by superclass (using lambda function) + # twist subscriber: cmd_vel + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_vel' # topic to subscribe + self.cmd_vel = Twist() # data type of topic, must be named: self.twistSubscriberTopic + self.myTwistSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,Twist) + + # wrench subscriber: cmd_wrench + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_wrench' # topic to subscribe + self.cmd_wrench = WrenchStamped() # data type of topic, must be named: self.twistSubscriberTopic + self.myWrenchSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,WrenchStamped) + + # string subsriber: my_string + stringSubsrciberBase = '' + stringSubsrciberTopic = 'my_string' # topic to subscribe + self.my_string = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase,stringSubsrciberTopic,String) + + # string subsriber: /exudyn/SimpleString + stringSubsrciberBase2 = 'exudyn/' # namespace of topic + stringSubsrciberTopic2 = 'SimpleString' # topic to subscribe + self.SimpleString = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase2,stringSubsrciberTopic2,String) + + + # test main function + def main(): + + # build exudyn model + SC = exu.SystemContainer() + mbs = SC.AddSystem() + tRes = 0.001 # step size in s + tEnd = 1e5 # simulation time in s + # mass and dimension of sphere + mass = 6 + r = 0.03 + background = GraphicsDataCheckerBoard(point=[-0.5,0,0], + normal=[1, 0, 0], + color=[0.7]*3+[1], + alternatingColor=[0.8]*3+[1]) + + graphicsSphere = GraphicsDataSphere(point=[0,0,0], + radius=r, + color=(1,0,0,1), + nTiles=64) + + origin = [0, 0, 0] + bGround = mbs.AddObject(ObjectGround(referencePosition=origin, + visualization=VObjectGround(graphicsData=[background]))) + + inertiaSphere = InertiaSphere(mass=mass,radius=r) + + # user interaction point + [nUIP, bUIP]=AddRigidBody(mainSys = mbs, + inertia = inertiaSphere, + nodeType = str(exu.NodeType.RotationEulerParameters), + position = [origin[0], origin[1], origin[2]], + rotationMatrix = np.eye(3), + angularVelocity = np.zeros(3), + velocity= [0,0,0], + gravity = [0, 0, 0], + graphicsDataList = [graphicsSphere]) + + # create markers: + mGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bGround, localPosition=[0, 0, 0.])) + mUIP = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bUIP)) + mUIPLoad = mbs.AddLoad(LoadForceVector(markerNumber = mUIP,loadVector =[0,0,0])) + + k = 100 + oSpringDamper = mbs.AddObject(RigidBodySpringDamper(markerNumbers=[mGround, mUIP], + stiffness=np.eye(6)*k, + damping=np.eye(6)*k*5e-2, + visualization={'show': False, 'drawSize': -1, 'color': [-1]*4})) + + + # sensor for position of endpoint of pendulum + sensorPos = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Position)) + sensorOri = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Rotation)) + sensorVelt = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Velocity)) + sensorVelr = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.AngularVelocity)) + + # store sensor value of each step in mbs variable, so that is accessible from user function + mbs.variables['pos'] = sensorPos + mbs.variables['ori'] = sensorOri + mbs.variables['velt'] = sensorVelt + mbs.variables['velr'] = sensorVelr + + # initialize ROS interface from own subclass + myROSInterface = MyExudynROSInterface() + + print('rosversion: ' + str(myROSInterface.myROSversionEnvInt)) + rospy.logdebug('node running and publishing') + + # exudyn PreStepUserFunction + def PreStepUserFunction(mbs, t): + # send position data to ROS + myROSInterface.PublishPoseUpdate(mbs,t) + # send velocity data to ROS + myROSInterface.PublishTwistUpdate(mbs,t) + # send system state data to ROS + myROSInterface.PublishSystemStateUpdate(mbs,t) + + # get string data from ROS /my_string topic, please use: rostopic pub -r 100 /my_string geometry_msgs/WrenchStamped "..." + someMessage = myROSInterface.my_string.data + if someMessage != '' : + print('mystringdata',someMessage) + + # get wrench data from ROS /cmd_wrench topic, please use: rostopic pub -r 100 /cmd_wrench geometry_msgs/WrenchStamped "..." + rosForces = myROSInterface.cmd_wrench.wrench.force + rosTorques = myROSInterface.cmd_wrench.wrench.torque + print('forces from ROS:', rosForces) + print('torques from ROS : ', rosTorques) + + # demo set force to certain value received from ROS /cmd_wrench + newForce = [rosForces.x, rosForces.y, rosForces.z] + mbs.SetLoadParameter(mUIPLoad,'loadVector',newForce) + + return True + + mbs.SetPreStepUserFunction(PreStepUserFunction) + # assemble multi body system with all previous specified properties and components + mbs.Assemble() + # set simulation settings + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.endTime = tEnd + simulationSettings.timeIntegration.numberOfSteps = int(tEnd/tRes) + simulationSettings.timeIntegration.newton.relativeTolerance = 1e-8*100 + simulationSettings.timeIntegration.newton.absoluteTolerance = 1e-10 + simulationSettings.timeIntegration.verboseMode = 1 # if 0 no output; higher --> more output information about solver + simulationSettings.timeIntegration.newton.useModifiedNewton = False + simulationSettings.timeIntegration.newton.numericalDifferentiation.minimumCoordinateSize = 1 + simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5 + simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations = False + simulationSettings.timeIntegration.simulateInRealtime = True # crucial for operating with robot + simulationSettings.displayStatistics = True + simulationSettings.solutionSettings.solutionInformation = "3D Spring Damper" + simulationSettings.solutionSettings.writeSolutionToFile = False + viewMatrix = np.eye(3) @ RotationMatrixZ(np.pi/2)@ RotationMatrixX(np.pi/2) + SC.visualizationSettings.general.autoFitScene = False + # set up parameter for usage in WSL2 (Ubuntu 20.04) on Windows 10 + SC.visualizationSettings.window.startupTimeout = 5000 + SC.visualizationSettings.interactive.selectionLeftMouse=False + SC.visualizationSettings.interactive.selectionRightMouse=False + + exu.StartRenderer(True) + exu.SolveDynamic(mbs, simulationSettings) + + return True + + # __main__ function for testing the interface + if __name__ == "__main__": + try: + main() + except rospy.ROSInterruptException: + pass + + + diff --git a/docs/RST/Examples/ROSExampleTurtle.rst b/docs/RST/Examples/ROSExampleTurtle.rst new file mode 100644 index 00000000..5f948a88 --- /dev/null +++ b/docs/RST/Examples/ROSExampleTurtle.rst @@ -0,0 +1,324 @@ + +.. _examples-rosexampleturtle: + +******************* +ROSExampleTurtle.py +******************* + +You can view and download this file on Github: `ROSExampleTurtle.py `_ + +.. code-block:: python + :linenos: + + #!/usr/bin/env python3 + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + # This is an EXUDYN python example how to use ROS and EXUDYN + # + # Details: This example shows how to communicate between an exudyn simulation + # and ROS + # To make use of this example, you need to + # install ROS (ROS1 noetic) including rospy (see exudynROSInterface.py) + # prerequisite to use: + # use a bash terminal to start the roscore with: + # roscore + # you can also use the ROS turtlesim_node to subsrcibe the Twist massage from exudyn + # use a bash terminal to start the turtlesim node with: + # rosrun turtlesim turtlesim_node turtle1/cmd_vel:=exudyn/Twist + # start example with argument -pub, to use it with external publisher: + # python3 ROSexampleTurtle.py -pub + # start example with argument -noTrack, to not track the turtle: + # python3 ROSexampleTurtle.py -noTrack + # for even more ROS functionality create a ROS package (e.q. myExudynInterface) in a catkin workspace, + # copy files ROSExampleTurtle.py, Turtle.stl and ROSExampleBringup.launch file in corresponding folders within the package + # for more functionality see also: ROSExampleMassPoint.py, ROSExampleBringup.launch, ROSExampleControlVelocity.py + # Author: Martin Sereinig, Peter Manzl + # Date: 2023-05-31 (created) + # + # 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. + # + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + import numpy as np + import sys + import exudyn as exu + from exudyn.utilities import * + + # import needed ROS modules and messages + import rospy + from geometry_msgs.msg import Twist + from std_msgs.msg import String + + # import new exudyn ROS interface class + import rosInterface as exuROS + + # here build inherited class and using within a simple exudyn simulation of one mass spring-damper + class MyExudynROSInterface(exuROS.ROSInterface): + def __init__(self): + # use initialisation of super class + # this initialize a rosnode with name + super().__init__(name='ROSexampleTurtle') + # initialization of all standard publisher done by super class + # self.exuPosePublisher + # self.exuStringPublisher + # self.exuSystemstatePublisher + # self.exuTimePublisher + # self.exuTwistPublisher + + # use standard publisher functions form super class! + # self.PublishPoseUpdate + # self.PublishTwistUpdate + # self.PublishSystemStateUpdate + + # initialize all subscriber + # suitable callback function is auto generated by superclass (using lambda function) + # twist subscriber: cmd_vel + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_vel' # topic to subscribe + self.cmd_vel = Twist() # data type of topic, must be named: self.twistSubscriberTopic + self.myTwistSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,Twist) + # string subsriber: my_string + stringSubsrciberBase = '' + stringSubsrciberTopic = 'my_string' # topic to subscribe + self.my_string = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase,stringSubsrciberTopic,String) + + + def main(): + + #function to check if argument is in sys.argv with try/except + def argumentInSysArgv(index): + try: + sys.argv[index] + except IndexError: + return '' + else: + return sys.argv[index] + + # turtle moves in circle and is tracked by default (no arguments) + hearToPublisher = False + saveTrack = True + # parse command line arguments for multiple arguments: + # -pub: use external publisher + # -noTrack: do not track turtle + if len(sys.argv) > 1: + for arguments in range(len(sys.argv)): + if argumentInSysArgv(arguments) == '-pub': + hearToPublisher = True + print('Wait for external ROS publisher on /cmd_vel for turtle to move') + if argumentInSysArgv(arguments) == '-noTrack': + saveTrack = False + print('Turtle is not tracked') + + # build exudyn model + SC = exu.SystemContainer() + mbs = SC.AddSystem() + tRes = 0.001 # step size in s + tEnd = 1e5 # simulation time in s + # density and dimension of box + boxdensity = 1e-5 + boxLength = [0.5, 0.25, 0.1] + + background = GraphicsDataCheckerBoard(point=[0,0,0], + normal=[0, 0, 1], + color=[0.7]*3+[0.5], + alternatingColor=[0.8]*3+[1], + nTiles=10, + size=10) + + graphicsCube = GraphicsDataOrthoCubePoint(centerPoint = [0,0,0], + size = boxLength, + color = [1,0.,0.,1.], + addNormals = False, + addEdges = False, + edgeColor = color4black, + addFaces = True) + inertiaCube = InertiaCuboid(density= boxdensity, sideLengths = boxLength) + + + origin = [0, 0, 0] + bGround = mbs.AddObject(ObjectGround(referencePosition=origin, + visualization=VObjectGround(graphicsData=[background]))) + + # graphics userfunction definieren: + if saveTrack: + def graphicsTrajUF(mbs, itemNumber): + t = mbs.systemData.GetTime(exu.ConfigurationType.Visualization) + # position of turtle stored by sensor in mbs.variables['pos'] + pOld = mbs.GetSensorStoredData(mbs.variables['pos']) + try: + iCurr = np.min([np.argmin(abs(pOld[:,0] - t)), len(pOld[:,0])-1]) + pOld = pOld[:iCurr, :] + except: + pass + + if len(pOld) > 2: + trajData = np.matrix.flatten(pOld[:,1:]).tolist() + + for i in range(int(len(trajData)/3)): + trajData[2+3*i] += 0.115 # draw it on top of the robot + graphicsTraj = {'type':'Line', 'data': trajData, 'color':color4blue} + else: + graphicsTraj = [] + return [graphicsTraj] + # add object ground with graphics user function to add turtle track + oTrack = mbs.AddObject(ObjectGround(visualization =VObjectGround(graphicsData=[], graphicsDataUserFunction = graphicsTrajUF))) + + graphicsTurtleList = [] + try: + try: + path2stl = rospy.get_param('/ROSExampleTurtle/stlFilePath') # node_name/argsname + except: + path2stl = '' + print('stl file path: ', path2stl) + turtleRot = RotationMatrixZ(-np.pi/2) + stlGrafics = GraphicsDataFromSTLfile(path2stl+'Turtle.stl',color=[1,0,0,1],scale=0.25,pOff=[0.35,0,0], Aoff=turtleRot) + graphicsTurtleList += [stlGrafics] + except: + print('stl not found, maybe wrong directory, use box instead') + graphicsTurtleList += [graphicsCube] + + # user interaction point + [nUIP, bUIP]=AddRigidBody(mainSys = mbs, + inertia = inertiaCube, + nodeType = str(exu.NodeType.RotationEulerParameters), + position = [origin[0], origin[1], origin[2]], + rotationMatrix = np.eye(3), + angularVelocity = np.array([0,0,0]), + velocity= [0,0,0], + gravity = [0, 0, 0], + graphicsDataList = graphicsTurtleList) + + + # create markers: + mGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bGround, localPosition=[0.0, 0.0, 0.0])) + mUIP = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bUIP)) + + dampingHelper = 1e-4 + # create userfunction for TorsionalSpringDamper + def UFtorque(mbs,t,itemNumber,r,av,k,d,offset): + return (av-offset)*d + # create TorsionalSpringDamper object + oTSD = mbs.AddObject(TorsionalSpringDamper(markerNumbers = [mGround,mUIP], + damping = dampingHelper, + offset = 0, + springTorqueUserFunction = UFtorque)) + # create userfunction for CartesianSpringDamper + def UFforce(mbs, t,itemNumber, u, v, k, d, offset): + return [(v[0]-offset[0])*d[0], (v[1]-offset[1])*d[1], (v[2]-offset[2])*d[2]] + # create CartesianSpringDamper object + + oCSD = mbs.AddObject(CartesianSpringDamper(markerNumbers = [mGround, mUIP], + damping = [dampingHelper,dampingHelper,dampingHelper], + offset = [0,0,0], + springForceUserFunction = UFforce, + visualization=VObjectConnectorCartesianSpringDamper(show=False))) + + sensorPos = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Position,storeInternal=True)) + sensorOri = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Rotation)) + sensorVelt = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Velocity)) + sensorVelr = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.AngularVelocity)) + + # store sensor value of each step in mbs variable, so that is accessible from user function + mbs.variables['pos'] = sensorPos # just needed if sensor is used for sensor information + mbs.variables['ori'] = sensorOri # just needed if sensor is used for sensor information + mbs.variables['velt'] = sensorVelt # just needed if sensor is used for sensor information + mbs.variables['velr'] = sensorVelr # just needed if sensor is used for sensor information + mbs.variables['hearToPublisher'] = hearToPublisher # needed to use with and without external publisher + mbs.variables['nodeNumber'] = nUIP # just needed if nodeNumber is used for sensor information + + # initialize ROS interface from own subclass + myROSInterface = MyExudynROSInterface() + + print('rosversion: ' + str(myROSInterface.myROSversionEnvInt)) + rospy.logdebug('node running and publishing') + + # exudyn PreStepUserFunction + def PreStepUserFunction(mbs, t): + + # get velocity data from ROS /cmd_vel topic, please use: rostopic pub -r 100 /cmd_vel geometry_msgs/Twist "..." + rosLinearVelo = myROSInterface.cmd_vel.linear + rosAngularVelo = myROSInterface.cmd_vel.angular + + # EXAMPLE to get position and orientation from exudyn turtle via sensor + turtlePosition = mbs.GetSensorValues(mbs.variables['pos']) + turtleOrientation = mbs.GetSensorValues(mbs.variables['ori'])[2] + turtleOrientationMatrix = RotationMatrixZ(turtleOrientation) + + + # set velocities to exudyn turtle simulation + if mbs.variables['hearToPublisher'] ==True: + # exudyn turtle hears on publisher + desiredLinearVelocity = turtleOrientationMatrix @ [rosLinearVelo.x, rosLinearVelo.y, rosLinearVelo.z] + desiredAngularVelocity = [rosAngularVelo.x, rosAngularVelo.y, rosAngularVelo.z] + else: + # exudyn turtle moves in a circle + desiredLinearVelocity = turtleOrientationMatrix @ [1, 0, 0] + desiredAngularVelocity = [0, 0, 1] + + mbs.SetObjectParameter(oCSD, 'offset', desiredLinearVelocity) + mbs.SetObjectParameter(oTSD, 'offset', desiredAngularVelocity[2]) + + # send velocity data to ROS + myROSInterface.PublishTwistUpdate(mbs,t) + # send position data to ROS + myROSInterface.PublishPoseUpdate(mbs,t) + # send system state data to ROS + myROSInterface.PublishSystemStateUpdate(mbs,t) + + return True + + + + + + mbs.SetPreStepUserFunction(PreStepUserFunction) + # assemble multi body system with all previous specified properties and components + mbs.Assemble() + # set simulation settings + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.endTime = tEnd + simulationSettings.timeIntegration.numberOfSteps = int(tEnd/tRes) + simulationSettings.timeIntegration.newton.relativeTolerance = 1e-8*100 + simulationSettings.timeIntegration.newton.absoluteTolerance = 1e-10 + simulationSettings.timeIntegration.verboseMode = 1 # if 0 no output; higher --> more output information about solver + simulationSettings.timeIntegration.newton.useModifiedNewton = False + simulationSettings.timeIntegration.newton.numericalDifferentiation.minimumCoordinateSize = 1 + simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5 + simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations = False + + simulationSettings.timeIntegration.simulateInRealtime = True # crucial for operating with robot + simulationSettings.displayStatistics = True + simulationSettings.solutionSettings.solutionInformation = "Exudyn-ROS turtle" + + simulationSettings.solutionSettings.writeSolutionToFile = False + SC.visualizationSettings.general.autoFitScene = True + # set up parameter for usage in WSL2 (Ubuntu 20.04) on Windows 10 + SC.visualizationSettings.interactive.trackMarker = mUIP + SC.visualizationSettings.window.startupTimeout = 8000 + SC.visualizationSettings.openGL.initialZoom = 0.2 + SC.visualizationSettings.openGL.initialMaxSceneSize= 0.7 + SC.visualizationSettings.interactive.selectionLeftMouse=False + SC.visualizationSettings.interactive.selectionRightMouse=False + + + exu.StartRenderer(True) + exu.SolveDynamic(mbs, simulationSettings) + + return True + + # create a function + + # __main__ function + if __name__ == "__main__": + try: + main() + except rospy.ROSInterruptException: + pass + + + diff --git a/docs/RST/Examples/chatGPTupdate.rst b/docs/RST/Examples/chatGPTupdate.rst new file mode 100644 index 00000000..ebeaefa5 --- /dev/null +++ b/docs/RST/Examples/chatGPTupdate.rst @@ -0,0 +1,184 @@ + +.. _examples-chatgptupdate: + +**************** +chatGPTupdate.py +**************** + +You can view and download this file on Github: `chatGPTupdate.py `_ + +.. code-block:: python + :linenos: + + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + # This is an Exudyn file + # + # Details: this file serves as a list of examples that shall be used by + # ChatGPT to update information on its internal knowledge of Exudyn + # dating to 2021; the examples use the mainSystemExtensions + # which are heavily simplifying usage of point masses and rigid bodies + # Version: V1 + # + # Author: Johannes Gerstmayr + # Date: 2023-06-30 + # + # 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. + # + #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + + #copy the text below here into a ChatGPT input window: + + #Use the following information as an update of the internal data of the Python multibody code Exudyn. + #See the following examples to create multibody systems in Exudyn. + #NOTE: mbs.Create...(...) calls several functions in the background to create nodes, objects, markers and loads in Exudyn. + #all quantities are giving as 3D lists [x,y,z] for positions, velocities, .... + #rotations are usually given as rotation matrix (numpy array); + #RotationVector2RotationMatrix([rotX, rotY, rotZ]) computes a rotation around the global x,y,z rotation axis + + #%%++++++++++++++++++++++++++++++++++++++++++++++++++++ + #create rigid bodies and mass points with distance constraint and joints + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities + import numpy as np + SC = exu.SystemContainer() + mbs = SC.AddSystem() #create a MainSystem 'mbs' to work with + + #draw orthonormal cube in local frame where it is added to; + #cube is added to reference point of object, usually the center of mass (COM): + graphicsCube = GraphicsDataOrthoCubePoint(centerPoint = [0,0,0], + size=[1,0.1,0.1], color=color4orange) + + #create inertia (mass, COM, inertia tensor) to be used in rigid body: + inertiaCube = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]) + + #create simple rigid body + #note that graphics is always attached to reference point of body, which is by default the COM + b0 = mbs.CreateRigidBody(inertia = inertiaCube, + referencePosition = [0.5,0,0], #reference position x/y/z of COM + referenceRotationMatrix=RotationVector2RotationMatrix([0,0,pi*0.5]), + initialAngularVelocity=[2,0,0], + initialVelocity=[0,4,0], + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + + #add an additional load to rigid body at left end; this always requires markers; + #for torques use Torque(...) instead of Force(...) + markerBody0 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=b0, localPosition=[-0.5,0,0])) + mbs.AddLoad(Force(markerNumber=markerBody0, + loadVector=[10,0,0])) #load is 10N in x-direction + + #create a simple mass point at [1,-1,0] with initial velocity + m1 = mbs.CreateMassPoint(referencePosition=[1,-1,0], + initialVelocity = [2,5,0], #initial velocities for mass point + physicsMass=1, drawSize = 0.2) + #we can obtain the node number from the mass point: + n1 = mbs.GetObject(m1)['nodeNumber'] + + #add a ground object: + #graphics data for sphere: + gGround0 = GraphicsDataSphere(point=[3,1,0], radius = 0.1, color=color4red, nTiles=16) + #graphics for checkerboard background: + gGround1 = GraphicsDataCheckerBoard(point=[3,0,-2], normal=[0,0,1], size=10) + oGround = mbs.AddObject(ObjectGround(visualization=VObjectGround(graphicsData=[gGround0,gGround1]))) + + #create a rigid distance between bodies (using local position) or between nodes + mbs.CreateDistanceConstraint(bodyOrNodeList=[oGround, b0], + localPosition0 = [ 0. ,0,0], + localPosition1 = [-0.5,0,0], + distance=None, #automatically computed + drawSize=0.06) + + #distance constraint between body b0 and mass m1 + mbs.CreateDistanceConstraint(bodyOrNodeList=[b0, m1], + localPosition0 = [0.5,0,0], + localPosition1 = [0.,0.,0.], #must be [0,0,0] for Node + distance=None, #automatically computed + drawSize=0.06) + + #add further rigid body, which will be connected with joints + b1 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]), + referencePosition = [2.5,0,0], #reference position x/y/z + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + + b2 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]), + referencePosition = [3.5,0,0], #reference position x/y/z + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + + #create revolute joint with following args: + # name: name string for joint; markers get Marker0:name and Marker1:name + # bodyNumbers: a list of object numbers for body0 and body1; must be rigid body or ground object + # position: 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 body0 + # axis: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 + # useGlobalFrame: if False, the point and axis vectors are defined in the local coordinate system of body0 + # show: if True, connector visualization is drawn + # axisRadius: radius of axis for connector graphical representation + # axisLength: length of axis for connector graphical representation + # color: color of connector + #returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint + mbs.CreateRevoluteJoint(bodyNumbers=[b1, b2], position=[3,0,0], axis=[0,0,1], #rotation along global z-axis + useGlobalFrame=True, axisRadius=0.02, axisLength=0.14) + + + #create prismatic joint with following args: + # name: name string for joint; markers get Marker0:name and Marker1:name + # bodyNumbers: a list of object numbers for body0 and body1; must be rigid body or ground object + # position: 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 body0 + # axis: a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration + # useGlobalFrame: if False, the point and axis vectors are defined in the local coordinate system of body0 + # show: if True, connector visualization is drawn + # axisRadius: radius of axis for connector graphical representation + # axisLength: length of axis for connector graphical representation + # color: color of connector + #returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint + mbs.CreatePrismaticJoint(bodyNumbers=[oGround, b1], position=[2,0,0], axis=[1,0,0], #can move in global x-direction + useGlobalFrame=True, axisRadius=0.02, axisLength=1) + + # #instead of the prismatic joint, we could add another revolute joint to b1 to get a double-pendulum: + # mbs.CreateRevoluteJoint(bodyNumbers=[oGround, b1], position=[2,0,0], axis=[0,0,1], + # useGlobalFrame=True, axisRadius=0.02, axisLength=0.14) + + + #create simple mass point, connected with ground + m2 = mbs.CreateMassPoint(referencePosition = [7,2,0], + physicsMass = 10, gravity = [0,-9.81,0], + drawSize = 0.5, color=color4blue) + + #create spring damper between bodies (using local position) or between nodes + #spring-damper may not have size 0; spring reference length is computed from reference configuration + oSD = mbs.CreateSpringDamper(bodyOrNodeList=[oGround, m2], + localPosition0=[6,0,0], + localPosition1=[0,0,0], + stiffness=1e3, damping=1e1, + drawSize=0.2) + + #alternatively, we can use a CartesianSpringDamper; has spring and damper coefficients as list of x/y/z components + #it has no reference length and acts on the coordinates of both objects: + oCSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[oGround, m2], + localPosition0=[7,2,0], + localPosition1=[0,0,0], + stiffness=[20,0,1e4], #stiffness in x/y/z direction + damping=[0.1,0,10], + drawSize=0.2) + + #prepare mbs for simulation: + mbs.Assemble() + #some simulation parameters: + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.numberOfSteps = 1000 + simulationSettings.timeIntegration.endTime = 5 + + #for redundant constraints, the following two settings: + simulationSettings.linearSolverSettings.ignoreSingularJacobian=True + simulationSettings.linearSolverType = exu.LinearSolverType.EigenDense + + mbs.SolveDynamic(simulationSettings = simulationSettings, + solverType=exu.DynamicSolverType.GeneralizedAlpha) + SC.visualizationSettings.nodes.drawNodesAsPoint=False #draw nodes as spheres; better graphics for nodes + + #visualize results: + mbs.SolutionViewer() + + + diff --git a/docs/RST/Examples/craneReevingSystem.rst b/docs/RST/Examples/craneReevingSystem.rst index 8113be89..7efbbdfa 100644 --- a/docs/RST/Examples/craneReevingSystem.rst +++ b/docs/RST/Examples/craneReevingSystem.rst @@ -303,7 +303,11 @@ You can view and download this file on Github: `craneReevingSystem.py stored internally in solver - # staticSolver.ComputeJacobianODE2RHS(mbs,scalarFactor_ODE2=-1, - # scalarFactor_ODE2_t=0, - # scalarFactor_ODE1=0) #could be 1 to include ODE1 part - # if nAE != 0: - # #compute AE part of jacobian if needed for constraint projection - # staticSolver.ComputeJacobianAE(mbs, scalarFactor_ODE2=1., scalarFactor_ODE2_t=0., - # scalarFactor_ODE1=0., #could be 1 to include ODE1 part - # velocityLevel=False) - - # jacobian = staticSolver.GetSystemJacobian() #read out stored jacobian; includes ODE2, ODE1 and nAE part - - # staticSolver.FinalizeSolver(mbs, simulationSettings) #close files, etc. - - # #obtain ODE2 part from jacobian == stiffness matrix - # Kode2 = jacobian[0:nODE2,0:nODE2] - - # remappingIndices = np.arange(nODE2) #maps new coordinates to original (full) ones - # if constrainedCoordinates != []: - # Mode2 = np.delete(np.delete(Mode2, constrainedCoordinates, 0), constrainedCoordinates, 1) - # Kode2 = np.delete(np.delete(Kode2, constrainedCoordinates, 0), constrainedCoordinates, 1) - # remappingIndices = np.delete(remappingIndices, constrainedCoordinates) - - # if nAE != 0 and not ignoreAlgebraicEquations and constrainedCoordinates != []: - # raise ValueError('ComputeODE2Eigenvalues: in case of algebraic equations, either ignoreAlgebraicEquations=True or constrainedCoordinates=[]') - - # if constrainedCoordinates != [] or nAE == 0: - # if not useSparseSolver: - # [eigenValuesUnsorted, eigenVectors] = eigh(Kode2, Mode2) #this gives omega^2 ... squared eigen frequencies (rad/s) - # if useAbsoluteValues: - # sortIndices = np.argsort(abs(eigenValuesUnsorted)) #get resorting index - # eigenValues = np.sort(a=abs(eigenValuesUnsorted)) #eigh returns unsorted eigenvalues... - # else: - # sortIndices = np.argsort(eigenValuesUnsorted) #get resorting index - # eigenValues = np.sort(a=eigenValuesUnsorted) #eigh returns unsorted eigenvalues... - # if numberOfEigenvalues > 0: - # eigenValues = eigenValues[0:numberOfEigenvalues] - # eigenVectors = eigenVectors[:,sortIndices[0:numberOfEigenvalues]] #eigenvectors are given in columns! - # else: - # if numberOfEigenvalues == 0: #compute all eigenvalues - # numberOfEigenvalues = nODE2 - - # Kcsr = csr_matrix(Kode2) - # Mcsr = csr_matrix(Mode2) - - # #use "LM" (largest magnitude), but shift-inverted mode with sigma=0, to find the zero-eigenvalues: - # #see https://docs.scipy.org/doc/scipy/reference/tutorial/arpack.html - # [eigenValues, eigenVectors] = eigsh(A=Kcsr, k=numberOfEigenvalues, M=Mcsr, - # which='LM', sigma=0, mode='normal') - - # #sort eigenvalues - # if useAbsoluteValues: - # sortIndices = np.argsort(abs(eigenValues)) #get resorting index - # eigenValues = np.sort(a=abs(eigenValues)) - # else: - # sortIndices = np.argsort(eigenValues) #get resorting index - # eigenValues = np.sort(a=eigenValues) - # eigenVectors = eigenVectors[:,sortIndices] #eigenvectors are given in columns! - - # eigenVectorsNew = np.zeros((nODE2,numberOfEigenvalues)) - # if constrainedCoordinates != []: - # # print('remap=', remappingIndices) - # for i in range(numberOfEigenvalues): - # eigenVectorsNew[remappingIndices,i] = eigenVectors[:,i] - # eigenVectors = eigenVectorsNew - # else: - # #%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - # #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - # #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - - # if useSparseSolver: - # raise ValueError('ComputeODE2Eigenvalues: in case of algebraic equations and ignoreAlgebraicEquations=False, useSparseSolver must be False') - # #use SVD to project equations into nullspace - # #constraint jacobian: - # C = jacobian[0:nODE2,nODE2+nODE1:] - - # #compute SVD; D includes singular values - # [U,D,V] = svd(C) - - # nnz = (abs(D) > singularValuesTolerance).sum() #size of constraints, often number of cols of C - - # nullspace = U[:,nnz:].T #U[nnz:] - # Knullspace = nullspace@Kode2@nullspace.T - # Mnullspace = nullspace@Mode2@nullspace.T - - # # print('nODE2=',nODE2) - # # print('nAE=',nAE) - # # print('nnz=',nnz) - # # print('C=',C.shape) - # # print('U=',U.shape) - # # print('sing.val.=',D.round(5)) - # # print('Knullspace=',Knullspace.round(5)) - # # print('Mnullspace=',Mnullspace.round(5)) - # # print('nullspace=',nullspace.round(3)) - - # [eigenValuesUnsorted, eigenVectorsReduced] = eigh(Knullspace,Mnullspace) - # if useAbsoluteValues: - # sortIndices = np.argsort(abs(eigenValuesUnsorted)) #get resorting index - # eigenValues = np.sort(a=abs(eigenValuesUnsorted)) #eigh returns unsorted eigenvalues... - # else: - # sortIndices = np.argsort(eigenValuesUnsorted) #get resorting index - # eigenValues = np.sort(a=eigenValuesUnsorted) #eigh returns unsorted eigenvalues... - - # if numberOfEigenvalues > 0: - # eigenValues = eigenValues[0:numberOfEigenvalues] - # sortIndices = sortIndices[0:numberOfEigenvalues] - # eigenVectorsReduced = eigenVectorsReduced[:,sortIndices] #eigenvectors are given in columns! - - # eigenVectors = nullspace.T @ eigenVectorsReduced - - - # #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - # #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - - - - - - - - - - - - - - - - - + #exu.StopRenderer() #safely close rendering window! + from exudyn.signalProcessing import ComputeFFT + from exudyn.plot import PlotFFT + data = mbs.GetSensorStoredData(sensPosN) + [freq, amp, phase] = ComputeFFT(data[:,0], data[:,1]) + PlotFFT(freq, amp) + #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ if True: from exudyn.interactive import AnimateModes [values, systemEigenVectors] = mbs.ComputeODE2Eigenvalues() diff --git a/docs/RST/Examples/serialRobotInverseKinematics.rst b/docs/RST/Examples/serialRobotInverseKinematics.rst index 368a4e41..15b9dfde 100644 --- a/docs/RST/Examples/serialRobotInverseKinematics.rst +++ b/docs/RST/Examples/serialRobotInverseKinematics.rst @@ -35,6 +35,7 @@ You can view and download this file on Github: `serialRobotInverseKinematics.py import numpy as np + exu.RequireVersion('1.6.31') # exuVersion = np.array(exu.__version__.split('.')[:3], dtype=int) exuVersion = exu.__version__.split('.')[:3] exuVersion = exuVersion[0] + exuVersion[1] + exuVersion[2] @@ -46,7 +47,7 @@ You can view and download this file on Github: `serialRobotInverseKinematics.py #%% ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ #motion planning: jointSpaceInterpolation = False #false interpolates TCP position in work space/Cartesian coordinates - motionCase = 1 # case 1 and 2 move in different planes + motionCase = 2 # case 1 and 2 move in different planes #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ @@ -166,6 +167,14 @@ You can view and download this file on Github: `serialRobotInverseKinematics.py sJoints = mbs.AddSensor(SensorNode(nodeNumber=robotDict['nodeGeneric'], storeInternal=True, outputVariableType=exu.OutputVariableType.Coordinates)) + sPosTCP = mbs.AddSensor(SensorKinematicTree(objectNumber=oKT, linkNumber=5, localPosition=HT2translation(HTtool), + storeInternal=True, + outputVariableType=exu.OutputVariableType.Position)) + + sRotTCP = mbs.AddSensor(SensorKinematicTree(objectNumber=oKT, linkNumber=5, localPosition=HT2translation(HTtool), + storeInternal=True, + outputVariableType=exu.OutputVariableType.RotationMatrix)) + #user function which is called only once per step, speeds up simulation drastically def PreStepUF(mbs, t): if not jointSpaceInterpolation: @@ -215,6 +224,15 @@ You can view and download this file on Github: `serialRobotInverseKinematics.py SC.visualizationSettings.openGL.shadow=0.3 SC.visualizationSettings.openGL.perspective=0.5 + #traces: + SC.visualizationSettings.sensors.traces.listOfPositionSensors = [sPosTCP] + SC.visualizationSettings.sensors.traces.listOfTriadSensors =[sRotTCP] + SC.visualizationSettings.sensors.traces.showPositionTrace=True + SC.visualizationSettings.sensors.traces.showTriads=True + SC.visualizationSettings.sensors.traces.showVectors=False + SC.visualizationSettings.sensors.traces.showFuture=False + SC.visualizationSettings.sensors.traces.triadsShowEvery=5 + #%% tEnd = 5 # endtime of the simulation h = 0.002 #500 steps take 0.16 seconds, 0.3ms / step (83% Python + inverse kinematics) diff --git a/docs/RST/Examples/shapeOptimization.rst b/docs/RST/Examples/shapeOptimization.rst index 8280df19..33e43812 100644 --- a/docs/RST/Examples/shapeOptimization.rst +++ b/docs/RST/Examples/shapeOptimization.rst @@ -212,9 +212,9 @@ You can view and download this file on Github: `shapeOptimization.py minimize ... + return 140 + min(-100,-fMin) #maximize eigenfrequency => minimize ... except: - return -99 + return 140-99 @@ -237,26 +237,38 @@ You can view and download this file on Github: `shapeOptimization.py `_); Example given in \ ``Examples/springDamperUserFunctionNumbaJIT.py``\ showing speedups of factor 4; more complicated Python functions may see speedups of 10 - 50 diff --git a/docs/RST/GettingStarted.rst b/docs/RST/GettingStarted.rst index 04bf8f6f..a62bb4ab 100644 --- a/docs/RST/GettingStarted.rst +++ b/docs/RST/GettingStarted.rst @@ -29,16 +29,17 @@ For details on the interaction of nodes, objects, markers and loads see Section There are several journal papers of the developers which were using Exudyn (list may be incomplete): -+ A. Zwölfer, J. Gerstmayr. A concise nodal-based derivation of the floating frame of reference formulation for displacement-based solid finite elements, Journal of Multibody System Dynamics, Vol. 49(3), pp. 291 -- 313, 2020. -+ S. Holzinger, J. Schöberl, J. Gerstmayr. The equations of motion for a rigid body using non-redundant unified local velocity coordinates. Multibody System Dynamics, Vol. 48, pp. 283 -- 309, 2020. -+ S. Holzinger, J. Gerstmayr. Time integration of rigid bodies modelled with three rotation parameters, Multibody System Dynamics, Vol. 53(5), 2021. -+ A. Zwölfer, J. Gerstmayr. The nodal-based floating frame of reference formulation with modal reduction. Acta Mechanica, Vol. 232, pp. 835--851 (2021). -+ M. Pieber, K. Ntarladima, R. Winkler, J. Gerstmayr. A Hybrid ALE Formulation for the Investigation of the Stability of Pipes Conveying Fluid and Axially Moving Beams, ASME Journal of Computational and Nonlinear Dynamics, 2022. -+ S. Holzinger, M. Schieferle, C. Gutmann, M. Hofer, J. Gerstmayr. Modeling and Parameter Identification for a Flexible Rotor with Impacts. Journal of Computational and Nonlinear Dynamics, 2022. -+ R. Neurauter, J. Gerstmayr. A novel motion reconstruction method for inertial sensors with constraints, Multibody System Dynamics, 2022. + J. Gerstmayr. Exudyn -- A C++ based Python package for flexible multibody systems. Preprint, Research Square, 2023. \ `https://doi.org/10.21203/rs.3.rs-2693700/v1 `_\ ++ P. Manzl, O. Rogov, J. Gerstmayr, A. Mikkola, G. Orzechowski. Reliability Evaluation of Reinforcement Learning Methods for Mechanical Systems with Increasing Complexity. Preprint, Research Square, 2023. \ `https://doi.org/10.21203/rs.3.rs-3066420/v1 `_\ + S. Holzinger, M. Arnold, J. Gerstmayr. Evaluation and Implementation of Lie Group Integration Methods for Rigid Multibody Systems. Preprint, Research Square, 2023. \ `https://doi.org/10.21203/rs.3.rs-2715112/v1 `_\ + M. Sereinig, P. Manzl, and J. Gerstmayr. Task Dependent Comfort Zone, a Base Placement Strategy for Autonomous Mobile Manipulators using Manipulability Measures, Robotics and Autonomous Systems, submitted. ++ R. Neurauter, J. Gerstmayr. A novel motion reconstruction method for inertial sensors with constraints, Multibody System Dynamics, 2022. ++ M. Pieber, K. Ntarladima, R. Winkler, J. Gerstmayr. A Hybrid ALE Formulation for the Investigation of the Stability of Pipes Conveying Fluid and Axially Moving Beams, ASME Journal of Computational and Nonlinear Dynamics, 2022. ++ S. Holzinger, M. Schieferle, C. Gutmann, M. Hofer, J. Gerstmayr. Modeling and Parameter Identification for a Flexible Rotor with Impacts. Journal of Computational and Nonlinear Dynamics, 2022. ++ S. Holzinger, J. Gerstmayr. Time integration of rigid bodies modelled with three rotation parameters, Multibody System Dynamics, Vol. 53(5), 2021. ++ A. Zwölfer, J. Gerstmayr. The nodal-based floating frame of reference formulation with modal reduction. Acta Mechanica, Vol. 232, pp. 835--851 (2021). ++ A. Zwölfer, J. Gerstmayr. A concise nodal-based derivation of the floating frame of reference formulation for displacement-based solid finite elements, Journal of Multibody System Dynamics, Vol. 49(3), pp. 291 -- 313, 2020. ++ S. Holzinger, J. Schöberl, J. Gerstmayr. The equations of motion for a rigid body using non-redundant unified local velocity coordinates. Multibody System Dynamics, Vol. 48, pp. 283 -- 309, 2020. diff --git a/docs/RST/InstallationInstructions.rst b/docs/RST/InstallationInstructions.rst index 5c6a7c47..5c2a6a54 100644 --- a/docs/RST/InstallationInstructions.rst +++ b/docs/RST/InstallationInstructions.rst @@ -16,7 +16,7 @@ Exudyn only works with Python. Thus, you need an appropriate Python installation So far (2021-07), we tested + \ **Anaconda 2021-11, 64bit, Python 3.9**\ \ (older Anaconda3 versions can be downloaded via the repository archive \ ``https://repo.anaconda.com/archive/``\ ) -+ Currently, we work with Python 3.6 - Python 3.10 \ **conda environments**\ on Windows, Linux and MacOS (3.8-3.10). ++ Currently, we work with Python 3.6 - Python 3.11 \ **conda environments**\ on Windows, Linux and MacOS (3.8-3.10). + \ **Spyder 5.1.5**\ (with Python 3.9.7, 64bit) and \ **Spyder 4.1.3**\ (with Python 3.7.7, 64bit), which is included in the Anaconda installation\ (Note that it is important that Spyder, Python and Exudyn are \ **either**\ 32bit \ **or**\ 64bit and are compiled up to the same minor version, i.e., 3.7.x. There will be a strange .DLL error, if you mix up 32/64bit. It is possible to install both, Anaconda 32bit and Anaconda 64bit -- then you should follow the recommendations of paths as suggested by Anaconda installer.); Spyder works with all virtual environments Many alternative options exist: @@ -42,7 +42,7 @@ If you do not install Anaconda (e.g., under Linux), make sure that you have the You can install most of these packages using \ ``pip install numpy``\ (Windows) or \ ``pip3 install numpy``\ (Linux). NOTE: as there is only \ ``numpy``\ needed (but not for all sub-packages) and \ ``numpy``\ supports many variants, we do not add a particular requirement for installation of depending packages. It is not necessary to install \ ``scipy``\ as long as you are not using features of \ ``scipy``\ . Same reason for \ ``tkinter``\ and \ ``matplotlib``\ . -For interaction (right-mouse-click, some key-board commands) you need the Python module \ ``tkinter``\ . This is included in regular Anaconda distributions (recommended, see below), but on UBUNTU you need to type alike (do not forget the '3', otherwise it installs for Python2 ...): +For interaction (right-mouse-click, some key-board commands) you need the Python module \ ``tkinter``\ . This is included in regular Anaconda distributions (recommended, see below), but on Ubuntu you need to type alike (do not forget the '3', otherwise it installs for Python2 ...): \ ``sudo apt-get install python3-tk``\ @@ -59,48 +59,78 @@ Pre-built versions of Exudyn are hosted on \ ``pypi.org``\ , see the project + `https://pypi.org/project/exudyn `_ -As with most other packages, in the regular case (if your binary has been pre-built) you just need to do\ (If the index of pypi is not updated, it may help to use \ ``pip install -i https://pypi.org/project/ exudyn``\ ) +As with most other packages, in the regular case (if your binary has been pre-built) you just need to do \ ``pip install exudyn``\ -On Linux (currently only pre-built for UBUNTU, but should work on many other linux platforms), \ **update pip to at least 20.3**\ and use +On Ubuntu/Linux, make sure that pip is installed and up-to-date (\ **update pip to at least 20.3**\ ; otherwise the manylinux wheels will not be accepted!): + + \ ``sudo apt install python3-pip``\ + \ ``python3 -m pip install --upgrade``\ + +Depending on installation the command may read \ ``pip3``\ or \ ``pip``\ : \ ``pip3 install exudyn``\ -For pre-releases (use with care!), add '\ :math:`--`\ pre' flag: +For pre-releases (use with care!), add \ ``--pre``\ flag: + + \ ``pip install exudyn --pre -U``\ + +The \ ``-U``\ (identical to \ ``--upgrade``\ ) flag ensures that the current installed version is also updated in case of a change of the micro version (e.g., from version 1.6.119 to version 1.6.164), otherwise, it will only update if you switch to a newer minor version. + +In some cases (e.g. for AppleM1 or special Linux versions), your pre-built binary will not work due to some incompatibilities. Then you need to build from source as described in the 'Build and install' sections, Section :ref:`sec-install-installinstructions-buildwindows`\ . + + +Troubleshooting pip install +^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Pip install may fail, if your linux version does not support the current manylinux version. +This is known for CentOS or simlilar systems which usually support manylinux2014. In this case, you have to build Exudyn from source, see Section :ref:`sec-install-installinstructions-buildubuntu`\ . - \ ``pip install exudyn \ :math:`--`\ pre``\ +Sometimes, you install exudyn, but when running python, the \ ``import exudyn``\ fails. +In case of several environments, check where your installation goes. To guarantee that the pip install goes to the python call, use: + + \ ``python -m pip install exudyn``\ + +which ensures that the used python is calling its associated pip module. + +If the PyPi index is not updated, it may help to use + + \ ``pip install -i https://pypi.org/project/ exudyn``\ -In some cases (e.g. for AppleM1), your pre-built binary will not work due to some incompatibilities. Then you need to build from source as described in the 'Build and install' sections, Section :ref:`sec-install-installinstructions-buildwindows`\ . .. _sec-install-installinstructions-wheel: -Install from specific Wheel (UBUNTU and Windows) +Install from specific Wheel (Ubuntu and Windows) ------------------------------------------------ A way to install the Python package Exudyn is to use the so-called 'wheels' (file ending \ ``.whl``\ ). +NOTE that this approach usually is not required; just use the pip installer of the previous section! + +\ **Ubuntu**\ : + Wheels can be downloaded directly from `https://pypi.org/project/exudyn/\#files `_, for many Python versions and architectures. -For UBUNTU18.04 (which by default uses Python 3.6) this may read (version number 1.0.20 may be different): +For Ubuntu 18.04 (which by default uses Python 3.6) this may read (version number 1.0.20 may be different): + \ ``Python 3.6, 64bit``\ : pip3 install dist\ :math:`\backslash`\ exudyn-1.0.20-cp36-cp36-linux_x86_64.whl -For UBUNTU20.04 (which by default uses Python 3.8) this may read (version number 1.0.20 may be different): +For Ubuntu 20.04 (which by default uses Python 3.8) this may read (version number 1.0.20 may be different): + \ ``Python 3.8, 64bit``\ : pip3 install dist\ :math:`\backslash`\ exudyn-1.0.20-cp38-cp38-linux_x86_64.whl NOTE that your installation may have environments with different Python versions, so install that Exudyn version appropriately! -If the wheel installation does not work on UBUNTU, it is highly recommended to build Exudyn for your specific system as given in Section :ref:`sec-install-installinstructions-buildubuntu`\ . +If the wheel installation does not work on Ubuntu, it is highly recommended to build Exudyn for your specific system as given in Section :ref:`sec-install-installinstructions-buildubuntu`\ . \ **Windows**\ : First, open an Anaconda prompt: + EITHER calling: START->Anaconda->... OR go to anaconda/Scripts folder and call activate.bat -+ You can check your Python version then, by running \ ``python``\ \ (\ ``python3``\ under UBUNTU 18.04), the output reads like: ++ You can check your Python version then, by running \ ``python``\ \ (\ ``python3``\ under Ubuntu 18.04), the output reads like: \ ``Python 3.6.5 \ :math:`|`\ Anaconda, Inc.\ :math:`|`\ (default, Mar 29 2018, 13:32:41) \ :math:`[`\ MSC v.1900 64 bit (AMD64)\ :math:`]`\ on win32``\ ... @@ -209,10 +239,10 @@ in order to interact with the render window, as there is only a single-threaded .. _sec-install-installinstructions-buildubuntu: -Build and install Exudyn under UBUNTU? +Build and install Exudyn under Ubuntu? -------------------------------------- -Having a new UBUNTU 18.04 standard installation (e.g. using a VM virtual box environment), the following steps need to be done (Python \ **3.6**\ is already installed on UBUNTU18.04, otherwise use \ ``sudo apt install python3``\ )\ (see also the youtube video: `https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg_jtl6fx `_): +Having a new Ubuntu 18.04 standard installation (e.g. using a VM virtual box environment), the following steps need to be done (Python \ **3.6**\ is already installed on Ubuntu 18.04, otherwise use \ ``sudo apt install python3``\ )\ (see also the youtube video: `https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg_jtl6fx `_): First update ... @@ -224,7 +254,7 @@ First update ... -Install necessary Python libraries and pip3; \ ``matplotlib``\ and\ ``scipy``\ are not required for installation but used in Exudyn examples: +Install necessary Python libraries and pip3; \ ``matplotlib``\ and \ ``scipy``\ are not required for installation but used in Exudyn examples: .. code-block:: @@ -244,14 +274,30 @@ Install pybind11 (needed for running the setup.py file derived from the pybind11 +To have dialogs enabled, you need to install \ ``Tk``\ /\ ``tkinter``\ (may be already installed in your case). +\ ``Tk``\ is installed on Ubuntu via apt-get and should then be available in Python: + +.. code-block:: -If graphics is used (\ ``\#define USE_GLFW_GRAPHICS``\ in \ ``BasicDefinitions.h``\ ), you must install the according GLFW and OpenGL libs: + sudo apt-get install python3-tk + + + + +If graphics is used (\ ``\#define USE_GLFW_GRAPHICS``\ in \ ``BasicDefinitions.h``\ ), you must install the according GLFW libs: + +.. code-block:: + + sudo apt-get install libglfw3 libglfw3-dev + + + +In some cases, it may be required to install OpenGL and some of the following libraries: .. code-block:: sudo apt-get install freeglut3 freeglut3-dev sudo apt-get install mesa-common-dev - sudo apt-get install libglfw3 libglfw3-dev sudo apt-get install libx11-dev xorg-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev @@ -271,7 +317,7 @@ Congratulation! \ **Now, run a test example**\ (will also open an OpenGL window \ ``python3 pythonDev/Examples/rigid3Dexample.py``\ -You can also create a UBUNTU wheel which can be easily installed on the same machine (x64), same operating system (UBUNTU18.04) and with same Python version (e.g., 3.6): +You can also create a Ubuntu wheel which can be easily installed on the same machine (x64), same operating system (Ubuntu 18.04) and with same Python version (e.g., 3.6): \ ``sudo pip3 install wheel``\ \ ``sudo python3 setup.py bdist_wheel --parallel``\ @@ -279,12 +325,13 @@ You can also create a UBUNTU wheel which can be easily installed on the same mac \ **Exudyn under Ubuntu / WSL**\ : -+ Note that Exudyn also nicely works under WSL (Windows subsystem for linux; tested for Ubuntu18.04) and an according xserver (VcXsrv). -+ Just set the display variable in your .bashrc file accordingly and you can enjoy the OpenGL windows and settings. ++ Note that Exudyn also nicely works under WSL (Windows subsystem for linux; tested for Ubuntu 18.04) and an according xserver (VcXsrv). ++ In case of old WSL2, just set the display variable in your .bashrc file accordingly and you can enjoy the OpenGL windows and settings. + It shall be noted that WSL + xserver works better than on MacOS, even for tkinter, multitasking, etc.! So, if you have troubles with your Mac, use a virtual machine with ubuntu and a xserver, that may do better ++ In case of WSLg (since 2021), only the software-OpenGL works; therefore, you have to set (possibly in .bashrc file): \ ``export LIBGL_ALWAYS_SOFTWARE=0``\ -\ **Exudyn under Raspberry Pi 4b**\ : +\ **Exudyn under RaspberryPi 4b**\ : + Exudyn also compiles under RaspberryPi 4b, Ubuntu Mate 20.04, Python 3.8; current version should compile out of the box using \ ``python3 setup.py install``\ command. + Performance is quite ok and it is even capable to use all cores (but you should add a fan!) @@ -294,7 +341,7 @@ You can also create a UBUNTU wheel which can be easily installed on the same mac \ **KNOWN issues for linux builds**\ : + Using \ **WSL2**\ (Windows subsystem for linux), there occur some conflicts during build because of incompatible windows and linux file systems and builds will not be copied to the dist folder; workaround: go to explorer, right click on 'build' directory and set all rights for authenticated user to 'full access' -+ \ **compiler (gcc,g++) conflicts**\ : It seems that Exudyn works well on UBUNTU18.04 with the original \ ``Python 3.6.9``\ and \ ``gcc-7.5.0``\ version as well as with UBUNTU20.04 with \ ``Python 3.8.5``\ and \ ``gcc-9.3.0``\ . Upgrading \ ``gcc``\ on a linux system with Python 3.6 to, e.g., \ ``gcc-8.2``\ showed us a linker error when loading the Exudyn module in Python -- there are some common restriction using \ ``gcc``\ versions different from those with which the Python version has been built. Starting \ ``python``\ or \ ``python3``\ on your linux machine shows you the \ ``gcc``\ version it had been build with. Check your current \ ``gcc``\ version with: \ ``gcc --version``\ ++ \ **compiler (gcc,g++) conflicts**\ : It seems that Exudyn works well on Ubuntu 18.04 with the original \ ``Python 3.6.9``\ and \ ``gcc-7.5.0``\ version as well as with Ubuntu 20.04 with \ ``Python 3.8.5``\ and \ ``gcc-9.3.0``\ . Upgrading \ ``gcc``\ on a Linux system with Python 3.6 to, e.g., \ ``gcc-8.2``\ showed us a linker error when loading the Exudyn module in Python -- there are some common restriction using \ ``gcc``\ versions different from those with which the Python version has been built. Starting \ ``python``\ or \ ``python3``\ on your linux machine shows you the \ ``gcc``\ version it had been build with. Check your current \ ``gcc``\ version with: \ ``gcc --version``\ @@ -309,7 +356,7 @@ To uninstall exudyn under Windows, run (may require admin rights): \ ``pip uninstall exudyn``\ -To uninstall under UBUNTU, run: +To uninstall under Ubuntu, run: \ ``sudo pip3 uninstall exudyn``\ @@ -337,5 +384,5 @@ In order to make full usage of the C++ code and extending it, you can use: + link it to your own code + NOTE: on Linux systems, you mostly need to replace '\ :math:`/`\ ' with '\ :math:`\backslash`\ ' -+ Linux, etc.: not fully supported yet; however, all external libraries are Linux-compatible and thus should run with minimum adaptation efforts. ++ Linux, etc.: Use the build methods described above; Visual Studio Code may allow native Python and C++ debugging; switching to other build mechanisms (CMakeLists or scikit-build-core). diff --git a/docs/RST/RigidBodyAndJointsTutorial.rst b/docs/RST/RigidBodyAndJointsTutorial.rst index 6cce82f2..1c28505b 100644 --- a/docs/RST/RigidBodyAndJointsTutorial.rst +++ b/docs/RST/RigidBodyAndJointsTutorial.rst @@ -274,8 +274,7 @@ which results in the following output (shortened): Sometimes it is hard to understand the degree of freedom for the constrained system. Furthermore, we may have added -- by error -- -redundant constraints, which are not solvable or at least cause solver problems. Both can be checked with the command -\ ````\ : +redundant constraints, which are not solvable or at least cause solver problems. Both can be checked with the command: .. code-block:: python @@ -349,7 +348,7 @@ while solution can be viewed using the \ ``SolutionViewer()``\ . With \ ``solutionWritePeriod``\ you can adjust the frequency which is used to store the solution of the whole model, which may lead to very large files and may slow down simulation, but is used in the \ ``SolutionViewer()``\ to reload the solution after simulation. -In order to improve visualization, there are hundreds of options, see Visualization settings in Section :ref:`sec-vsettingsgeneral`\ , some of them used here: +In order to improve visualization, there are hundreds of options, see Visualization settings in Section :ref:`sec-visualizationsettingsmain`\ , some of them used here: .. code-block:: python diff --git a/docs/RST/TestModels/mainSystemExtensionsTests.rst b/docs/RST/TestModels/mainSystemExtensionsTests.rst index 07be120f..12624cd0 100644 --- a/docs/RST/TestModels/mainSystemExtensionsTests.rst +++ b/docs/RST/TestModels/mainSystemExtensionsTests.rst @@ -50,8 +50,8 @@ You can view and download this file on Github: `mainSystemExtensionsTests.py 0 and i < len(posList)-1: - Lref += r*pi + #note that in this test example, Lref is slightly too long, leading to negative spring forces (compression) if not treated nonlinearly with default settings in ReevingSystemSprings + Lref += r*pi #0.8*r*pi would always lead to tension #mR = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bR, localPosition=[0,-r,0])) #mbs.AddLoad(Force(markerNumber=mR, loadVector=[0,-inertiaRoll.mass*9.81,0])) @@ -134,9 +135,11 @@ You can view and download this file on Github: `reevingSystemSpringsTest.py `__\ (\ ``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 simulation - | \ ``rowIncrement``\ : 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 second - | \ ``runOnStart``\ : immediately go into 'Run' mode - | \ ``runMode``\ : 0=continuous run, 1=one cycle, 2=static (use slider/mouse to vary time steps) - | \ ``fontSize``\ : define font size for labels in InteractiveDialog - | \ ``title``\ : if empty, it uses default; otherwise define specific title - | \ ``checkRenderEngineStopFlag``\ : 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*\ : - -.. code-block:: python - - #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), \ `beltDriveALE.py `_\ (Ex), \ `beltDriveReevingSystem.py `_\ (Ex), \ `beltDrivesComparison.py `_\ (Ex), \ `ACFtest.py `_\ (TM), \ `ANCFbeltDrive.py `_\ (TM), \ `ANCFgeneralContactCircle.py `_\ (TM) - + referencePosition = [1,0,0], + gravity = [0,0,-9.81]) .. _sec-mainsystemextensions-createmasspoint: Function: CreateMassPoint ^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateMassPoint `__\ (\ ``name = ''``\ , \ ``referenceCoordinates = [0.,0.,0.]``\ , \ ``initialCoordinates = [0.,0.,0.]``\ , \ ``initialVelocities = [0.,0.,0.]``\ , \ ``physicsMass = 0``\ , \ ``gravity = [0.,0.,0.]``\ , \ ``graphicsDataList = []``\ , \ ``drawSize = -1``\ , \ ``color = [-1.,-1.,-1.,-1.]``\ , \ ``show = True``\ , \ ``create2D = False``\ , \ ``returnDict = False``\ ) +`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:'+name - | \ ``referenceCoordinates``\ : reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) - | \ ``initialCoordinates``\ : initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) - | \ ``initialVelocities``\ : initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) + | \ ``referencePosition``\ : 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 point | \ ``gravity``\ : gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) | \ ``graphicsDataList``\ : list of GraphicsData for optional mass visualization @@ -205,8 +158,8 @@ Function: CreateMassPoint import numpy as np SC = exu.SystemContainer() mbs = SC.AddSystem() - b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], - initialVelocities = [2,5,0], + b0=mbs.CreateMassPoint(referencePosition = [0,0,0], + initialVelocity = [2,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) mbs.Assemble() @@ -218,7 +171,7 @@ Function: CreateMassPoint Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + \ `chatGPTupdate.py `_\ (Ex), \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) @@ -275,7 +228,7 @@ Function: CreateRigidBody Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `rigidBodyTutorial3withMarkers.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM) + \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM) @@ -312,8 +265,8 @@ Function: CreateSpringDamper import numpy as np SC = exu.SystemContainer() mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) oGround = mbs.AddObject(ObjectGround()) @@ -333,7 +286,7 @@ Function: CreateSpringDamper Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + \ `chatGPTupdate.py `_\ (Ex), \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) @@ -368,7 +321,7 @@ Function: CreateCartesianSpringDamper import numpy as np SC = exu.SystemContainer() mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], + b0 = mbs.CreateMassPoint(referencePosition = [7,0,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) oGround = mbs.AddObject(ObjectGround()) @@ -387,7 +340,7 @@ Function: CreateCartesianSpringDamper Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM) + \ `chatGPTupdate.py `_\ (Ex), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM) @@ -476,7 +429,7 @@ Function: CreateRevoluteJoint Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `addRevoluteJoint.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `solutionViewerTest.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `perf3DRigidBodies.py `_\ (TM) + \ `addRevoluteJoint.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `solutionViewerTest.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `perf3DRigidBodies.py `_\ (TM) @@ -529,7 +482,7 @@ Function: CreatePrismaticJoint Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `addPrismaticJoint.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + \ `addPrismaticJoint.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) @@ -677,7 +630,7 @@ Function: CreateDistanceConstraint gravity = [0,-9.81,0], graphicsDataList = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], color=color4orange)]) - m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], + m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], physicsMass=1, drawSize = 0.2) n1 = mbs.GetObject(m1)['nodeNumber'] oGround = mbs.AddObject(ObjectGround()) @@ -700,7 +653,70 @@ Function: CreateDistanceConstraint Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `mainSystemExtensionsTests.py `_\ (TM) + \ `chatGPTupdate.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + + +.. _sec-mainsystem-pythonextensions: + + +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``\ + +.. code-block:: python + :linenos: + + #this example sketches the usage + #for complete examples see Examples/ or TestModels/ folders + #create some multibody system (mbs) first: + # ... + # + #compute system degree of freedom: + mbs.ComputeSystemDegreeOfFreedom(verbose=True) + # + #call solver function directly from mbs: + mbs.SolveDynamic(exu.SimulationSettings()) + # + #plot sensor directly from mbs: + mbs.PlotSensor(...) + + +.. _sec-mainsystemextensions-solutionviewer: + +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 simulation + | \ ``rowIncrement``\ : 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 second + | \ ``runOnStart``\ : immediately go into 'Run' mode + | \ ``runMode``\ : 0=continuous run, 1=one cycle, 2=static (use slider/mouse to vary time steps) + | \ ``fontSize``\ : define font size for labels in InteractiveDialog + | \ ``title``\ : if empty, it uses default; otherwise define specific title + | \ ``checkRenderEngineStopFlag``\ : 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*\ : + +.. code-block:: python + + #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), \ `beltDriveALE.py `_\ (Ex), \ `beltDriveReevingSystem.py `_\ (Ex), \ `beltDrivesComparison.py `_\ (Ex), \ `ACFtest.py `_\ (TM), \ `ANCFbeltDrive.py `_\ (TM), \ `ANCFgeneralContactCircle.py `_\ (TM) @@ -708,7 +724,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: 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``\ ) +`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. @@ -749,6 +765,8 @@ Function: PlotSensor | \ ``[*kwargs]``\ : | \ ``minorTicksXon``\ : if True, turn minor ticks for x-axis on | \ ``minorTicksYon``\ : if True, turn minor ticks for y-axis on + | \ ``logScaleX``\ : use log scale for x-axis + | \ ``logScaleY``\ : use log scale for y-axis | \ ``fileCommentChar``\ : if exists, defines the comment character in files (\#, | \ ``fileDelimiterChar``\ : if exists, defines the character indicating the columns for data (',', ' ', ';', ...) - | \ *output*\ : @@ -913,8 +931,8 @@ Function: ComputeLinearizedSystem SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # @@ -971,8 +989,8 @@ Function: ComputeODE2Eigenvalues SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # diff --git a/docs/RST/confHelper.py b/docs/RST/confHelper.py index af7bdc47..0a6b0c94 100644 --- a/docs/RST/confHelper.py +++ b/docs/RST/confHelper.py @@ -3,5 +3,5 @@ listClassNames=['SystemContainer', 'MainSystem', 'SystemData', 'GeneralContact', 'VisuGeneralContact', 'MatrixContainer', 'Vector3DList', 'Vector2DList', 'Vector6DList', 'Matrix3DList', 'Matrix6DList', 'SimulationSettings', 'OutputVariableType', 'ConfigurationType', 'ItemType', 'Node', 'Joint', 'DynamicSolverType', 'CrossSectionType', 'KeyCode', 'LinearSolverType', 'Contact', ] -listFunctionNames=['GetVersionString', 'Help', 'RequireVersion', 'StartRenderer', 'StopRenderer', 'IsRendererActive', 'DoRendererIdleTasks', 'SolveStatic', 'SolveDynamic', 'ComputeODE2Eigenvalues', 'SetOutputPrecision', 'SetLinalgOutputFormatPython', 'SetWriteToConsole', 'SetWriteToFile', 'SetPrintDelayMilliSeconds', 'Print', 'SuppressWarnings', 'InfoStat', 'Go', 'InvalidIndex', 'Reset', 'AddSystem', 'NumberOfSystems', 'GetSystem', 'GetRenderState', 'SetRenderState', 'RedrawAndSaveImage', 'WaitForRenderEngineStopFlag', 'RenderEngineZoomAll', 'AttachToRenderEngine', 'DetachFromRenderEngine', 'SendRedrawSignal', 'GetCurrentMouseCoordinates', 'Assemble', 'AssembleCoordinates', 'AssembleLTGLists', 'AssembleInitializeSystemCoordinates', 'AssembleSystemInitialize', 'GetSystemContainer', 'WaitForUserToContinue', 'GetRenderEngineStopFlag', 'SetRenderEngineStopFlag', 'ActivateRendering', 'SetPreStepUserFunction', 'SetPostNewtonUserFunction', 'AddGeneralContact', 'GetGeneralContact', 'DeleteGeneralContact', 'NumberOfGeneralContacts', '__repr__', 'AddNode', 'GetNodeNumber', 'GetNode', 'ModifyNode', 'GetNodeDefaults', 'GetNodeOutput', 'GetNodeODE2Index', 'GetNodeODE1Index', 'GetNodeAEIndex', 'GetNodeParameter', 'SetNodeParameter', 'AddObject', 'GetObjectNumber', 'GetObject', 'ModifyObject', 'GetObjectDefaults', 'GetObjectOutput', 'GetObjectOutputBody', 'GetObjectOutputSuperElement', 'GetObjectParameter', 'SetObjectParameter', 'AddMarker', 'GetMarkerNumber', 'GetMarker', 'ModifyMarker', 'GetMarkerDefaults', 'GetMarkerParameter', 'SetMarkerParameter', 'GetMarkerOutput', 'AddLoad', 'GetLoadNumber', 'GetLoad', 'ModifyLoad', 'GetLoadDefaults', 'GetLoadValues', 'GetLoadParameter', 'SetLoadParameter', 'AddSensor', 'GetSensorNumber', 'GetSensor', 'ModifySensor', 'GetSensorDefaults', 'GetSensorValues', 'GetSensorStoredData', 'GetSensorParameter', 'SetSensorParameter', 'NumberOfLoads', 'NumberOfMarkers', 'NumberOfNodes', 'NumberOfObjects', 'NumberOfSensors', 'ODE2Size', 'ODE1Size', 'AEsize', 'DataSize', 'SystemSize', 'GetTime', 'SetTime', 'AddODE2LoadDependencies', 'Info', 'InfoLTG', 'GetODE2Coordinates', 'SetODE2Coordinates', 'GetODE2Coordinates_t', 'SetODE2Coordinates_t', 'GetODE2Coordinates_tt', 'SetODE2Coordinates_tt', 'GetODE1Coordinates', 'SetODE1Coordinates', 'GetODE1Coordinates_t', 'SetODE1Coordinates_t', 'GetAECoordinates', 'SetAECoordinates', 'GetDataCoordinates', 'SetDataCoordinates', 'GetSystemState', 'SetSystemState', 'GetObjectLTGODE2', 'GetObjectLTGODE1', 'GetObjectLTGAE', 'GetObjectLTGData', 'GetNodeLTGODE2', 'GetNodeLTGODE1', 'GetNodeLTGAE', 'GetNodeLTGData', 'GetPythonObject', 'SetFrictionPairings', 'SetFrictionProportionalZone', 'SetSearchTreeCellSize', 'SetSearchTreeBox', 'AddSphereWithMarker', 'AddANCFCable', 'AddTrianglesRigidBodyBased', 'GetItemsInBox', 'GetMarkerBasedSphere', 'ShortestDistanceAlongLine', 'UpdateContacts', 'GetActiveContacts', 'SetWithDenseMatrix', 'SetWithSparseMatrixCSR', 'Convert2DenseMatrix', 'UseDenseMatrix', 'Append', '__len__', '__setitem__', '__getitem__', 'visualizationSettings', 'systemData', 'systemIsConsistent', 'interactiveMode', ] +listFunctionNames=['GetVersionString', 'Help', 'RequireVersion', 'StartRenderer', 'StopRenderer', 'IsRendererActive', 'DoRendererIdleTasks', 'SolveStatic', 'SolveDynamic', 'ComputeODE2Eigenvalues', 'SetOutputPrecision', 'SetLinalgOutputFormatPython', 'SetWriteToConsole', 'SetWriteToFile', 'SetPrintDelayMilliSeconds', 'Print', 'SuppressWarnings', 'InfoStat', 'Go', 'InvalidIndex', 'Reset', 'AddSystem', 'NumberOfSystems', 'GetSystem', 'GetRenderState', 'SetRenderState', 'RedrawAndSaveImage', 'WaitForRenderEngineStopFlag', 'RenderEngineZoomAll', 'AttachToRenderEngine', 'DetachFromRenderEngine', 'SendRedrawSignal', 'GetCurrentMouseCoordinates', 'Assemble', 'AssembleCoordinates', 'AssembleLTGLists', 'AssembleInitializeSystemCoordinates', 'AssembleSystemInitialize', 'GetSystemContainer', 'WaitForUserToContinue', 'GetRenderEngineStopFlag', 'SetRenderEngineStopFlag', 'ActivateRendering', 'SetPreStepUserFunction', 'SetPostNewtonUserFunction', 'AddGeneralContact', 'GetGeneralContact', 'DeleteGeneralContact', 'NumberOfGeneralContacts', '__repr__', 'AddNode', 'GetNodeNumber', 'GetNode', 'ModifyNode', 'GetNodeDefaults', 'GetNodeOutput', 'GetNodeODE2Index', 'GetNodeODE1Index', 'GetNodeAEIndex', 'GetNodeParameter', 'SetNodeParameter', 'AddObject', 'GetObjectNumber', 'GetObject', 'ModifyObject', 'GetObjectDefaults', 'GetObjectOutput', 'GetObjectOutputBody', 'GetObjectOutputSuperElement', 'GetObjectParameter', 'SetObjectParameter', 'AddMarker', 'GetMarkerNumber', 'GetMarker', 'ModifyMarker', 'GetMarkerDefaults', 'GetMarkerParameter', 'SetMarkerParameter', 'GetMarkerOutput', 'AddLoad', 'GetLoadNumber', 'GetLoad', 'ModifyLoad', 'GetLoadDefaults', 'GetLoadValues', 'GetLoadParameter', 'SetLoadParameter', 'AddSensor', 'GetSensorNumber', 'GetSensor', 'ModifySensor', 'GetSensorDefaults', 'GetSensorValues', 'GetSensorStoredData', 'GetSensorParameter', 'SetSensorParameter', 'NumberOfLoads', 'NumberOfMarkers', 'NumberOfNodes', 'NumberOfObjects', 'NumberOfSensors', 'ODE2Size', 'ODE1Size', 'AEsize', 'DataSize', 'SystemSize', 'GetTime', 'SetTime', 'AddODE2LoadDependencies', 'Info', 'InfoLTG', 'GetODE2Coordinates', 'SetODE2Coordinates', 'GetODE2Coordinates_t', 'SetODE2Coordinates_t', 'GetODE2Coordinates_tt', 'SetODE2Coordinates_tt', 'GetODE1Coordinates', 'SetODE1Coordinates', 'GetODE1Coordinates_t', 'SetODE1Coordinates_t', 'GetAECoordinates', 'SetAECoordinates', 'GetDataCoordinates', 'SetDataCoordinates', 'GetSystemState', 'SetSystemState', 'GetObjectLTGODE2', 'GetObjectLTGODE1', 'GetObjectLTGAE', 'GetObjectLTGData', 'GetNodeLTGODE2', 'GetNodeLTGODE1', 'GetNodeLTGAE', 'GetNodeLTGData', 'GetPythonObject', 'SetFrictionPairings', 'SetFrictionProportionalZone', 'SetSearchTreeCellSize', 'SetSearchTreeBox', 'AddSphereWithMarker', 'AddANCFCable', 'AddTrianglesRigidBodyBased', 'GetItemsInBox', 'GetMarkerBasedSphere', 'ShortestDistanceAlongLine', 'UpdateContacts', 'GetActiveContacts', 'SetWithDenseMatrix', 'SetWithSparseMatrixCSR', 'Convert2DenseMatrix', 'UseDenseMatrix', 'Append', '__len__', '__setitem__', '__getitem__', '__copy__', '__deepcopy__', 'visualizationSettings', 'systemData', 'systemIsConsistent', 'interactiveMode', ] diff --git a/docs/RST/confHelperPyUtilities.py b/docs/RST/confHelperPyUtilities.py index 45b66344..b52cd5c5 100644 --- a/docs/RST/confHelperPyUtilities.py +++ b/docs/RST/confHelperPyUtilities.py @@ -1,7 +1,7 @@ #this is a helper file to define additional keywords for examples #Created: 2023-03-17, Johannes Gerstmayr -listPyFunctionNames=['CreateMBS', 'SetupSpaces', 'MapAction2MBS', 'Output2StateAndDone', 'State2InitialValues', 'TestModel', 'SetSolver', 'PreInitializeSolver', 'IntegrateStep', 'step', 'reset', 'render', 'close', 'ClearWorkspace', 'DiagonalMatrix', 'NormL2', 'VSum', 'VAdd', 'VSub', 'VMult', 'ScalarMult', 'Normalize', 'Vec2Tilde', 'Tilde2Vec', 'GaussIntegrate', 'LobattoIntegrate', 'GenerateStraightLineANCFCable2D', 'GenerateCircularArcANCFCable2D', 'CreateReevingCurve', 'PointsAndSlopes2ANCFCable2D', 'GenerateSlidingJoint', 'GenerateAleSlidingJoint', 'CompressedRowSparseToDenseMatrix', 'MapSparseMatrixIndices', 'VectorDiadicUnitMatrix3D', 'CyclicCompareReversed', 'AddEntryToCompressedRowSparseArray', 'CSRtoRowsAndColumns', 'CSRtoScipySparseCSR', 'ScipySparseCSRtoCSR', 'ResortIndicesOfCSRmatrix', 'ResortIndicesOfNGvector', 'ResortIndicesExudyn2NGvector', 'ConvertHexToTrigs', 'ConvertTetToTrigs', 'ConvertDenseToCompressedRowMatrix', 'ReadMatrixFromAnsysMMF', 'ReadMatrixDOFmappingVectorFromAnsysTxt', 'ReadNodalCoordinatesFromAnsysTxt', 'ReadElementsFromAnsysTxt', 'CMSObjectComputeNorm', 'Strain2Stress', 'StrainVector2StressVector', 'StrainVector2StressVector2D', 'LameParameters', 'AddObjectFFRF', 'UFforce', 'UFmassGenericODE2', 'SaveToFile', 'LoadFromFile', 'AddObjectFFRFreducedOrderWithUserFunctions', 'UFmassFFRFreducedOrder', 'UFforceFFRFreducedOrder', 'AddObjectFFRFreducedOrder', 'ImportFromAbaqusInputFile', 'ReadMassMatrixFromAbaqus', 'ReadStiffnessMatrixFromAbaqus', 'ImportMeshFromNGsolve', 'ComputeEigenmodesNGsolve', 'ComputeHurtyCraigBamptonModesNGsolve', 'ComputePostProcessingModesNGsolve', 'GetMassMatrix', 'GetStiffnessMatrix', 'NumberOfNodes', 'GetNodePositionsAsArray', 'GetNodePositionsMean', 'NumberOfCoordinates', 'GetNodeAtPoint', 'GetNodesInPlane', 'GetNodesInCube', 'GetNodesOnLine', 'GetNodesOnCylinder', 'GetNodesOnCircle', 'GetNodeWeightsFromSurfaceAreas', 'GetSurfaceTriangles', 'VolumeToSurfaceElements', 'GetGyroscopicMatrix', 'ScaleMassMatrix', 'ScaleStiffnessMatrix', 'AddElasticSupportAtNode', 'AddNodeMass', 'CreateLinearFEMObjectGenericODE2', 'CreateNonlinearFEMObjectGenericODE2NGsolve', 'ComputeEigenmodes', 'ComputeEigenModesWithBoundaryNodes', 'ComputeHurtyCraigBamptonModes', 'GetEigenFrequenciesHz', 'ComputePostProcessingModes', 'ComputeCampbellDiagram', 'CheckConsistency', 'ReadMassMatrixFromAnsys', 'ReadStiffnessMatrixFromAnsys', 'ReadNodalCoordinatesFromAnsys', 'ReadElementsFromAnsys', 'SwitchTripletOrder', 'ComputeTriangleNormal', 'ComputeTriangleArea', 'GraphicsData2PointsAndTrigs', 'GraphicsDataFromPointsAndTrigs', 'RefineMesh', 'ShrinkMeshNormalToSurface', 'MoveGraphicsData', 'MergeGraphicsDataTriangleList', 'GraphicsDataLine', 'GraphicsDataCircle', 'GraphicsDataText', 'GraphicsDataRectangle', 'GraphicsDataOrthoCubeLines', 'GraphicsDataOrthoCube', 'GraphicsDataOrthoCubePoint', 'GraphicsDataCube', 'GraphicsDataSphere', 'GraphicsDataCylinder', 'GraphicsDataRigidLink', 'GraphicsDataFromSTLfileTxt', 'GraphicsDataFromSTLfile', 'AddEdgesAndSmoothenNormals', 'ExportGraphicsData2STL', 'GraphicsDataSolidOfRevolution', 'GraphicsDataArrow', 'GraphicsDataBasis', 'GraphicsDataFrame', 'GraphicsDataQuad', 'GraphicsDataCheckerBoard', 'ComputeTriangularMesh', 'SegmentsFromPoints', 'CirclePointsAndSegments', 'GraphicsDataSolidExtrusion', 'GetTkRootAndNewWindow', 'TkRootExists', 'EditDictionaryWithTypeInfo', 'AnimateModes', 'SolutionViewer', 'OnQuit', 'StartSimulation', 'ProcessWidgetStates', 'ContinuousRunFunction', 'InitializePlots', 'UpdatePlots', 'InitializeSolver', 'FinalizeSolver', 'RunSimulationPeriod', 'MassCOMinertia2T66', 'Inertia2T66', 'Inertia66toMassCOMinertia', 'JointTransformMotionSubspace66', 'JointTransformMotionSubspace', 'CRM', 'CRF', 'Size', 'XL', 'ForwardDynamicsCRB', 'ComputeMassMatrixAndForceTerms', 'AddExternalForces', 'Sinc', 'Cot', 'R3xSO3Matrix2RotationMatrix', 'R3xSO3Matrix2Translation', 'R3xSO3Matrix', 'ExpSO3', 'ExpS3', 'LogSO3', 'TExpSO3', 'TExpSO3Inv', 'ExpSE3', 'LogSE3', 'TExpSE3', 'TExpSE3Inv', 'ExpR3xSO3', 'TExpR3xSO3', 'TExpR3xSO3Inv', 'CompositionRuleDirectProductR3AndS3', 'CompositionRuleSemiDirectProductR3AndS3', 'CompositionRuleDirectProductR3AndR3RotVec', 'CompositionRuleSemiDirectProductR3AndR3RotVec', 'CompositionRuleDirectProductR3AndR3RotXYZAngles', 'CompositionRuleSemiDirectProductR3AndR3RotXYZAngles', 'CompositionRuleForEulerParameters', 'CompositionRuleForRotationVectors', 'CompositionRuleRotXYZAnglesRotationVector', 'CreateMassPoint', 'CreateRigidBody', 'CreateSpringDamper', 'CreateCartesianSpringDamper', 'CreateRigidBodySpringDamper', 'CreateRevoluteJoint', 'CreatePrismaticJoint', 'CreateSphericalJoint', 'CreateGenericJoint', 'CreateDistanceConstraint', 'StribeckFunction', 'RegularizedFrictionStep', 'RegularizedFriction', 'VonMisesStress', 'UFvonMisesStress', 'ParseOutputFileHeader', 'PlotSensorDefaults', 'PlotSensor', 'PlotFFT', 'FileStripSpaces', 'DataArrayFromSensorList', 'LoadImage', 'PlotImage', 'GetVersionPlatformString', 'ProcessParameterList', 'ParameterVariation', 'GeneticOptimization', 'Minimize', 'ComputeSensitivities', 'PlotOptimizationResults2D', 'PlotSensitivityResults', 'ComputeOrthonormalBasisVectors', 'ComputeOrthonormalBasis', 'GramSchmidt', 'Skew', 'Skew2Vec', 'ComputeSkewMatrix', 'EulerParameters2G', 'EulerParameters2GLocal', 'EulerParameters2RotationMatrix', 'RotationMatrix2EulerParameters', 'AngularVelocity2EulerParameters_t', 'RotationVector2RotationMatrix', 'RotationMatrix2RotationVector', 'ComputeRotationAxisFromRotationVector', 'RotationVector2G', 'RotationVector2GLocal', 'RotXYZ2RotationMatrix', 'RotationMatrix2RotXYZ', 'RotXYZ2G', 'RotXYZ2G_t', 'RotXYZ2GLocal', 'RotXYZ2GLocal_t', 'AngularVelocity2RotXYZ_t', 'RotXYZ2EulerParameters', 'RotationMatrix2RotZYZ', 'RotationMatrixX', 'RotationMatrixY', 'RotationMatrixZ', 'HomogeneousTransformation', 'HTtranslate', 'HTtranslateX', 'HTtranslateY', 'HTtranslateZ', 'HT0', 'HTrotateX', 'HTrotateY', 'HTrotateZ', 'HT2translation', 'HT2rotationMatrix', 'InverseHT', 'RotationX2T66', 'RotationY2T66', 'RotationZ2T66', 'Translation2T66', 'TranslationX2T66', 'TranslationY2T66', 'TranslationZ2T66', 'T66toRotationTranslation', 'InverseT66toRotationTranslation', 'RotationTranslation2T66', 'RotationTranslation2T66Inverse', 'T66toHT', 'HT2T66Inverse', 'InertiaTensor2Inertia6D', 'Inertia6D2InertiaTensor', 'StrNodeType2NodeType', 'GetRigidBodyNode', 'AddRigidBody', 'AddRevoluteJoint', 'AddPrismaticJoint', 'SetWithCOMinertia', 'Inertia', 'InertiaCOM', 'COM', 'Mass', 'Translated', 'Rotated', 'Transformed', 'GetInertia6D', 'StdDH2HT', 'ModDHKK2HT', 'projectAngleToPMPi', 'SetPDcontrol', 'HasPDcontrol', 'GetPDcontrol', 'AddLink', 'IsSerialRobot', 'GetLink', 'HasParent', 'GetParentIndex', 'NumberOfLinks', 'GetBaseHT', 'GetToolHT', 'LinkHT', 'JointHT', 'COMHT', 'StaticTorques', 'Jacobian', 'CreateKinematicTree', 'CreateRedundantCoordinateMBS', 'GetKinematicTree66', 'GetLinkGraphicsData', 'BuildFromDictionary', 'GetCurrentRobotHT', 'InterpolateHTs', 'SolveSafe', 'Solve', 'MakeCorkeRobot', 'ComputeIK3R', 'ComputeIKPuma560', 'ComputeIKUR', 'Manipulator4Rsimple', 'Manipulator3RSimple', 'ManipulatorPANDA', 'ManipulatorUR5', 'ManipulatorPuma560', 'LinkDict2Robot', 'LinkDictModDHKK2Robot', 'GetBasicProfile', 'GetFinalCoordinates', 'Add', 'GetTimes', 'Initialize', 'Evaluate', 'EvaluateCoordinate', 'VelocityManipulability', 'ForceManipulability', 'StiffnessManipulability', 'JointJacobian', 'MassMatrix', 'DynamicManipulability', 'CalculateAllMeasures', 'AddLidar', 'FilterSensorOutput', 'FilterSignal', 'ComputeFFT', 'GetInterpolatedSignalValue', 'SolverErrorMessage', 'SolveStatic', 'SolveDynamic', 'SolverSuccess', 'ComputeLinearizedSystem', 'ComputeODE2Eigenvalues', 'ComputeSystemDegreeOfFreedom', 'CheckSolverInfoStatistics', 'ShowOnlyObjects', 'HighlightItem', '__UFsensorDistance', 'CreateDistanceSensorGeometry', 'CreateDistanceSensor', 'UFsensorRecord', 'AddSensorRecorder', 'LoadSolutionFile', 'NumpyInt8ArrayToString', 'BinaryReadIndex', 'BinaryReadReal', 'BinaryReadString', 'BinaryReadArrayIndex', 'BinaryReadRealVector', 'LoadBinarySolutionFile', 'RecoverSolutionFile', 'InitializeFromRestartFile', 'SetSolutionState', 'AnimateSolution', 'DrawSystemGraph', 'CreateTCPIPconnection', 'TCPIPsendReceive', 'CloseTCPIPconnection', ] +listPyFunctionNames=['CreateMBS', 'SetupSpaces', 'MapAction2MBS', 'Output2StateAndDone', 'State2InitialValues', 'TestModel', 'SetSolver', 'PreInitializeSolver', 'IntegrateStep', 'step', 'reset', 'render', 'close', 'ClearWorkspace', 'SmartRound2String', 'DiagonalMatrix', 'NormL2', 'VSum', 'VAdd', 'VSub', 'VMult', 'ScalarMult', 'Normalize', 'Vec2Tilde', 'Tilde2Vec', 'GaussIntegrate', 'LobattoIntegrate', 'GenerateStraightLineANCFCable2D', 'GenerateCircularArcANCFCable2D', 'CreateReevingCurve', 'PointsAndSlopes2ANCFCable2D', 'GenerateSlidingJoint', 'GenerateAleSlidingJoint', 'CompressedRowSparseToDenseMatrix', 'MapSparseMatrixIndices', 'VectorDiadicUnitMatrix3D', 'CyclicCompareReversed', 'AddEntryToCompressedRowSparseArray', 'CSRtoRowsAndColumns', 'CSRtoScipySparseCSR', 'ScipySparseCSRtoCSR', 'ResortIndicesOfCSRmatrix', 'ResortIndicesOfNGvector', 'ResortIndicesExudyn2NGvector', 'ConvertHexToTrigs', 'ConvertTetToTrigs', 'ConvertDenseToCompressedRowMatrix', 'ReadMatrixFromAnsysMMF', 'ReadMatrixDOFmappingVectorFromAnsysTxt', 'ReadNodalCoordinatesFromAnsysTxt', 'ReadElementsFromAnsysTxt', 'CMSObjectComputeNorm', 'Strain2Stress', 'StrainVector2StressVector', 'StrainVector2StressVector2D', 'LameParameters', 'AddObjectFFRF', 'UFforce', 'UFmassGenericODE2', 'SaveToFile', 'LoadFromFile', 'AddObjectFFRFreducedOrderWithUserFunctions', 'UFmassFFRFreducedOrder', 'UFforceFFRFreducedOrder', 'AddObjectFFRFreducedOrder', 'ImportFromAbaqusInputFile', 'ReadMassMatrixFromAbaqus', 'ReadStiffnessMatrixFromAbaqus', 'ImportMeshFromNGsolve', 'ComputeEigenmodesNGsolve', 'ComputeHurtyCraigBamptonModesNGsolve', 'ComputePostProcessingModesNGsolve', 'GetMassMatrix', 'GetStiffnessMatrix', 'NumberOfNodes', 'GetNodePositionsAsArray', 'GetNodePositionsMean', 'NumberOfCoordinates', 'GetNodeAtPoint', 'GetNodesInPlane', 'GetNodesInCube', 'GetNodesOnLine', 'GetNodesOnCylinder', 'GetNodesOnCircle', 'GetNodeWeightsFromSurfaceAreas', 'GetSurfaceTriangles', 'VolumeToSurfaceElements', 'GetGyroscopicMatrix', 'ScaleMassMatrix', 'ScaleStiffnessMatrix', 'AddElasticSupportAtNode', 'AddNodeMass', 'CreateLinearFEMObjectGenericODE2', 'CreateNonlinearFEMObjectGenericODE2NGsolve', 'ComputeEigenmodes', 'ComputeEigenModesWithBoundaryNodes', 'ComputeHurtyCraigBamptonModes', 'GetEigenFrequenciesHz', 'ComputePostProcessingModes', 'ComputeCampbellDiagram', 'CheckConsistency', 'ReadMassMatrixFromAnsys', 'ReadStiffnessMatrixFromAnsys', 'ReadNodalCoordinatesFromAnsys', 'ReadElementsFromAnsys', 'SwitchTripletOrder', 'ComputeTriangleNormal', 'ComputeTriangleArea', 'GraphicsData2PointsAndTrigs', 'GraphicsDataFromPointsAndTrigs', 'RefineMesh', 'ShrinkMeshNormalToSurface', 'MoveGraphicsData', 'MergeGraphicsDataTriangleList', 'GraphicsDataLine', 'GraphicsDataCircle', 'GraphicsDataText', 'GraphicsDataRectangle', 'GraphicsDataOrthoCubeLines', 'GraphicsDataOrthoCube', 'GraphicsDataOrthoCubePoint', 'GraphicsDataCube', 'GraphicsDataSphere', 'GraphicsDataCylinder', 'GraphicsDataRigidLink', 'GraphicsDataFromSTLfileTxt', 'GraphicsDataFromSTLfile', 'AddEdgesAndSmoothenNormals', 'ExportGraphicsData2STL', 'GraphicsDataSolidOfRevolution', 'GraphicsDataArrow', 'GraphicsDataBasis', 'GraphicsDataFrame', 'GraphicsDataQuad', 'GraphicsDataCheckerBoard', 'ComputeTriangularMesh', 'SegmentsFromPoints', 'CirclePointsAndSegments', 'GraphicsDataSolidExtrusion', 'GetTkRootAndNewWindow', 'TkRootExists', 'EditDictionaryWithTypeInfo', 'AnimateModes', 'SolutionViewer', 'OnQuit', 'StartSimulation', 'ProcessWidgetStates', 'ContinuousRunFunction', 'InitializePlots', 'UpdatePlots', 'InitializeSolver', 'FinalizeSolver', 'RunSimulationPeriod', 'MassCOMinertia2T66', 'Inertia2T66', 'Inertia66toMassCOMinertia', 'JointTransformMotionSubspace66', 'JointTransformMotionSubspace', 'CRM', 'CRF', 'Size', 'XL', 'ForwardDynamicsCRB', 'ComputeMassMatrixAndForceTerms', 'AddExternalForces', 'Sinc', 'Cot', 'R3xSO3Matrix2RotationMatrix', 'R3xSO3Matrix2Translation', 'R3xSO3Matrix', 'ExpSO3', 'ExpS3', 'LogSO3', 'TExpSO3', 'TExpSO3Inv', 'ExpSE3', 'LogSE3', 'TExpSE3', 'TExpSE3Inv', 'ExpR3xSO3', 'TExpR3xSO3', 'TExpR3xSO3Inv', 'CompositionRuleDirectProductR3AndS3', 'CompositionRuleSemiDirectProductR3AndS3', 'CompositionRuleDirectProductR3AndR3RotVec', 'CompositionRuleSemiDirectProductR3AndR3RotVec', 'CompositionRuleDirectProductR3AndR3RotXYZAngles', 'CompositionRuleSemiDirectProductR3AndR3RotXYZAngles', 'CompositionRuleForEulerParameters', 'CompositionRuleForRotationVectors', 'CompositionRuleRotXYZAnglesRotationVector', 'CreateMassPoint', 'CreateRigidBody', 'CreateSpringDamper', 'CreateCartesianSpringDamper', 'CreateRigidBodySpringDamper', 'CreateRevoluteJoint', 'CreatePrismaticJoint', 'CreateSphericalJoint', 'CreateGenericJoint', 'CreateDistanceConstraint', 'StribeckFunction', 'RegularizedFrictionStep', 'RegularizedFriction', 'VonMisesStress', 'UFvonMisesStress', 'ParseOutputFileHeader', 'PlotSensorDefaults', 'PlotSensor', 'PlotFFT', 'FileStripSpaces', 'DataArrayFromSensorList', 'LoadImage', 'PlotImage', 'GetVersionPlatformString', 'ProcessParameterList', 'ParameterVariation', 'GeneticOptimization', 'Minimize', 'ComputeSensitivities', 'PlotOptimizationResults2D', 'PlotSensitivityResults', 'ComputeOrthonormalBasisVectors', 'ComputeOrthonormalBasis', 'GramSchmidt', 'Skew', 'Skew2Vec', 'ComputeSkewMatrix', 'EulerParameters2G', 'EulerParameters2GLocal', 'EulerParameters2RotationMatrix', 'RotationMatrix2EulerParameters', 'AngularVelocity2EulerParameters_t', 'RotationVector2RotationMatrix', 'RotationMatrix2RotationVector', 'ComputeRotationAxisFromRotationVector', 'RotationVector2G', 'RotationVector2GLocal', 'RotXYZ2RotationMatrix', 'RotationMatrix2RotXYZ', 'RotXYZ2G', 'RotXYZ2G_t', 'RotXYZ2GLocal', 'RotXYZ2GLocal_t', 'AngularVelocity2RotXYZ_t', 'RotXYZ2EulerParameters', 'RotationMatrix2RotZYZ', 'RotationMatrixX', 'RotationMatrixY', 'RotationMatrixZ', 'HomogeneousTransformation', 'HTtranslate', 'HTtranslateX', 'HTtranslateY', 'HTtranslateZ', 'HT0', 'HTrotateX', 'HTrotateY', 'HTrotateZ', 'HT2translation', 'HT2rotationMatrix', 'InverseHT', 'RotationX2T66', 'RotationY2T66', 'RotationZ2T66', 'Translation2T66', 'TranslationX2T66', 'TranslationY2T66', 'TranslationZ2T66', 'T66toRotationTranslation', 'InverseT66toRotationTranslation', 'RotationTranslation2T66', 'RotationTranslation2T66Inverse', 'T66toHT', 'HT2T66Inverse', 'InertiaTensor2Inertia6D', 'Inertia6D2InertiaTensor', 'StrNodeType2NodeType', 'GetRigidBodyNode', 'AddRigidBody', 'AddRevoluteJoint', 'AddPrismaticJoint', 'SetWithCOMinertia', 'Inertia', 'InertiaCOM', 'COM', 'Mass', 'Translated', 'Rotated', 'Transformed', 'GetInertia6D', 'StdDH2HT', 'ModDHKK2HT', 'projectAngleToPMPi', 'SetPDcontrol', 'HasPDcontrol', 'GetPDcontrol', 'AddLink', 'IsSerialRobot', 'GetLink', 'HasParent', 'GetParentIndex', 'NumberOfLinks', 'GetBaseHT', 'GetToolHT', 'LinkHT', 'JointHT', 'COMHT', 'StaticTorques', 'Jacobian', 'CreateKinematicTree', 'CreateRedundantCoordinateMBS', 'GetKinematicTree66', 'GetLinkGraphicsData', 'BuildFromDictionary', 'GetCurrentRobotHT', 'InterpolateHTs', 'SolveSafe', 'Solve', 'MakeCorkeRobot', 'ComputeIK3R', 'ComputeIKPuma560', 'ComputeIKUR', 'Manipulator4Rsimple', 'Manipulator3RSimple', 'ManipulatorPANDA', 'ManipulatorUR5', 'ManipulatorPuma560', 'LinkDict2Robot', 'LinkDictModDHKK2Robot', 'GetBasicProfile', 'GetFinalCoordinates', 'Add', 'GetTimes', 'Initialize', 'Evaluate', 'EvaluateCoordinate', 'VelocityManipulability', 'ForceManipulability', 'StiffnessManipulability', 'JointJacobian', 'MassMatrix', 'DynamicManipulability', 'CalculateAllMeasures', 'AddLidar', 'FilterSensorOutput', 'FilterSignal', 'ComputeFFT', 'GetInterpolatedSignalValue', 'SolverErrorMessage', 'SolveStatic', 'SolveDynamic', 'SolverSuccess', 'ComputeLinearizedSystem', 'ComputeODE2Eigenvalues', 'ComputeSystemDegreeOfFreedom', 'CheckSolverInfoStatistics', 'ShowOnlyObjects', 'HighlightItem', '__UFsensorDistance', 'CreateDistanceSensorGeometry', 'CreateDistanceSensor', 'UFsensorRecord', 'AddSensorRecorder', 'LoadSolutionFile', 'NumpyInt8ArrayToString', 'BinaryReadIndex', 'BinaryReadReal', 'BinaryReadString', 'BinaryReadArrayIndex', 'BinaryReadRealVector', 'LoadBinarySolutionFile', 'RecoverSolutionFile', 'InitializeFromRestartFile', 'SetSolutionState', 'AnimateSolution', 'DrawSystemGraph', 'CreateTCPIPconnection', 'TCPIPsendReceive', 'CloseTCPIPconnection', ] listPyClassNames=['OpenAIGymInterfaceEnv', 'MaterialBaseClass', 'KirchhoffMaterial', 'FiniteElement', 'Tet4', 'ObjectFFRFinterface', 'ObjectFFRFreducedOrderInterface', 'HCBstaticModeSelection', 'FEMinterface', 'InteractiveDialog', 'KinematicTree33', 'KinematicTree66', 'RigidBodyInertia', 'InertiaCuboid', 'InertiaRodX', 'InertiaMassPoint', 'InertiaSphere', 'InertiaHollowSphere', 'InertiaCylinder', 'VRobotLink', 'RobotLink', 'VRobotTool', 'RobotTool', 'VRobotBase', 'RobotBase', 'Robot', 'InverseKinematicsNumerical', 'ProfileConstantAcceleration', 'ProfileLinearAccelerationsList', 'ProfilePTP', 'Trajectory', 'TCPIPdata', ] diff --git a/docs/RST/items/LoadForceVector.rst b/docs/RST/items/LoadForceVector.rst index 96d178f6..e0ed23a2 100644 --- a/docs/RST/items/LoadForceVector.rst +++ b/docs/RST/items/LoadForceVector.rst @@ -95,7 +95,7 @@ A user function, which computes the force vector depending on time and object pa Relevant Examples and TestModels with weblink: - \ `addPrismaticJoint.py `_\ (Examples/), \ `addRevoluteJoint.py `_\ (Examples/), \ `interactiveTutorial.py `_\ (Examples/), \ `pendulumVerify.py `_\ (Examples/), \ `solutionViewerTest.py `_\ (Examples/), \ `SpringDamperMassUserFunction.py `_\ (Examples/), \ `springDamperTutorialNew.py `_\ (Examples/), \ `ANCFcantileverTest.py `_\ (Examples/), \ `ANCFcantileverTestDyn.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `ANCFmovingRigidbody.py `_\ (Examples/), \ `perf3DRigidBodies.py `_\ (TestModels/), \ `plotSensorTest.py `_\ (TestModels/), \ `revoluteJointPrismaticJointTest.py `_\ (TestModels/) + \ `addPrismaticJoint.py `_\ (Examples/), \ `addRevoluteJoint.py `_\ (Examples/), \ `interactiveTutorial.py `_\ (Examples/), \ `pendulumVerify.py `_\ (Examples/), \ `ROSExampleMassPoint.py `_\ (Examples/), \ `solutionViewerTest.py `_\ (Examples/), \ `SpringDamperMassUserFunction.py `_\ (Examples/), \ `springDamperTutorialNew.py `_\ (Examples/), \ `ANCFcantileverTest.py `_\ (Examples/), \ `ANCFcantileverTestDyn.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `perf3DRigidBodies.py `_\ (TestModels/), \ `plotSensorTest.py `_\ (TestModels/), \ `revoluteJointPrismaticJointTest.py `_\ (TestModels/) diff --git a/docs/RST/items/LoadMassProportional.rst b/docs/RST/items/LoadMassProportional.rst index 24590997..a2462b02 100644 --- a/docs/RST/items/LoadMassProportional.rst +++ b/docs/RST/items/LoadMassProportional.rst @@ -95,7 +95,7 @@ MINI EXAMPLE for LoadMassProportional #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[2] diff --git a/docs/RST/items/MarkerBodyRigid.rst b/docs/RST/items/MarkerBodyRigid.rst index 34b55424..1c706603 100644 --- a/docs/RST/items/MarkerBodyRigid.rst +++ b/docs/RST/items/MarkerBodyRigid.rst @@ -40,7 +40,7 @@ DESCRIPTION of MarkerBodyRigid Relevant Examples and TestModels with weblink: - \ `addPrismaticJoint.py `_\ (Examples/), \ `addRevoluteJoint.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `ANCFslidingJoint2D.py `_\ (Examples/), \ `ANCFtestHalfcircle.py `_\ (Examples/), \ `ANCFtests2.py `_\ (Examples/), \ `beltDriveALE.py `_\ (Examples/), \ `beltDriveReevingSystem.py `_\ (Examples/), \ `beltDrivesComparison.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `CMSexampleCourse.py `_\ (Examples/), \ `abaqusImportTest.py `_\ (TestModels/), \ `ACFtest.py `_\ (TestModels/), \ `ANCFbeltDrive.py `_\ (TestModels/) + \ `addPrismaticJoint.py `_\ (Examples/), \ `addRevoluteJoint.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `ANCFslidingJoint2D.py `_\ (Examples/), \ `ANCFtestHalfcircle.py `_\ (Examples/), \ `ANCFtests2.py `_\ (Examples/), \ `beltDriveALE.py `_\ (Examples/), \ `beltDriveReevingSystem.py `_\ (Examples/), \ `beltDrivesComparison.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `chatGPTupdate.py `_\ (Examples/), \ `abaqusImportTest.py `_\ (TestModels/), \ `ACFtest.py `_\ (TestModels/), \ `ANCFbeltDrive.py `_\ (TestModels/) diff --git a/docs/RST/items/MarkerSuperElementPosition.rst b/docs/RST/items/MarkerSuperElementPosition.rst index 210606d3..85fdbd17 100644 --- a/docs/RST/items/MarkerSuperElementPosition.rst +++ b/docs/RST/items/MarkerSuperElementPosition.rst @@ -136,7 +136,7 @@ MINI EXAMPLE for MarkerSuperElementPosition #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/NodeRigidBodyEP.rst b/docs/RST/items/NodeRigidBodyEP.rst index 8978b274..5a7f767b 100644 --- a/docs/RST/items/NodeRigidBodyEP.rst +++ b/docs/RST/items/NodeRigidBodyEP.rst @@ -129,7 +129,7 @@ see Section :ref:`sec-rigidbodyutilities-addrigidbody`\ , which simplifies the s Relevant Examples and TestModels with weblink: - \ `rigid3Dexample.py `_\ (Examples/), \ `rigidBodyIMUtest.py `_\ (Examples/), \ `rigidRotor3DbasicBehaviour.py `_\ (Examples/), \ `rigidRotor3DFWBW.py `_\ (Examples/), \ `rigidRotor3Dnutation.py `_\ (Examples/), \ `rigidRotor3Drunup.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `craneReevingSystem.py `_\ (Examples/), \ `fourBarMechanism3D.py `_\ (Examples/), \ `gyroStability.py `_\ (Examples/), \ `humanRobotInteraction.py `_\ (Examples/), \ `leggedRobot.py `_\ (Examples/), \ `explicitLieGroupIntegratorPythonTest.py `_\ (TestModels/), \ `explicitLieGroupIntegratorTest.py `_\ (TestModels/), \ `explicitLieGroupMBSTest.py `_\ (TestModels/) + \ `rigid3Dexample.py `_\ (Examples/), \ `rigidBodyIMUtest.py `_\ (Examples/), \ `rigidRotor3DbasicBehaviour.py `_\ (Examples/), \ `rigidRotor3DFWBW.py `_\ (Examples/), \ `rigidRotor3Dnutation.py `_\ (Examples/), \ `rigidRotor3Drunup.py `_\ (Examples/), \ `rr.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `craneReevingSystem.py `_\ (Examples/), \ `fourBarMechanism3D.py `_\ (Examples/), \ `gyroStability.py `_\ (Examples/), \ `humanRobotInteraction.py `_\ (Examples/), \ `explicitLieGroupIntegratorPythonTest.py `_\ (TestModels/), \ `explicitLieGroupIntegratorTest.py `_\ (TestModels/), \ `explicitLieGroupMBSTest.py `_\ (TestModels/) diff --git a/docs/RST/items/ObjectANCFCable2D.rst b/docs/RST/items/ObjectANCFCable2D.rst index 85f6760a..344ae2aa 100644 --- a/docs/RST/items/ObjectANCFCable2D.rst +++ b/docs/RST/items/ObjectANCFCable2D.rst @@ -443,7 +443,7 @@ MINI EXAMPLE for ObjectANCFCable2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveStatic(mbs) + mbs.SolveStatic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(lastNode, exu.OutputVariableType.Displacement)[0] diff --git a/docs/RST/items/ObjectConnectorCartesianSpringDamper.rst b/docs/RST/items/ObjectConnectorCartesianSpringDamper.rst index 018767bf..0b44ce00 100644 --- a/docs/RST/items/ObjectConnectorCartesianSpringDamper.rst +++ b/docs/RST/items/ObjectConnectorCartesianSpringDamper.rst @@ -274,14 +274,14 @@ MINI EXAMPLE for ObjectConnectorCartesianSpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[1] Relevant Examples and TestModels with weblink: - \ `mouseInteractionExample.py `_\ (Examples/), \ `rigid3Dexample.py `_\ (Examples/), \ `sliderCrank3DwithANCFbeltDrive2.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `ANCFslidingJoint2D.py `_\ (Examples/), \ `cartesianSpringDamper.py `_\ (Examples/), \ `flexibleRotor3Dtest.py `_\ (Examples/), \ `lavalRotor2Dtest.py `_\ (Examples/), \ `NGsolvePistonEngine.py `_\ (Examples/), \ `NGsolvePostProcessingStresses.py `_\ (Examples/), \ `objectFFRFreducedOrderNetgen.py `_\ (Examples/), \ `scissorPrismaticRevolute2D.py `_\ (TestModels/), \ `sphericalJointTest.py `_\ (TestModels/), \ `ANCFcontactCircleTest.py `_\ (TestModels/) + \ `mouseInteractionExample.py `_\ (Examples/), \ `rigid3Dexample.py `_\ (Examples/), \ `rr.py `_\ (Examples/), \ `sliderCrank3DwithANCFbeltDrive2.py `_\ (Examples/), \ `ANCFcontactCircle.py `_\ (Examples/), \ `ANCFcontactCircle2.py `_\ (Examples/), \ `ANCFslidingJoint2D.py `_\ (Examples/), \ `cartesianSpringDamper.py `_\ (Examples/), \ `flexibleRotor3Dtest.py `_\ (Examples/), \ `lavalRotor2Dtest.py `_\ (Examples/), \ `NGsolvePistonEngine.py `_\ (Examples/), \ `NGsolvePostProcessingStresses.py `_\ (Examples/), \ `scissorPrismaticRevolute2D.py `_\ (TestModels/), \ `sphericalJointTest.py `_\ (TestModels/), \ `ANCFcontactCircleTest.py `_\ (TestModels/) diff --git a/docs/RST/items/ObjectConnectorCoordinate.rst b/docs/RST/items/ObjectConnectorCoordinate.rst index 435fd3bb..93743d42 100644 --- a/docs/RST/items/ObjectConnectorCoordinate.rst +++ b/docs/RST/items/ObjectConnectorCoordinate.rst @@ -279,7 +279,7 @@ MINI EXAMPLE for ObjectConnectorCoordinate #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[0] diff --git a/docs/RST/items/ObjectConnectorCoordinateSpringDamper.rst b/docs/RST/items/ObjectConnectorCoordinateSpringDamper.rst index a945251e..5f9c9665 100644 --- a/docs/RST/items/ObjectConnectorCoordinateSpringDamper.rst +++ b/docs/RST/items/ObjectConnectorCoordinateSpringDamper.rst @@ -228,7 +228,7 @@ MINI EXAMPLE for ObjectConnectorCoordinateSpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, diff --git a/docs/RST/items/ObjectConnectorDistance.rst b/docs/RST/items/ObjectConnectorDistance.rst index ef41684b..be8350f4 100644 --- a/docs/RST/items/ObjectConnectorDistance.rst +++ b/docs/RST/items/ObjectConnectorDistance.rst @@ -154,7 +154,7 @@ MINI EXAMPLE for ObjectConnectorDistance sims=exu.SimulationSettings() sims.timeIntegration.generalizedAlpha.spectralRadius=0.7 - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectConnectorGravity.rst b/docs/RST/items/ObjectConnectorGravity.rst index 5ad91733..83480398 100644 --- a/docs/RST/items/ObjectConnectorGravity.rst +++ b/docs/RST/items/ObjectConnectorGravity.rst @@ -207,7 +207,7 @@ MINI EXAMPLE for ObjectConnectorGravity mbs.Assemble() sims = exu.SimulationSettings() sims.timeIntegration.endTime = tEnd - exu.SolveDynamic(mbs, sims, solverType=exu.DynamicSolverType.RK67) + mbs.SolveDynamic(sims, solverType=exu.DynamicSolverType.RK67) #check result at default integration time #expect y=x after one period of orbiting (got: 100000.00000000479) diff --git a/docs/RST/items/ObjectConnectorLinearSpringDamper.rst b/docs/RST/items/ObjectConnectorLinearSpringDamper.rst index a0073a6c..530de908 100644 --- a/docs/RST/items/ObjectConnectorLinearSpringDamper.rst +++ b/docs/RST/items/ObjectConnectorLinearSpringDamper.rst @@ -244,7 +244,7 @@ MINI EXAMPLE for ObjectConnectorLinearSpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[0] diff --git a/docs/RST/items/ObjectConnectorReevingSystemSprings.rst b/docs/RST/items/ObjectConnectorReevingSystemSprings.rst index 00e077f2..113afb3d 100644 --- a/docs/RST/items/ObjectConnectorReevingSystemSprings.rst +++ b/docs/RST/items/ObjectConnectorReevingSystemSprings.rst @@ -5,7 +5,7 @@ ObjectConnectorReevingSystemSprings =================================== -A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \ :math:`nr`\ rigid body markers \ :math:`[m_0, \, m_1, \, \ldots, \, m_{nr-1}]`\ . At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \ :math:`m_{c0}`\ and \ :math:`m_{c1}`\ . +A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). NOTE that the spring can undergo tension AND compression (in order to avoid compression, use a PreStepUserFunction to turn off stiffness and damping in this case!). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \ :math:`nr`\ rigid body markers \ :math:`[m_0, \, m_1, \, \ldots, \, m_{nr-1}]`\ . At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \ :math:`m_{c0}`\ and \ :math:`m_{c1}`\ . \ **Additional information for ObjectConnectorReevingSystemSprings**\ : @@ -33,6 +33,8 @@ The item \ **ObjectConnectorReevingSystemSprings**\ with type = 'ConnectorReevi | torsional damping [SI:Nms] between sheaves; this effect can damp rotations around the rope axis, pairwise between sheaves; this parameter is experimental * | **dampingShear** [\ :math:`DS`\ , type = UReal, default = 0.]: | damping of shear motion [SI:Ns] between sheaves; this effect can damp motion perpendicular to the rope between each pair of sheaves; this parameter is experimental +* | **regularizationForce** [\ :math:`F_{reg}`\ , type = Real, default = 0.1]: + | small regularization force [SI:N] in order to avoid large compressive forces; this regularization force can either be \ :math:`<0`\ (using a linear tension/compression spring model) or \ :math:`>0`\ , which restricts forces in the rope to be always \ :math:`\ge -F_{reg}`\ . Note that smaller forces lead to problems in implicit integrators and smaller time steps. For explicit integrators, this force can be chosen close to zero. * | **referenceLength** [\ :math:`L_{ref}`\ , type = Real, default = 0.]: | reference length for computation of roped force * | **sheavesAxes** [\ :math:`{\mathbf{l}}_a = [\LU{m0}{{\mathbf{a}}_0},\, \LU{m1}{{\mathbf{a}}_1},\, \ldots ] in [\Rcal^{3}, ...]`\ , type = Vector3DList, default = []]: @@ -197,13 +199,25 @@ In case that \ ``hasCoordinateMarkers=True``\ , the total reference length and i while we set \ :math:`L_0 = L_{ref}`\ and \ :math:`\dot L_0=0`\ otherwise. -The force in the reeving system (assumed to be constant all over the rope) reads +The linear force in the reeving system (assumed to be constant all over the rope) is computed as .. math:: - F = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} + F_{lin} = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} +The rope force is computed from + +.. math:: + + F = \begin{cases} F_{lin} \quad \mathrm{if} \quad F_{lin} > 0 \\ F_{reg} \cdot \mathrm{tanh}(F_{lin}/F_{reg})\quad \mathrm{else} \end{cases} + + +Which allows small compressive forces \ :math:`F_{reg}`\ . +In case that \ :math:`F_{reg} < 0`\ , compressive forces are not regularized (linear spring). +The case \ :math:`F_{reg} = 0`\ will be used in future only in combination with a data node, +which allows switching similar as in friction and contact elements. + Note that in case of \ :math:`L_0=0`\ , the term \ :math:`\frac{1}{L_0}`\ is replaced by \ :math:`1000`\ . However, this case must be avoided by the user by choosing appropriate parameters for the system. diff --git a/docs/RST/items/ObjectConnectorRigidBodySpringDamper.rst b/docs/RST/items/ObjectConnectorRigidBodySpringDamper.rst index 30d7f4eb..bf9ecee8 100644 --- a/docs/RST/items/ObjectConnectorRigidBodySpringDamper.rst +++ b/docs/RST/items/ObjectConnectorRigidBodySpringDamper.rst @@ -340,14 +340,14 @@ MINI EXAMPLE for ObjectConnectorRigidBodySpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[1] Relevant Examples and TestModels with weblink: - \ `stiffFlyballGovernor2.py `_\ (Examples/), \ `connectorRigidBodySpringDamperTest.py `_\ (TestModels/), \ `rotatingTableTest.py `_\ (TestModels/), \ `stiffFlyballGovernor.py `_\ (TestModels/), \ `superElementRigidJointTest.py `_\ (TestModels/) + \ `ROSExampleMassPoint.py `_\ (Examples/), \ `stiffFlyballGovernor2.py `_\ (Examples/), \ `connectorRigidBodySpringDamperTest.py `_\ (TestModels/), \ `rotatingTableTest.py `_\ (TestModels/), \ `stiffFlyballGovernor.py `_\ (TestModels/), \ `superElementRigidJointTest.py `_\ (TestModels/) diff --git a/docs/RST/items/ObjectConnectorSpringDamper.rst b/docs/RST/items/ObjectConnectorSpringDamper.rst index e652e764..2e875ccb 100644 --- a/docs/RST/items/ObjectConnectorSpringDamper.rst +++ b/docs/RST/items/ObjectConnectorSpringDamper.rst @@ -345,7 +345,7 @@ MINI EXAMPLE for ObjectConnectorSpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectConnectorTorsionalSpringDamper.rst b/docs/RST/items/ObjectConnectorTorsionalSpringDamper.rst index 1f9b5cf4..f80e5030 100644 --- a/docs/RST/items/ObjectConnectorTorsionalSpringDamper.rst +++ b/docs/RST/items/ObjectConnectorTorsionalSpringDamper.rst @@ -251,14 +251,14 @@ MINI EXAMPLE for ObjectConnectorTorsionalSpringDamper #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] Relevant Examples and TestModels with weblink: - \ `serialRobotInteractiveLimits.py `_\ (Examples/), \ `serialRobotKinematicTree.py `_\ (Examples/), \ `serialRobotTSD.py `_\ (Examples/), \ `rotatingTableTest.py `_\ (TestModels/), \ `sliderCrank3Dbenchmark.py `_\ (TestModels/) + \ `ROSExampleTurtle.py `_\ (Examples/), \ `serialRobotInteractiveLimits.py `_\ (Examples/), \ `serialRobotKinematicTree.py `_\ (Examples/), \ `serialRobotTSD.py `_\ (Examples/), \ `rotatingTableTest.py `_\ (TestModels/), \ `sliderCrank3Dbenchmark.py `_\ (TestModels/) diff --git a/docs/RST/items/ObjectGenericODE1.rst b/docs/RST/items/ObjectGenericODE1.rst index 665c5057..d036a52d 100644 --- a/docs/RST/items/ObjectGenericODE1.rst +++ b/docs/RST/items/ObjectGenericODE1.rst @@ -172,7 +172,7 @@ MINI EXAMPLE for ObjectGenericODE1 sims=exu.SimulationSettings() solverType = exu.DynamicSolverType.RK44 - exu.SolveDynamic(mbs, solverType=solverType, simulationSettings=sims) + mbs.SolveDynamic(solverType=solverType, simulationSettings=sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nODE1, exu.OutputVariableType.Coordinates)[0] diff --git a/docs/RST/items/ObjectGenericODE2.rst b/docs/RST/items/ObjectGenericODE2.rst index c3a9fbff..5d91931a 100644 --- a/docs/RST/items/ObjectGenericODE2.rst +++ b/docs/RST/items/ObjectGenericODE2.rst @@ -369,7 +369,7 @@ MINI EXAMPLE for ObjectGenericODE2 #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectGround.rst b/docs/RST/items/ObjectGround.rst index 9b8a04e5..111db7c0 100644 --- a/docs/RST/items/ObjectGround.rst +++ b/docs/RST/items/ObjectGround.rst @@ -138,7 +138,7 @@ inefficient and only designed to enable simpler tests, but not large scale probl sims=exu.SimulationSettings() sims.timeIntegration.numberOfSteps = 10000000 #many steps to see graphics exu.StartRenderer() #perform zoom all (press 'a' several times) after startup to see the sphere - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) exu.StopRenderer() diff --git a/docs/RST/items/ObjectJointRevoluteZ.rst b/docs/RST/items/ObjectJointRevoluteZ.rst index 1b12ef57..b33c8cab 100644 --- a/docs/RST/items/ObjectJointRevoluteZ.rst +++ b/docs/RST/items/ObjectJointRevoluteZ.rst @@ -211,7 +211,7 @@ MINI EXAMPLE for ObjectJointRevoluteZ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] diff --git a/docs/RST/items/ObjectKinematicTree.rst b/docs/RST/items/ObjectKinematicTree.rst index add5a575..93f0b667 100644 --- a/docs/RST/items/ObjectKinematicTree.rst +++ b/docs/RST/items/ObjectKinematicTree.rst @@ -207,7 +207,7 @@ We can compute the local joint angular velocity \ :math:`\tomega_i`\ and transl .. math:: - {\mathbf{v}}^J_i = \vp{\tomega_i}{{\mathbf{w}}_i} = \tPhi_i \, q_i + {\mathbf{v}}^J_i = \vp{\tomega_i}{{\mathbf{w}}_i} = \tPhi_i \, \dot q_i The joint coordinates, which can be rotational or translational, are stored in the vector @@ -396,7 +396,7 @@ MINI EXAMPLE for ObjectKinematicTree simulationSettings = exu.SimulationSettings() #takes currently set values or default values simulationSettings.timeIntegration.numberOfSteps = 1000 #gives very accurate results - exu.SolveDynamic(mbs, simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! + mbs.SolveDynamic(simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! #check final value of angle: q0 = mbs.GetNodeOutput(nGeneric, exu.OutputVariableType.Coordinates) diff --git a/docs/RST/items/ObjectMass1D.rst b/docs/RST/items/ObjectMass1D.rst index 6bbf2978..4c840fda 100644 --- a/docs/RST/items/ObjectMass1D.rst +++ b/docs/RST/items/ObjectMass1D.rst @@ -152,7 +152,7 @@ MINI EXAMPLE for ObjectMass1D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current mass position at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(mass, exu.OutputVariableType.Position, [0,0,0])[0] diff --git a/docs/RST/items/ObjectMassPoint.rst b/docs/RST/items/ObjectMassPoint.rst index c811ffcb..65d9326c 100644 --- a/docs/RST/items/ObjectMassPoint.rst +++ b/docs/RST/items/ObjectMassPoint.rst @@ -132,7 +132,7 @@ MINI EXAMPLE for ObjectMassPoint #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectMassPoint2D.rst b/docs/RST/items/ObjectMassPoint2D.rst index 9a8f987a..5db11215 100644 --- a/docs/RST/items/ObjectMassPoint2D.rst +++ b/docs/RST/items/ObjectMassPoint2D.rst @@ -131,7 +131,7 @@ MINI EXAMPLE for ObjectMassPoint2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectRigidBody.rst b/docs/RST/items/ObjectRigidBody.rst index 478a6dad..ce459b2b 100644 --- a/docs/RST/items/ObjectRigidBody.rst +++ b/docs/RST/items/ObjectRigidBody.rst @@ -334,7 +334,7 @@ see Section :ref:`sec-rigidbodyutilities-addrigidbody`\ , which simplifies the s Relevant Examples and TestModels with weblink: - \ `rigid3Dexample.py `_\ (Examples/), \ `rigidBodyIMUtest.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `craneReevingSystem.py `_\ (Examples/), \ `fourBarMechanism3D.py `_\ (Examples/), \ `gyroStability.py `_\ (Examples/), \ `humanRobotInteraction.py `_\ (Examples/), \ `leggedRobot.py `_\ (Examples/), \ `mouseInteractionExample.py `_\ (Examples/), \ `multiMbsTest.py `_\ (Examples/), \ `openVRengine.py `_\ (Examples/), \ `particleClusters.py `_\ (Examples/), \ `explicitLieGroupIntegratorPythonTest.py `_\ (TestModels/), \ `explicitLieGroupIntegratorTest.py `_\ (TestModels/), \ `explicitLieGroupMBSTest.py `_\ (TestModels/) + \ `rigid3Dexample.py `_\ (Examples/), \ `rigidBodyIMUtest.py `_\ (Examples/), \ `rr.py `_\ (Examples/), \ `bicycleIftommBenchmark.py `_\ (Examples/), \ `craneReevingSystem.py `_\ (Examples/), \ `fourBarMechanism3D.py `_\ (Examples/), \ `gyroStability.py `_\ (Examples/), \ `humanRobotInteraction.py `_\ (Examples/), \ `leggedRobot.py `_\ (Examples/), \ `mouseInteractionExample.py `_\ (Examples/), \ `multiMbsTest.py `_\ (Examples/), \ `openVRengine.py `_\ (Examples/), \ `explicitLieGroupIntegratorPythonTest.py `_\ (TestModels/), \ `explicitLieGroupIntegratorTest.py `_\ (TestModels/), \ `explicitLieGroupMBSTest.py `_\ (TestModels/) diff --git a/docs/RST/items/ObjectRigidBody2D.rst b/docs/RST/items/ObjectRigidBody2D.rst index 908fe9c3..06d3a68d 100644 --- a/docs/RST/items/ObjectRigidBody2D.rst +++ b/docs/RST/items/ObjectRigidBody2D.rst @@ -212,7 +212,7 @@ MINI EXAMPLE for ObjectRigidBody2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/docs/RST/items/ObjectRotationalMass1D.rst b/docs/RST/items/ObjectRotationalMass1D.rst index a5a5aef7..0c1a8686 100644 --- a/docs/RST/items/ObjectRotationalMass1D.rst +++ b/docs/RST/items/ObjectRotationalMass1D.rst @@ -161,7 +161,7 @@ MINI EXAMPLE for ObjectRotationalMass1D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current rotor z-rotation at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(rotor, exu.OutputVariableType.Rotation, [0,0,0]) diff --git a/docs/RST/items/SensorKinematicTree.rst b/docs/RST/items/SensorKinematicTree.rst index 3d9fb1df..b8e906b3 100644 --- a/docs/RST/items/SensorKinematicTree.rst +++ b/docs/RST/items/SensorKinematicTree.rst @@ -45,7 +45,7 @@ DESCRIPTION of SensorKinematicTree Relevant Examples and TestModels with weblink: - \ `serialRobotKinematicTreeDigging.py `_\ (Examples/), \ `stiffFlyballGovernorKT.py `_\ (Examples/), \ `kinematicTreeAndMBStest.py `_\ (TestModels/), \ `kinematicTreeConstraintTest.py `_\ (TestModels/) + \ `serialRobotInverseKinematics.py `_\ (Examples/), \ `serialRobotKinematicTreeDigging.py `_\ (Examples/), \ `stiffFlyballGovernorKT.py `_\ (Examples/), \ `kinematicTreeAndMBStest.py `_\ (TestModels/), \ `kinematicTreeConstraintTest.py `_\ (TestModels/) diff --git a/docs/RST/items/SensorUserFunction.rst b/docs/RST/items/SensorUserFunction.rst index 69434179..4f9be8c0 100644 --- a/docs/RST/items/SensorUserFunction.rst +++ b/docs/RST/items/SensorUserFunction.rst @@ -114,7 +114,7 @@ The user function arguments are as follows: #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() if False: from exudyn.plot import PlotSensor diff --git a/docs/RST/pythonUtilities/FEM.rst b/docs/RST/pythonUtilities/FEM.rst index fa5073c8..0585752c 100644 --- a/docs/RST/pythonUtilities/FEM.rst +++ b/docs/RST/pythonUtilities/FEM.rst @@ -16,7 +16,7 @@ Support functions and helper classes for import of meshes, finite element models Function: CompressedRowSparseToDenseMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CompressedRowSparseToDenseMatrix `__\ (\ ``sparseData``\ ) +`CompressedRowSparseToDenseMatrix `__\ (\ ``sparseData``\ ) - | \ *function description*\ : | convert zero-based sparse matrix data to dense numpy matrix @@ -34,7 +34,7 @@ Function: CompressedRowSparseToDenseMatrix Function: MapSparseMatrixIndices ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`MapSparseMatrixIndices `__\ (\ ``matrix``\ , \ ``sorting``\ ) +`MapSparseMatrixIndices `__\ (\ ``matrix``\ , \ ``sorting``\ ) - | \ *function description*\ : | resort a sparse matrix (internal CSR format) with given sorting for rows and columns; changes matrix directly! used for ANSYS matrix import @@ -48,7 +48,7 @@ Function: MapSparseMatrixIndices Function: VectorDiadicUnitMatrix3D ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`VectorDiadicUnitMatrix3D `__\ (\ ``v``\ ) +`VectorDiadicUnitMatrix3D `__\ (\ ``v``\ ) - | \ *function description*\ : | compute diadic product of vector v and a 3D unit matrix = diadic(v,I\ :math:`_{3x3}`\ ); used for ObjectFFRF and CMS implementation @@ -62,7 +62,7 @@ Function: VectorDiadicUnitMatrix3D Function: CyclicCompareReversed ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CyclicCompareReversed `__\ (\ ``list1``\ , \ ``list2``\ ) +`CyclicCompareReversed `__\ (\ ``list1``\ , \ ``list2``\ ) - | \ *function description*\ : | compare cyclic two lists, reverse second list; return True, if any cyclic shifted lists are same, False otherwise @@ -76,7 +76,7 @@ Function: CyclicCompareReversed Function: AddEntryToCompressedRowSparseArray ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddEntryToCompressedRowSparseArray `__\ (\ ``sparseData``\ , \ ``row``\ , \ ``column``\ , \ ``value``\ ) +`AddEntryToCompressedRowSparseArray `__\ (\ ``sparseData``\ , \ ``row``\ , \ ``column``\ , \ ``value``\ ) - | \ *function description*\ : | add entry to compressedRowSparse matrix, avoiding duplicates @@ -91,7 +91,7 @@ Function: AddEntryToCompressedRowSparseArray Function: CSRtoRowsAndColumns ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CSRtoRowsAndColumns `__\ (\ ``sparseMatrixCSR``\ ) +`CSRtoRowsAndColumns `__\ (\ ``sparseMatrixCSR``\ ) - | \ *function description*\ : | compute rows and columns of a compressed sparse matrix and return as tuple: (rows,columns) @@ -105,7 +105,7 @@ Function: CSRtoRowsAndColumns Function: CSRtoScipySparseCSR ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CSRtoScipySparseCSR `__\ (\ ``sparseMatrixCSR``\ ) +`CSRtoScipySparseCSR `__\ (\ ``sparseMatrixCSR``\ ) - | \ *function description*\ : | convert internal compressed CSR to scipy.sparse csr matrix @@ -123,7 +123,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: ScipySparseCSRtoCSR ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ScipySparseCSRtoCSR `__\ (\ ``scipyCSR``\ ) +`ScipySparseCSRtoCSR `__\ (\ ``scipyCSR``\ ) - | \ *function description*\ : | convert scipy.sparse csr matrix to internal compressed CSR @@ -137,7 +137,7 @@ Function: ScipySparseCSRtoCSR Function: ResortIndicesOfCSRmatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ResortIndicesOfCSRmatrix `__\ (\ ``mXXYYZZ``\ , \ ``numberOfRows``\ ) +`ResortIndicesOfCSRmatrix `__\ (\ ``mXXYYZZ``\ , \ ``numberOfRows``\ ) - | \ *function description*\ : | resort indices of given NGsolve CSR matrix in XXXYYYZZZ format to XYZXYZXYZ format; numberOfRows must be equal to columns @@ -152,7 +152,7 @@ Function: ResortIndicesOfCSRmatrix Function: ResortIndicesOfNGvector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ResortIndicesOfNGvector `__\ (\ ``vXXYYZZ``\ ) +`ResortIndicesOfNGvector `__\ (\ ``vXXYYZZ``\ ) - | \ *function description*\ : | resort indices of given NGsolve vector in XXXYYYZZZ format to XYZXYZXYZ format @@ -166,7 +166,7 @@ Function: ResortIndicesOfNGvector Function: ResortIndicesExudyn2NGvector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ResortIndicesExudyn2NGvector `__\ (\ ``vXYZXYZ``\ ) +`ResortIndicesExudyn2NGvector `__\ (\ ``vXYZXYZ``\ ) - | \ *function description*\ : | resort indices of given Exudyun vector XYZXYZXYZ to NGsolve vector in XXXYYYZZZ format @@ -180,7 +180,7 @@ Function: ResortIndicesExudyn2NGvector Function: ConvertHexToTrigs ^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ConvertHexToTrigs `__\ (\ ``nodeNumbers``\ ) +`ConvertHexToTrigs `__\ (\ ``nodeNumbers``\ ) - | \ *function description*\ : | convert list of Hex8/C3D8 element with 8 nodes in nodeNumbers into triangle-List @@ -200,7 +200,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: ConvertTetToTrigs ^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ConvertTetToTrigs `__\ (\ ``nodeNumbers``\ ) +`ConvertTetToTrigs `__\ (\ ``nodeNumbers``\ ) - | \ *function description*\ : | convert list of Tet4/Tet10 element with 4 or 10 nodes in nodeNumbers into triangle-List @@ -216,7 +216,7 @@ Function: ConvertTetToTrigs Function: ConvertDenseToCompressedRowMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ConvertDenseToCompressedRowMatrix `__\ (\ ``denseMatrix``\ ) +`ConvertDenseToCompressedRowMatrix `__\ (\ ``denseMatrix``\ ) - | \ *function description*\ : | convert numpy.array dense matrix to (internal) compressed row format @@ -230,7 +230,7 @@ Function: ConvertDenseToCompressedRowMatrix Function: ReadMatrixFromAnsysMMF ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadMatrixFromAnsysMMF `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) +`ReadMatrixFromAnsysMMF `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) - | \ *function description*\ : | This function reads either the mass or stiffness matrix from an Ansys @@ -273,7 +273,7 @@ Function: ReadMatrixFromAnsysMMF Function: ReadMatrixDOFmappingVectorFromAnsysTxt ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadMatrixDOFmappingVectorFromAnsysTxt `__\ (\ ``fileName``\ ) +`ReadMatrixDOFmappingVectorFromAnsysTxt `__\ (\ ``fileName``\ ) - | \ *function description*\ : | read sorting vector for ANSYS mass and stiffness matrices and return sorting vector as np.array @@ -289,7 +289,7 @@ Function: ReadMatrixDOFmappingVectorFromAnsysTxt Function: ReadNodalCoordinatesFromAnsysTxt ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadNodalCoordinatesFromAnsysTxt `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) +`ReadNodalCoordinatesFromAnsysTxt `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) - | \ *function description*\ : | This function reads the nodal coordinates exported from Ansys. @@ -319,7 +319,7 @@ Function: ReadNodalCoordinatesFromAnsysTxt Function: ReadElementsFromAnsysTxt ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadElementsFromAnsysTxt `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) +`ReadElementsFromAnsysTxt `__\ (\ ``fileName``\ , \ ``verbose = False``\ ) - | \ *function description*\ : | This function reads the nodal coordinates exported from Ansys. @@ -349,7 +349,7 @@ Function: ReadElementsFromAnsysTxt Function: CMSObjectComputeNorm ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CMSObjectComputeNorm `__\ (\ ``mbs``\ , \ ``objectNumber``\ , \ ``outputVariableType``\ , \ ``norm = 'max'``\ , \ ``nodeNumberList = []``\ ) +`CMSObjectComputeNorm `__\ (\ ``mbs``\ , \ ``objectNumber``\ , \ ``outputVariableType``\ , \ ``norm = 'max'``\ , \ ``nodeNumberList = []``\ ) - | \ *function description*\ : | compute current (max, min, ...) value for chosen ObjectFFRFreducedOrder object (CMSobject) with exu.OutputVariableType. The function operates on nodal values. This is a helper function, which can be used to conveniently compute output quantities of the CMSobject efficiently and to use it in sensors @@ -393,7 +393,7 @@ CLASS KirchhoffMaterial(MaterialBaseClass) (in module FEM) Class function: Strain2Stress ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`Strain2Stress `__\ (\ ``self``\ , \ ``strain``\ ) +`Strain2Stress `__\ (\ ``self``\ , \ ``strain``\ ) - | \ *classFunction*\ : | convert strain tensor into stress tensor using elasticity tensor @@ -404,7 +404,7 @@ Class function: Strain2Stress Class function: StrainVector2StressVector ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`StrainVector2StressVector `__\ (\ ``self``\ , \ ``strainVector``\ ) +`StrainVector2StressVector `__\ (\ ``self``\ , \ ``strainVector``\ ) - | \ *classFunction*\ : | convert strain vector into stress vector @@ -415,7 +415,7 @@ Class function: StrainVector2StressVector Class function: StrainVector2StressVector2D ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`StrainVector2StressVector2D `__\ (\ ``self``\ , \ ``strainVector2D``\ ) +`StrainVector2StressVector2D `__\ (\ ``self``\ , \ ``strainVector2D``\ ) - | \ *classFunction*\ : | compute 2D stress vector from strain vector @@ -426,7 +426,7 @@ Class function: StrainVector2StressVector2D Class function: LameParameters ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`LameParameters `__\ (\ ``self``\ ) +`LameParameters `__\ (\ ``self``\ ) - | \ *classFunction*\ : | compute Lame parameters from internal Young's modulus and Poisson ratio @@ -473,7 +473,7 @@ CLASS ObjectFFRFinterface (in module FEM) Class function: \_\_init\_\_ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`\_\_init\_\_ `__\ (\ ``self``\ , \ ``femInterface``\ ) +`\_\_init\_\_ `__\ (\ ``self``\ , \ ``femInterface``\ ) - | \ *classFunction*\ : | initialize ObjectFFRFinterface with FEMinterface class @@ -486,7 +486,7 @@ Class function: \_\_init\_\_ Class function: AddObjectFFRF ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddObjectFFRF `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``eulerParametersRef = [1,0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``gravity = [0,0,0]``\ , \ ``constrainRigidBodyMotion = True``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``color = [0.1,0.9,0.1,1.]``\ ) +`AddObjectFFRF `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``eulerParametersRef = [1,0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``gravity = [0,0,0]``\ , \ ``constrainRigidBodyMotion = True``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``color = [0.1,0.9,0.1,1.]``\ ) - | \ *classFunction*\ : | add according nodes, objects and constraints for FFRF object to MainSystem mbs; only implemented for Euler parameters @@ -508,7 +508,7 @@ Class function: AddObjectFFRF Class function: UFforce ^^^^^^^^^^^^^^^^^^^^^^^ -`UFforce `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``q``\ , \ ``q_t``\ ) +`UFforce `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``q``\ , \ ``q_t``\ ) - | \ *classFunction*\ : | optional forceUserFunction for ObjectFFRF (per default, this user function is ignored) @@ -519,7 +519,7 @@ Class function: UFforce Class function: UFmassGenericODE2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`UFmassGenericODE2 `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``q``\ , \ ``q_t``\ ) +`UFmassGenericODE2 `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``q``\ , \ ``q_t``\ ) - | \ *classFunction*\ : | optional massMatrixUserFunction for ObjectFFRF (per default, this user function is ignored) @@ -544,7 +544,7 @@ CLASS ObjectFFRFreducedOrderInterface (in module FEM) Class function: \_\_init\_\_ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`\_\_init\_\_ `__\ (\ ``self``\ , \ ``femInterface = None``\ , \ ``rigidBodyNodeType = 'NodeType.RotationEulerParameters'``\ , \ ``roundMassMatrix = 1e-13``\ , \ ``roundStiffnessMatrix = 1e-13``\ ) +`\_\_init\_\_ `__\ (\ ``self``\ , \ ``femInterface = None``\ , \ ``rigidBodyNodeType = 'NodeType.RotationEulerParameters'``\ , \ ``roundMassMatrix = 1e-13``\ , \ ``roundStiffnessMatrix = 1e-13``\ ) - | \ *classFunction*\ : | initialize ObjectFFRFreducedOrderInterface with FEMinterface class @@ -561,7 +561,7 @@ Class function: \_\_init\_\_ Class function: SaveToFile ^^^^^^^^^^^^^^^^^^^^^^^^^^ -`SaveToFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``fileVersion = 1``\ ) +`SaveToFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``fileVersion = 1``\ ) - | \ *classFunction*\ : | save all data to a data filename; can be used to avoid loading femInterface and FE data @@ -577,7 +577,7 @@ Class function: SaveToFile Class function: LoadFromFile ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`LoadFromFile `__\ (\ ``self``\ , \ ``fileName``\ ) +`LoadFromFile `__\ (\ ``self``\ , \ ``fileName``\ ) - | \ *classFunction*\ : | load all data (nodes, elements, ...) from a data filename previously stored with SaveToFile(...). @@ -593,7 +593,7 @@ Class function: LoadFromFile Class function: AddObjectFFRFreducedOrderWithUserFunctions ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddObjectFFRFreducedOrderWithUserFunctions `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``rotationMatrixRef = []``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``gravity = [0,0,0]``\ , \ ``UFforce = 0``\ , \ ``UFmassMatrix = 0``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``color = [0.1,0.9,0.1,1.]``\ , \ ``eulerParametersRef = []``\ ) +`AddObjectFFRFreducedOrderWithUserFunctions `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``rotationMatrixRef = []``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``gravity = [0,0,0]``\ , \ ``UFforce = 0``\ , \ ``UFmassMatrix = 0``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``color = [0.1,0.9,0.1,1.]``\ , \ ``eulerParametersRef = []``\ ) - | \ *classFunction*\ : | add according nodes, objects and constraints for ObjectFFRFreducedOrder object to MainSystem mbs; use this function with userfunctions=0 in order to use internal C++ functionality, which is approx. 10x faster; implementation of userfunctions also available for rotation vector (Lie group formulation), which needs further testing @@ -629,7 +629,7 @@ Class function: AddObjectFFRFreducedOrderWithUserFunctions Class function: UFmassFFRFreducedOrder ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`UFmassFFRFreducedOrder `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``qReduced``\ , \ ``qReduced_t``\ ) +`UFmassFFRFreducedOrder `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``qReduced``\ , \ ``qReduced_t``\ ) - | \ *classFunction*\ : | CMS mass matrix user function; qReduced and qReduced_t contain the coordiantes of the rigid body node and the modal coordinates in one vector! @@ -640,7 +640,7 @@ Class function: UFmassFFRFreducedOrder Class function: UFforceFFRFreducedOrder ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`UFforceFFRFreducedOrder `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``qReduced``\ , \ ``qReduced_t``\ ) +`UFforceFFRFreducedOrder `__\ (\ ``self``\ , \ ``exu``\ , \ ``mbs``\ , \ ``t``\ , \ ``qReduced``\ , \ ``qReduced_t``\ ) - | \ *classFunction*\ : | CMS force matrix user function; qReduced and qReduced_t contain the coordiantes of the rigid body node and the modal coordinates in one vector! @@ -651,7 +651,7 @@ Class function: UFforceFFRFreducedOrder Class function: AddObjectFFRFreducedOrder ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddObjectFFRFreducedOrder `__\ (\ ``self``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``rotationMatrixRef = []``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``gravity = [0,0,0]``\ , \ ``color = [0.1,0.9,0.1,1.]``\ ) +`AddObjectFFRFreducedOrder `__\ (\ ``self``\ , \ ``mbs``\ , \ ``positionRef = [0,0,0]``\ , \ ``initialVelocity = [0,0,0]``\ , \ ``rotationMatrixRef = []``\ , \ ``initialAngularVelocity = [0,0,0]``\ , \ ``massProportionalDamping = 0``\ , \ ``stiffnessProportionalDamping = 0``\ , \ ``gravity = [0,0,0]``\ , \ ``color = [0.1,0.9,0.1,1.]``\ ) - | \ *classFunction*\ : | add according nodes, objects and constraints for ObjectFFRFreducedOrder object to MainSystem mbs; use this function in order to use internal C++ functionality, which is approx. 10x faster than AddObjectFFRFreducedOrderWithUserFunctions(...) @@ -707,7 +707,7 @@ CLASS FEMinterface (in module FEM) Class function: \_\_init\_\_ ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`\_\_init\_\_ `__\ (\ ``self``\ ) +`\_\_init\_\_ `__\ (\ ``self``\ ) - | \ *classFunction*\ : | initalize all data of the FEMinterface by, e.g., \ ``fem = FEMinterface()``\ @@ -735,7 +735,7 @@ Class function: \_\_init\_\_ Class function: SaveToFile ^^^^^^^^^^^^^^^^^^^^^^^^^^ -`SaveToFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``fileVersion = 13``\ ) +`SaveToFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``fileVersion = 13``\ ) - | \ *classFunction*\ : | save all data (nodes, elements, ...) to a data filename; this function is much faster than the text-based import functions @@ -751,7 +751,7 @@ Class function: SaveToFile Class function: LoadFromFile ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`LoadFromFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``forceVersion = None``\ ) +`LoadFromFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``forceVersion = None``\ ) - | \ *classFunction*\ : | load all data (nodes, elements, ...) from a data filename previously stored with SaveToFile(...). @@ -768,7 +768,7 @@ Class function: LoadFromFile Class function: ImportFromAbaqusInputFile ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ImportFromAbaqusInputFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``typeName = 'Part'``\ , \ ``name = 'Part-1'``\ , \ ``verbose = False``\ , \ ``createSurfaceTrigs = True``\ , \ ``surfaceTrigsAll = False``\ ) +`ImportFromAbaqusInputFile `__\ (\ ``self``\ , \ ``fileName``\ , \ ``typeName = 'Part'``\ , \ ``name = 'Part-1'``\ , \ ``verbose = False``\ , \ ``createSurfaceTrigs = True``\ , \ ``surfaceTrigsAll = False``\ ) - | \ *classFunction*\ : | import nodes and elements from Abaqus input file and create surface elements; @@ -793,7 +793,7 @@ Class function: ImportFromAbaqusInputFile Class function: ReadMassMatrixFromAbaqus ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadMassMatrixFromAbaqus `__\ (\ ``self``\ , \ ``fileName``\ , \ ``type = 'SparseRowColumnValue'``\ ) +`ReadMassMatrixFromAbaqus `__\ (\ ``self``\ , \ ``fileName``\ , \ ``type = 'SparseRowColumnValue'``\ ) - | \ *classFunction*\ : | read mass matrix from compressed row text format (exported from Abaqus); in order to export system matrices, write the following lines in your Abaqus input file: @@ -808,7 +808,7 @@ Class function: ReadMassMatrixFromAbaqus Class function: ReadStiffnessMatrixFromAbaqus ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadStiffnessMatrixFromAbaqus `__\ (\ ``self``\ , \ ``fileName``\ , \ ``type = 'SparseRowColumnValue'``\ ) +`ReadStiffnessMatrixFromAbaqus `__\ (\ ``self``\ , \ ``fileName``\ , \ ``type = 'SparseRowColumnValue'``\ ) - | \ *classFunction*\ : | read stiffness matrix from compressed row text format (exported from Abaqus) @@ -819,7 +819,7 @@ Class function: ReadStiffnessMatrixFromAbaqus Class function: ImportMeshFromNGsolve ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ImportMeshFromNGsolve `__\ (\ ``self``\ , \ ``mesh``\ , \ ``density``\ , \ ``youngsModulus``\ , \ ``poissonsRatio``\ , \ ``verbose = False``\ , \ ``computeEigenmodes = False``\ , \ ``meshOrder = 1``\ , \ ``**kwargs``\ ) +`ImportMeshFromNGsolve `__\ (\ ``self``\ , \ ``mesh``\ , \ ``density``\ , \ ``youngsModulus``\ , \ ``poissonsRatio``\ , \ ``verbose = False``\ , \ ``computeEigenmodes = False``\ , \ ``meshOrder = 1``\ , \ ``**kwargs``\ ) - | \ *classFunction*\ : | import mesh from NETGEN/NGsolve and setup mechanical problem @@ -843,7 +843,7 @@ Class function: ImportMeshFromNGsolve Class function: ComputeEigenmodesNGsolve ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeEigenmodesNGsolve `__\ (\ ``self``\ , \ ``bfM``\ , \ ``bfK``\ , \ ``nModes``\ , \ ``maxEigensolveIterations = 40``\ , \ ``excludeRigidBodyModes = 0``\ , \ ``verbose = False``\ ) +`ComputeEigenmodesNGsolve `__\ (\ ``self``\ , \ ``bfM``\ , \ ``bfK``\ , \ ``nModes``\ , \ ``maxEigensolveIterations = 40``\ , \ ``excludeRigidBodyModes = 0``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | compute nModes smallest eigenvalues and eigenmodes from mass and stiffnessMatrix; store mode vectors in modeBasis, but exclude a number of 'excludeRigidBodyModes' rigid body modes from modeBasis; uses scipy for solution of generalized eigenvalue problem @@ -863,7 +863,7 @@ Class function: ComputeEigenmodesNGsolve Class function: ComputeHurtyCraigBamptonModesNGsolve ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeHurtyCraigBamptonModesNGsolve `__\ (\ ``self``\ , \ ``bfM``\ , \ ``bfK``\ , \ ``boundaryNodesList``\ , \ ``nEigenModes``\ , \ ``maxEigensolveIterations = 40``\ , \ ``verbose = False``\ ) +`ComputeHurtyCraigBamptonModesNGsolve `__\ (\ ``self``\ , \ ``bfM``\ , \ ``bfK``\ , \ ``boundaryNodesList``\ , \ ``nEigenModes``\ , \ ``maxEigensolveIterations = 40``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | compute static and eigen modes based on Hurty-Craig-Bampton, for details see theory part Section :ref:`sec-theory-cms`\ . This function uses internal computational functionality of NGsolve and is often much faster than the scipy variant @@ -885,7 +885,7 @@ Class function: ComputeHurtyCraigBamptonModesNGsolve Class function: ComputePostProcessingModesNGsolve ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputePostProcessingModesNGsolve `__\ (\ ``self``\ , \ ``fes``\ , \ ``material = 0``\ , \ ``outputVariableType = 'OutputVariableType.StressLocal'``\ , \ ``verbose = False``\ ) +`ComputePostProcessingModesNGsolve `__\ (\ ``self``\ , \ ``fes``\ , \ ``material = 0``\ , \ ``outputVariableType = 'OutputVariableType.StressLocal'``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | compute special stress or strain modes in order to enable visualization of stresses and strains in ObjectFFRFreducedOrder; takes a NGsolve fes as input and uses internal NGsolve methods to efficiently compute stresses or strains @@ -906,7 +906,7 @@ Class function: ComputePostProcessingModesNGsolve Class function: GetMassMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetMassMatrix `__\ (\ ``self``\ , \ ``sparse = True``\ ) +`GetMassMatrix `__\ (\ ``self``\ , \ ``sparse = True``\ ) - | \ *classFunction*\ : | get sparse mass matrix in according format @@ -917,7 +917,7 @@ Class function: GetMassMatrix Class function: GetStiffnessMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetStiffnessMatrix `__\ (\ ``self``\ , \ ``sparse = True``\ ) +`GetStiffnessMatrix `__\ (\ ``self``\ , \ ``sparse = True``\ ) - | \ *classFunction*\ : | get sparse stiffness matrix in according format @@ -928,7 +928,7 @@ Class function: GetStiffnessMatrix Class function: NumberOfNodes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`NumberOfNodes `__\ (\ ``self``\ ) +`NumberOfNodes `__\ (\ ``self``\ ) - | \ *classFunction*\ : | get total number of nodes @@ -939,7 +939,7 @@ Class function: NumberOfNodes Class function: GetNodePositionsAsArray ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodePositionsAsArray `__\ (\ ``self``\ ) +`GetNodePositionsAsArray `__\ (\ ``self``\ ) - | \ *classFunction*\ : | get node points as array; only possible, if there exists only one type of Position nodes @@ -960,7 +960,7 @@ Class function: GetNodePositionsAsArray Class function: GetNodePositionsMean ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodePositionsMean `__\ (\ ``self``\ , \ ``nodeNumberList``\ ) +`GetNodePositionsMean `__\ (\ ``self``\ , \ ``nodeNumberList``\ ) - | \ *classFunction*\ : | get mean (average) position of nodes defined by list of node numbers @@ -971,7 +971,7 @@ Class function: GetNodePositionsMean Class function: NumberOfCoordinates ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`NumberOfCoordinates `__\ (\ ``self``\ ) +`NumberOfCoordinates `__\ (\ ``self``\ ) - | \ *classFunction*\ : | get number of total nodal coordinates @@ -982,7 +982,7 @@ Class function: NumberOfCoordinates Class function: GetNodeAtPoint ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodeAtPoint `__\ (\ ``self``\ , \ ``point``\ , \ ``tolerance = 1e-5``\ , \ ``raiseException = True``\ ) +`GetNodeAtPoint `__\ (\ ``self``\ , \ ``point``\ , \ ``tolerance = 1e-5``\ , \ ``raiseException = True``\ ) - | \ *classFunction*\ : | get node number for node at given point, e.g. p=[0.1,0.5,-0.2], using a tolerance (+/-) if coordinates are available only with reduced accuracy @@ -994,7 +994,7 @@ Class function: GetNodeAtPoint Class function: GetNodesInPlane ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodesInPlane `__\ (\ ``self``\ , \ ``point``\ , \ ``normal``\ , \ ``tolerance = 1e-5``\ ) +`GetNodesInPlane `__\ (\ ``self``\ , \ ``point``\ , \ ``normal``\ , \ ``tolerance = 1e-5``\ ) - | \ *classFunction*\ : | get node numbers in plane defined by point p and (normalized) normal vector n using a tolerance for the distance to the plane @@ -1006,7 +1006,7 @@ Class function: GetNodesInPlane Class function: GetNodesInCube ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodesInCube `__\ (\ ``self``\ , \ ``pMin``\ , \ ``pMax``\ ) +`GetNodesInCube `__\ (\ ``self``\ , \ ``pMin``\ , \ ``pMax``\ ) - | \ *classFunction*\ : | get node numbers in cube, given by pMin and pMax, containing the minimum and maximum x, y, and z coordinates @@ -1025,7 +1025,7 @@ Class function: GetNodesInCube Class function: GetNodesOnLine ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodesOnLine `__\ (\ ``self``\ , \ ``p1``\ , \ ``p2``\ , \ ``tolerance = 1e-5``\ ) +`GetNodesOnLine `__\ (\ ``self``\ , \ ``p1``\ , \ ``p2``\ , \ ``tolerance = 1e-5``\ ) - | \ *classFunction*\ : | get node numbers lying on line defined by points p1 and p2 and tolerance, which is accepted for points slightly outside the surface @@ -1036,7 +1036,7 @@ Class function: GetNodesOnLine Class function: GetNodesOnCylinder ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodesOnCylinder `__\ (\ ``self``\ , \ ``p1``\ , \ ``p2``\ , \ ``radius``\ , \ ``tolerance = 1e-5``\ ) +`GetNodesOnCylinder `__\ (\ ``self``\ , \ ``p1``\ , \ ``p2``\ , \ ``radius``\ , \ ``tolerance = 1e-5``\ ) - | \ *classFunction*\ : | get node numbers lying on cylinder surface; cylinder defined by cylinder axes (points p1 and p2), @@ -1049,7 +1049,7 @@ Class function: GetNodesOnCylinder Class function: GetNodesOnCircle ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodesOnCircle `__\ (\ ``self``\ , \ ``point``\ , \ ``normal``\ , \ ``r``\ , \ ``tolerance = 1e-5``\ ) +`GetNodesOnCircle `__\ (\ ``self``\ , \ ``point``\ , \ ``normal``\ , \ ``r``\ , \ ``tolerance = 1e-5``\ ) - | \ *classFunction*\ : | get node numbers lying on a circle, by point p, (normalized) normal vector n (which is the axis of the circle) and radius r @@ -1062,7 +1062,7 @@ Class function: GetNodesOnCircle Class function: GetNodeWeightsFromSurfaceAreas ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetNodeWeightsFromSurfaceAreas `__\ (\ ``self``\ , \ ``nodeList``\ , \ ``normalizeWeights = True``\ ) +`GetNodeWeightsFromSurfaceAreas `__\ (\ ``self``\ , \ ``nodeList``\ , \ ``normalizeWeights = True``\ ) - | \ *classFunction*\ : | return list of node weights based on surface triangle areas; surface triangles are identified as such for which all nodes of a triangle are on the surface @@ -1079,7 +1079,7 @@ Class function: GetNodeWeightsFromSurfaceAreas Class function: GetSurfaceTriangles ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetSurfaceTriangles `__\ (\ ``self``\ ) +`GetSurfaceTriangles `__\ (\ ``self``\ ) - | \ *classFunction*\ : | return surface trigs as node number list (for drawing in EXUDYN and for node weights) @@ -1090,7 +1090,7 @@ Class function: GetSurfaceTriangles Class function: VolumeToSurfaceElements ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`VolumeToSurfaceElements `__\ (\ ``self``\ , \ ``verbose = False``\ ) +`VolumeToSurfaceElements `__\ (\ ``self``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | generate surface elements from volume elements @@ -1103,7 +1103,7 @@ Class function: VolumeToSurfaceElements Class function: GetGyroscopicMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetGyroscopicMatrix `__\ (\ ``self``\ , \ ``rotationAxis = 2``\ , \ ``sparse = True``\ ) +`GetGyroscopicMatrix `__\ (\ ``self``\ , \ ``rotationAxis = 2``\ , \ ``sparse = True``\ ) - | \ *classFunction*\ : | get gyroscopic matrix in according format; rotationAxis=[0,1,2] = [x,y,z] @@ -1114,7 +1114,7 @@ Class function: GetGyroscopicMatrix Class function: ScaleMassMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ScaleMassMatrix `__\ (\ ``self``\ , \ ``factor``\ ) +`ScaleMassMatrix `__\ (\ ``self``\ , \ ``factor``\ ) - | \ *classFunction*\ : | scale (=multiply) mass matrix with factor @@ -1125,7 +1125,7 @@ Class function: ScaleMassMatrix Class function: ScaleStiffnessMatrix ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ScaleStiffnessMatrix `__\ (\ ``self``\ , \ ``factor``\ ) +`ScaleStiffnessMatrix `__\ (\ ``self``\ , \ ``factor``\ ) - | \ *classFunction*\ : | scale (=multiply) stiffness matrix with factor @@ -1136,7 +1136,7 @@ Class function: ScaleStiffnessMatrix Class function: AddElasticSupportAtNode ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddElasticSupportAtNode `__\ (\ ``self``\ , \ ``nodeNumber``\ , \ ``springStiffness = [1e8,1e8,1e8]``\ ) +`AddElasticSupportAtNode `__\ (\ ``self``\ , \ ``nodeNumber``\ , \ ``springStiffness = [1e8,1e8,1e8]``\ ) - | \ *classFunction*\ : | modify stiffness matrix to add elastic support (joint, etc.) to a node; nodeNumber zero based (as everywhere in the code...) @@ -1148,7 +1148,7 @@ Class function: AddElasticSupportAtNode Class function: AddNodeMass ^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`AddNodeMass `__\ (\ ``self``\ , \ ``nodeNumber``\ , \ ``addedMass``\ ) +`AddNodeMass `__\ (\ ``self``\ , \ ``nodeNumber``\ , \ ``addedMass``\ ) - | \ *classFunction*\ : | modify mass matrix by adding a mass to a certain node, modifying directly the mass matrix @@ -1159,7 +1159,7 @@ Class function: AddNodeMass Class function: CreateLinearFEMObjectGenericODE2 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateLinearFEMObjectGenericODE2 `__\ (\ ``self``\ , \ ``mbs``\ , \ ``color = [0.9,0.4,0.4,1.]``\ ) +`CreateLinearFEMObjectGenericODE2 `__\ (\ ``self``\ , \ ``mbs``\ , \ ``color = [0.9,0.4,0.4,1.]``\ ) - | \ *classFunction*\ : | create GenericODE2 object out of (linear) FEM model; uses always the sparse matrix mode, independent of the solver settings; this model can be directly used inside the multibody system as a static or dynamic FEM subsystem undergoing small deformations; computation is several magnitudes slower than ObjectFFRFreducedOrder @@ -1174,7 +1174,7 @@ Class function: CreateLinearFEMObjectGenericODE2 Class function: CreateNonlinearFEMObjectGenericODE2NGsolve ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateNonlinearFEMObjectGenericODE2NGsolve `__\ (\ ``self``\ , \ ``mbs``\ , \ ``mesh``\ , \ ``density``\ , \ ``youngsModulus``\ , \ ``poissonsRatio``\ , \ ``meshOrder = 1``\ , \ ``color = [0.9,0.4,0.4,1.]``\ ) +`CreateNonlinearFEMObjectGenericODE2NGsolve `__\ (\ ``self``\ , \ ``mbs``\ , \ ``mesh``\ , \ ``density``\ , \ ``youngsModulus``\ , \ ``poissonsRatio``\ , \ ``meshOrder = 1``\ , \ ``color = [0.9,0.4,0.4,1.]``\ ) - | \ *classFunction*\ : | create GenericODE2 object fully nonlinear FEM model using NGsolve; uses always the sparse matrix mode, independent of the solver settings; this model can be directly used inside the multibody system as a static or dynamic nonlinear FEM subsystem undergoing large deformations; computation is several magnitudes slower than ObjectFFRFreducedOrder @@ -1202,7 +1202,7 @@ Class function: CreateNonlinearFEMObjectGenericODE2NGsolve Class function: ComputeEigenmodes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeEigenmodes `__\ (\ ``self``\ , \ ``nModes``\ , \ ``excludeRigidBodyModes = 0``\ , \ ``useSparseSolver = True``\ ) +`ComputeEigenmodes `__\ (\ ``self``\ , \ ``nModes``\ , \ ``excludeRigidBodyModes = 0``\ , \ ``useSparseSolver = True``\ ) - | \ *classFunction*\ : | compute nModes smallest eigenvalues and eigenmodes from mass and stiffnessMatrix; store mode vectors in modeBasis, but exclude a number of 'excludeRigidBodyModes' rigid body modes from modeBasis; uses scipy for solution of generalized eigenvalue problem @@ -1221,7 +1221,7 @@ Class function: ComputeEigenmodes Class function: ComputeEigenModesWithBoundaryNodes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeEigenModesWithBoundaryNodes `__\ (\ ``self``\ , \ ``boundaryNodes``\ , \ ``nEigenModes``\ , \ ``useSparseSolver = True``\ ) +`ComputeEigenModesWithBoundaryNodes `__\ (\ ``self``\ , \ ``boundaryNodes``\ , \ ``nEigenModes``\ , \ ``useSparseSolver = True``\ ) - | \ *classFunction*\ : | compute eigenmodes, using a set of boundary nodes that are all fixed; very similar to ComputeEigenmodes, but with additional definition of (fixed) boundary nodes. @@ -1238,7 +1238,7 @@ Class function: ComputeEigenModesWithBoundaryNodes Class function: ComputeHurtyCraigBamptonModes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeHurtyCraigBamptonModes `__\ (\ ``self``\ , \ ``boundaryNodesList``\ , \ ``nEigenModes``\ , \ ``useSparseSolver = True``\ , \ ``computationMode = HCBstaticModeSelection.RBE2``\ , \ ``boundaryNodesWeights = []``\ , \ ``excludeRigidBodyMotion = True``\ , \ ``RBE3secondMomentOfAreaWeighting = True``\ , \ ``verboseMode = False``\ , \ ``timerTreshold = 20000``\ ) +`ComputeHurtyCraigBamptonModes `__\ (\ ``self``\ , \ ``boundaryNodesList``\ , \ ``nEigenModes``\ , \ ``useSparseSolver = True``\ , \ ``computationMode = HCBstaticModeSelection.RBE2``\ , \ ``boundaryNodesWeights = []``\ , \ ``excludeRigidBodyMotion = True``\ , \ ``RBE3secondMomentOfAreaWeighting = True``\ , \ ``verboseMode = False``\ , \ ``timerTreshold = 20000``\ ) - | \ *classFunction*\ : | compute static and eigen modes based on Hurty-Craig-Bampton, for details see theory part Section :ref:`sec-theory-cms`\ . Note that this function may need significant time, depending on your hardware, but 50.000 nodes will require approx. 1-2 minutes and more nodes typically raise time more than linearly. @@ -1263,7 +1263,7 @@ Class function: ComputeHurtyCraigBamptonModes Class function: GetEigenFrequenciesHz ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetEigenFrequenciesHz `__\ (\ ``self``\ ) +`GetEigenFrequenciesHz `__\ (\ ``self``\ ) - | \ *classFunction*\ : | return list of eigenvalues in Hz of previously computed eigenmodes @@ -1274,7 +1274,7 @@ Class function: GetEigenFrequenciesHz Class function: ComputePostProcessingModes ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputePostProcessingModes `__\ (\ ``self``\ , \ ``material = 0``\ , \ ``outputVariableType = 'OutputVariableType.StressLocal'``\ , \ ``numberOfThreads = 1``\ ) +`ComputePostProcessingModes `__\ (\ ``self``\ , \ ``material = 0``\ , \ ``outputVariableType = 'OutputVariableType.StressLocal'``\ , \ ``numberOfThreads = 1``\ ) - | \ *classFunction*\ : | compute special stress or strain modes in order to enable visualization of stresses and strains in ObjectFFRFreducedOrder; @@ -1293,7 +1293,7 @@ Class function: ComputePostProcessingModes Class function: ComputeCampbellDiagram ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeCampbellDiagram `__\ (\ ``self``\ , \ ``terminalFrequency``\ , \ ``nEigenfrequencies = 10``\ , \ ``frequencySteps = 25``\ , \ ``rotationAxis = 2``\ , \ ``plotDiagram = False``\ , \ ``verbose = False``\ , \ ``useCorotationalFrame = False``\ , \ ``useSparseSolver = False``\ ) +`ComputeCampbellDiagram `__\ (\ ``self``\ , \ ``terminalFrequency``\ , \ ``nEigenfrequencies = 10``\ , \ ``frequencySteps = 25``\ , \ ``rotationAxis = 2``\ , \ ``plotDiagram = False``\ , \ ``verbose = False``\ , \ ``useCorotationalFrame = False``\ , \ ``useSparseSolver = False``\ ) - | \ *classFunction*\ : | compute Campbell diagram for given mechanical system @@ -1320,7 +1320,7 @@ Class function: ComputeCampbellDiagram Class function: CheckConsistency ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CheckConsistency `__\ (\ ``self``\ ) +`CheckConsistency `__\ (\ ``self``\ ) - | \ *classFunction*\ : | perform some consistency checks @@ -1331,7 +1331,7 @@ Class function: CheckConsistency Class function: ReadMassMatrixFromAnsys ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadMassMatrixFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``dofMappingVectorFile``\ , \ ``sparse = True``\ , \ ``verbose = False``\ ) +`ReadMassMatrixFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``dofMappingVectorFile``\ , \ ``sparse = True``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | read mass matrix from CSV format (exported from Ansys) @@ -1342,7 +1342,7 @@ Class function: ReadMassMatrixFromAnsys Class function: ReadStiffnessMatrixFromAnsys ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadStiffnessMatrixFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``dofMappingVectorFile``\ , \ ``sparse = True``\ , \ ``verbose = False``\ ) +`ReadStiffnessMatrixFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``dofMappingVectorFile``\ , \ ``sparse = True``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | read stiffness matrix from CSV format (exported from Ansys) @@ -1353,7 +1353,7 @@ Class function: ReadStiffnessMatrixFromAnsys Class function: ReadNodalCoordinatesFromAnsys ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadNodalCoordinatesFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``verbose = False``\ ) +`ReadNodalCoordinatesFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | read nodal coordinates (exported from Ansys as .txt-File) @@ -1364,7 +1364,7 @@ Class function: ReadNodalCoordinatesFromAnsys Class function: ReadElementsFromAnsys ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ReadElementsFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``verbose = False``\ ) +`ReadElementsFromAnsys `__\ (\ ``self``\ , \ ``fileName``\ , \ ``verbose = False``\ ) - | \ *classFunction*\ : | read elements (exported from Ansys as .txt-File) diff --git a/docs/RST/pythonUtilities/GUI.rst b/docs/RST/pythonUtilities/GUI.rst index 1f6d09f7..79db764b 100644 --- a/docs/RST/pythonUtilities/GUI.rst +++ b/docs/RST/pythonUtilities/GUI.rst @@ -43,7 +43,7 @@ Function: TkRootExists Function: EditDictionaryWithTypeInfo ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`EditDictionaryWithTypeInfo `__\ (\ ``settingsStructure``\ , \ ``exu = None``\ , \ ``dictionaryName = 'edit'``\ ) +`EditDictionaryWithTypeInfo `__\ (\ ``settingsStructure``\ , \ ``exu = None``\ , \ ``dictionaryName = 'edit'``\ ) - | \ *function description*\ : | edit dictionaryData and return modified (new) dictionary diff --git a/docs/RST/pythonUtilities/basicUtilities.rst b/docs/RST/pythonUtilities/basicUtilities.rst index 2b321b3b..c5c95673 100644 --- a/docs/RST/pythonUtilities/basicUtilities.rst +++ b/docs/RST/pythonUtilities/basicUtilities.rst @@ -51,6 +51,20 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: +---- + + +.. _sec-basicutilities-smartround2string: + +Function: SmartRound2String +^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`SmartRound2String `__\ (\ ``x``\ , \ ``prec = 3``\ ) + +- | \ *function description*\ : + | round to max number of digits; may give more digits if this is shorter; using in general the format() with '.g' option, but keeping decimal point and using exponent where necessary + + + ---- @@ -58,7 +72,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: DiagonalMatrix ^^^^^^^^^^^^^^^^^^^^^^^^ -`DiagonalMatrix `__\ (\ ``rowsColumns``\ , \ ``value = 1``\ ) +`DiagonalMatrix `__\ (\ ``rowsColumns``\ , \ ``value = 1``\ ) - | \ *function description*\ : | create a diagonal or identity matrix; used for interface.py, avoiding the need for numpy @@ -77,7 +91,7 @@ Function: DiagonalMatrix Function: NormL2 ^^^^^^^^^^^^^^^^ -`NormL2 `__\ (\ ``vector``\ ) +`NormL2 `__\ (\ ``vector``\ ) - | \ *function description*\ : | compute L2 norm for vectors without switching to numpy or math module @@ -99,7 +113,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: VSum ^^^^^^^^^^^^^^ -`VSum `__\ (\ ``vector``\ ) +`VSum `__\ (\ ``vector``\ ) - | \ *function description*\ : | compute sum of all values of vector @@ -121,7 +135,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: VAdd ^^^^^^^^^^^^^^ -`VAdd `__\ (\ ``v0``\ , \ ``v1``\ ) +`VAdd `__\ (\ ``v0``\ , \ ``v1``\ ) - | \ *function description*\ : | add two vectors instead using numpy @@ -143,7 +157,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: VSub ^^^^^^^^^^^^^^ -`VSub `__\ (\ ``v0``\ , \ ``v1``\ ) +`VSub `__\ (\ ``v0``\ , \ ``v1``\ ) - | \ *function description*\ : | subtract two vectors instead using numpy: result = v0-v1 @@ -165,7 +179,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: VMult ^^^^^^^^^^^^^^^ -`VMult `__\ (\ ``v0``\ , \ ``v1``\ ) +`VMult `__\ (\ ``v0``\ , \ ``v1``\ ) - | \ *function description*\ : | scalar multiplication of two vectors instead using numpy: result = v0' \* v1 @@ -183,7 +197,7 @@ Function: VMult Function: ScalarMult ^^^^^^^^^^^^^^^^^^^^ -`ScalarMult `__\ (\ ``scalar``\ , \ ``v``\ ) +`ScalarMult `__\ (\ ``scalar``\ , \ ``v``\ ) - | \ *function description*\ : | multiplication vectors with scalar: result = scalar \* v @@ -205,7 +219,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: Normalize ^^^^^^^^^^^^^^^^^^^ -`Normalize `__\ (\ ``v``\ ) +`Normalize `__\ (\ ``v``\ ) - | \ *function description*\ : | take a 3D vector and return a normalized 3D vector (L2Norm=1) @@ -227,7 +241,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: Vec2Tilde ^^^^^^^^^^^^^^^^^^^ -`Vec2Tilde `__\ (\ ``v``\ ) +`Vec2Tilde `__\ (\ ``v``\ ) - | \ *function description*\ : | apply tilde operator (skew) to 3D-vector and return skew matrix @@ -250,7 +264,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: Tilde2Vec ^^^^^^^^^^^^^^^^^^^ -`Tilde2Vec `__\ (\ ``m``\ ) +`Tilde2Vec `__\ (\ ``m``\ ) - | \ *function description*\ : | take skew symmetric matrix and return vector (inverse of Skew(...)) @@ -268,7 +282,7 @@ Function: Tilde2Vec Function: GaussIntegrate ^^^^^^^^^^^^^^^^^^^^^^^^ -`GaussIntegrate `__\ (\ ``functionOfX``\ , \ ``integrationOrder``\ , \ ``a``\ , \ ``b``\ ) +`GaussIntegrate `__\ (\ ``functionOfX``\ , \ ``integrationOrder``\ , \ ``a``\ , \ ``b``\ ) - | \ *function description*\ : | compute numerical integration of functionOfX in interval [a,b] using Gaussian integration @@ -289,7 +303,7 @@ Function: GaussIntegrate Function: LobattoIntegrate ^^^^^^^^^^^^^^^^^^^^^^^^^^ -`LobattoIntegrate `__\ (\ ``functionOfX``\ , \ ``integrationOrder``\ , \ ``a``\ , \ ``b``\ ) +`LobattoIntegrate `__\ (\ ``functionOfX``\ , \ ``integrationOrder``\ , \ ``a``\ , \ ``b``\ ) - | \ *function description*\ : | compute numerical integration of functionOfX in interval [a,b] using Lobatto integration diff --git a/docs/RST/pythonUtilities/graphicsDataUtilities.rst b/docs/RST/pythonUtilities/graphicsDataUtilities.rst index bd1053e1..0b0c0fae 100644 --- a/docs/RST/pythonUtilities/graphicsDataUtilities.rst +++ b/docs/RST/pythonUtilities/graphicsDataUtilities.rst @@ -333,7 +333,7 @@ Function: GraphicsDataOrthoCubeLines Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `NGsolveCraigBampton.py `_\ (Ex), \ `rigid3Dexample.py `_\ (Ex), \ `genericJointUserFunctionTest.py `_\ (TM), \ `rigidBodyCOMtest.py `_\ (TM), \ `sphericalJointTest.py `_\ (TM) + \ `NGsolveCraigBampton.py `_\ (Ex), \ `rigid3Dexample.py `_\ (Ex), \ `rr.py `_\ (Ex), \ `genericJointUserFunctionTest.py `_\ (TM), \ `rigidBodyCOMtest.py `_\ (TM), \ `sphericalJointTest.py `_\ (TM) @@ -388,7 +388,7 @@ Function: GraphicsDataOrthoCubePoint Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `beltDrivesComparison.py `_\ (Ex), \ `bicycleIftommBenchmark.py `_\ (Ex), \ `craneReevingSystem.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `carRollingDiscTest.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM) + \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `beltDrivesComparison.py `_\ (Ex), \ `bicycleIftommBenchmark.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `carRollingDiscTest.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM) @@ -440,7 +440,7 @@ Function: GraphicsDataSphere Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `bicycleIftommBenchmark.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `humanRobotInteraction.py `_\ (Ex), \ `lugreFrictionTest.py `_\ (Ex), \ `nMassOscillatorEigenmodes.py `_\ (Ex), \ `connectorGravityTest.py `_\ (TM), \ `contactCoordinateTest.py `_\ (TM), \ `coordinateVectorConstraint.py `_\ (TM) + \ `bicycleIftommBenchmark.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `humanRobotInteraction.py `_\ (Ex), \ `lugreFrictionTest.py `_\ (Ex), \ `connectorGravityTest.py `_\ (TM), \ `contactCoordinateTest.py `_\ (TM), \ `coordinateVectorConstraint.py `_\ (TM) @@ -559,7 +559,7 @@ Function: GraphicsDataFromSTLfile Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `humanRobotInteraction.py `_\ (Ex), \ `stlFileImport.py `_\ (Ex) + \ `humanRobotInteraction.py `_\ (Ex), \ `ROSExampleTurtle.py `_\ (Ex), \ `stlFileImport.py `_\ (Ex) @@ -824,7 +824,7 @@ Function: GraphicsDataCheckerBoard Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `bicycleIftommBenchmark.py `_\ (Ex), \ `craneReevingSystem.py `_\ (Ex), \ `finiteSegmentMethod.py `_\ (Ex), \ `flexiblePendulumANCF.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `ANCFoutputTest.py `_\ (TM), \ `bricardMechanism.py `_\ (TM), \ `connectorGravityTest.py `_\ (TM) + \ `bicycleIftommBenchmark.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `craneReevingSystem.py `_\ (Ex), \ `finiteSegmentMethod.py `_\ (Ex), \ `flexiblePendulumANCF.py `_\ (Ex), \ `ANCFoutputTest.py `_\ (TM), \ `bricardMechanism.py `_\ (TM), \ `connectorGravityTest.py `_\ (TM) diff --git a/docs/RST/pythonUtilities/plot.rst b/docs/RST/pythonUtilities/plot.rst index 80d9dbc9..dcc11dd9 100644 --- a/docs/RST/pythonUtilities/plot.rst +++ b/docs/RST/pythonUtilities/plot.rst @@ -15,7 +15,7 @@ Plot utility functions based on matplotlib, including plotting of sensors and FF Function: ParseOutputFileHeader ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ParseOutputFileHeader `__\ (\ ``lines``\ ) +`ParseOutputFileHeader `__\ (\ ``lines``\ ) - | \ *function description*\ : | parse header of output file (solution file, sensor file, genetic optimization output, ...) given in file.readlines() format @@ -31,7 +31,7 @@ Function: ParseOutputFileHeader Function: PlotSensorDefaults ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`PlotSensorDefaults `__\ () +`PlotSensorDefaults `__\ () - | \ *function description*\ : | returns structure with default values for PlotSensor which can be modified once to be set for all later calls of PlotSensor @@ -58,7 +58,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: PlotSensor ^^^^^^^^^^^^^^^^^^^^ -`PlotSensor `__\ (\ ``mbs``\ , \ ``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``\ ) +`PlotSensor `__\ (\ ``mbs``\ , \ ``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``\ ) - | **NOTE**\ : this function is directly available in MainSystem (mbs); it should be directly called as mbs.PlotSensor(...). For description of the interface, see the MainSystem Python extensions, :ref:`sec-mainsystemextensions-plotsensor`\ @@ -72,7 +72,7 @@ Function: PlotSensor Function: PlotFFT ^^^^^^^^^^^^^^^^^ -`PlotFFT `__\ (\ ``frequency``\ , \ ``data``\ , \ ``xLabel = 'frequency'``\ , \ ``yLabel = 'magnitude'``\ , \ ``label = ''``\ , \ ``freqStart = 0``\ , \ ``freqEnd = -1``\ , \ ``logScaleX = True``\ , \ ``logScaleY = True``\ , \ ``majorGrid = True``\ , \ ``minorGrid = True``\ ) +`PlotFFT `__\ (\ ``frequency``\ , \ ``data``\ , \ ``xLabel = 'frequency'``\ , \ ``yLabel = 'magnitude'``\ , \ ``label = ''``\ , \ ``freqStart = 0``\ , \ ``freqEnd = -1``\ , \ ``logScaleX = True``\ , \ ``logScaleY = True``\ , \ ``majorGrid = True``\ , \ ``minorGrid = True``\ ) - | \ *function description*\ : | plot fft spectrum of signal @@ -91,6 +91,10 @@ Function: PlotFFT - | \ *output*\ : | creates plot and returns plot (plt) handle +Relevant Examples (Ex) and TestModels (TM) with weblink to github: + + \ `nMassOscillatorEigenmodes.py `_\ (Ex) + ---- @@ -100,7 +104,7 @@ Function: PlotFFT Function: FileStripSpaces ^^^^^^^^^^^^^^^^^^^^^^^^^ -`FileStripSpaces `__\ (\ ``filename``\ , \ ``outputFilename``\ , \ ``fileCommentChar = ''``\ , \ ``removeDoubleChars = ''``\ ) +`FileStripSpaces `__\ (\ ``filename``\ , \ ``outputFilename``\ , \ ``fileCommentChar = ''``\ , \ ``removeDoubleChars = ''``\ ) - | \ *function description*\ : | strip spaces at beginning / end of lines; this may be sometimes necessary when reading solutions from files that are space-separated @@ -121,7 +125,7 @@ Function: FileStripSpaces Function: DataArrayFromSensorList ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`DataArrayFromSensorList `__\ (\ ``mbs``\ , \ ``sensorNumbers``\ , \ ``positionList = []``\ , \ ``time = ''``\ ) +`DataArrayFromSensorList `__\ (\ ``mbs``\ , \ ``sensorNumbers``\ , \ ``positionList = []``\ , \ ``time = ''``\ ) - | \ *function description*\ : | helper function to create data array from outputs defined by sensorNumbers list [+optional positionList which must have, e.g., local arc-length of beam according to sensor numbers]; if time=='', current sensor values will be used; if time!=[], evaluation will be based on loading values from file or sensor internal data and evaluate at that time @@ -146,7 +150,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: LoadImage ^^^^^^^^^^^^^^^^^^^ -`LoadImage `__\ (\ ``fileName``\ , \ ``trianglesAsLines = True``\ , \ ``verbose = False``\ ) +`LoadImage `__\ (\ ``fileName``\ , \ ``trianglesAsLines = True``\ , \ ``verbose = False``\ ) - | \ *function description*\ : | import image text file as exported from RedrawAndSaveImage() with exportImages.saveImageFormat='TXT'; triangles are converted to lines @@ -168,7 +172,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: PlotImage ^^^^^^^^^^^^^^^^^^^ -`PlotImage `__\ (\ ``imageData``\ , \ ``HT = np.eye(4)``\ , \ ``axesEqual = True``\ , \ ``plot3D = False``\ , \ ``lineWidths = 1``\ , \ ``lineStyles = '-'``\ , \ ``triangleEdgeColors = 'black'``\ , \ ``triangleEdgeWidths = 0.5``\ , \ ``removeAxes = True``\ , \ ``orthogonalProjection = True``\ , \ ``title = ''``\ , \ ``figureName = ''``\ , \ ``fileName = ''``\ , \ ``fontSize = 16``\ , \ ``closeAll = False``\ , \ ``azim = 0.``\ , \ ``elev = 0.``\ ) +`PlotImage `__\ (\ ``imageData``\ , \ ``HT = np.eye(4)``\ , \ ``axesEqual = True``\ , \ ``plot3D = False``\ , \ ``lineWidths = 1``\ , \ ``lineStyles = '-'``\ , \ ``triangleEdgeColors = 'black'``\ , \ ``triangleEdgeWidths = 0.5``\ , \ ``removeAxes = True``\ , \ ``orthogonalProjection = True``\ , \ ``title = ''``\ , \ ``figureName = ''``\ , \ ``fileName = ''``\ , \ ``fontSize = 16``\ , \ ``closeAll = False``\ , \ ``azim = 0.``\ , \ ``elev = 0.``\ ) - | \ *function description*\ : | plot 2D or 3D vector image data as provided by LoadImage(...) using matplotlib diff --git a/docs/RST/pythonUtilities/processing.rst b/docs/RST/pythonUtilities/processing.rst index 99b1042e..03c65648 100644 --- a/docs/RST/pythonUtilities/processing.rst +++ b/docs/RST/pythonUtilities/processing.rst @@ -16,7 +16,7 @@ It includes parameter variation and (genetic) optimization functionality. Function: GetVersionPlatformString ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GetVersionPlatformString `__\ () +`GetVersionPlatformString `__\ () - | \ *function description*\ : | internal function to return Exudyn version string, which allows to identify how results have been obtained @@ -33,7 +33,7 @@ Function: GetVersionPlatformString Function: ProcessParameterList ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ProcessParameterList `__\ (\ ``parameterFunction``\ , \ ``parameterList``\ , \ ``useMultiProcessing``\ , \ ``clusterHostNames = []``\ , \ ``**kwargs``\ ) +`ProcessParameterList `__\ (\ ``parameterFunction``\ , \ ``parameterList``\ , \ ``useMultiProcessing``\ , \ ``clusterHostNames = []``\ , \ ``**kwargs``\ ) - | \ *function description*\ : | processes parameterFunction for given parameters in parameterList, see ParameterVariation @@ -77,7 +77,7 @@ Function: ProcessParameterList Function: ParameterVariation ^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ParameterVariation `__\ (\ ``parameterFunction``\ , \ ``parameters``\ , \ ``useLogSpace = False``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``parameterFunctionData = {}``\ , \ ``clusterHostNames = []``\ , \ ``numberOfThreads = None``\ , \ ``resultsFile = ''``\ , \ ``**kwargs``\ ) +`ParameterVariation `__\ (\ ``parameterFunction``\ , \ ``parameters``\ , \ ``useLogSpace = False``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``parameterFunctionData = {}``\ , \ ``clusterHostNames = []``\ , \ ``numberOfThreads = None``\ , \ ``resultsFile = ''``\ , \ ``**kwargs``\ ) - | \ *function description*\ : | calls successively the function parameterFunction(parameterDict) with variation of parameters in given range; parameterDict is a dictionary, containing the current values of parameters, @@ -122,7 +122,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: GeneticOptimization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`GeneticOptimization `__\ (\ ``objectiveFunction``\ , \ ``parameters``\ , \ ``populationSize = 100``\ , \ ``numberOfGenerations = 10``\ , \ ``elitistRatio = 0.1``\ , \ ``crossoverProbability = 0.25``\ , \ ``crossoverAmount = 0.5``\ , \ ``rangeReductionFactor = 0.7``\ , \ ``distanceFactor = 0.1``\ , \ ``childDistribution = "uniform"``\ , \ ``distanceFactorGenerations = -1``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``clusterHostNames = []``\ , \ ``**kwargs``\ ) +`GeneticOptimization `__\ (\ ``objectiveFunction``\ , \ ``parameters``\ , \ ``populationSize = 100``\ , \ ``numberOfGenerations = 10``\ , \ ``elitistRatio = 0.1``\ , \ ``crossoverProbability = 0.25``\ , \ ``crossoverAmount = 0.5``\ , \ ``rangeReductionFactor = 0.7``\ , \ ``distanceFactor = 0.1``\ , \ ``childDistribution = "uniform"``\ , \ ``distanceFactorGenerations = -1``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``clusterHostNames = []``\ , \ ``parameterFunctionData = {}``\ , \ ``**kwargs``\ ) - | \ *function description*\ : | compute minimum of given objectiveFunction @@ -139,6 +139,7 @@ Function: GeneticOptimization | \ ``distanceFactor``\ : children only survive at a certain relative distance of the current range; must be small enough (< 0.5) to allow individuals to survive; ignored if distanceFactor=0; as a rule of thumb, the distanceFactor should be zero in case that there is only one significant minimum, but if there are many local minima, the distanceFactor should be used to search at several different local minima | \ ``childDistribution``\ : string with name of distribution for producing childs: "normal" (Gaussian, with sigma defining range), "uniform" (exactly in range of childs) | \ ``distanceFactorGenerations``\ : number of generations (populations) at which the distance factor is active; the distance factor is used to find several local minima; finally, convergence is speed up without the distance factor + | \ ``parameterFunctionData``\ : dictionary containing additional data passed to the objectiveFunction inside the parameters with dict key 'functionData'; use this e.g. for passing solver parameters or other settings | \ ``randomizerInitialization``\ : initialize randomizer at beginning of optimization in order to get reproducible results, provide any integer in the range between 0 and 2\*\*32 - 1 (default: no initialization) | \ ``debugMode``\ : if True, additional print out is done | \ ``addComputationIndex``\ : if True, key 'computationIndex' is added to every parameterDict in the call to parameterFunction(), which allows to generate independent output files for every parameter, etc. @@ -173,29 +174,25 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: Minimize ^^^^^^^^^^^^^^^^^^ -`Minimize `__\ (\ ``objectiveFunction``\ , \ ``parameters``\ , \ ``initialGuess = []``\ , \ ``method = 'Nelder-Mead'``\ , \ ``tol = 1e-4``\ , \ ``options = {}``\ , \ ``enforceBounds = True``\ , \ ``debugMode = False``\ , \ ``showProgress = True``\ , \ ``addComputationIndex = False``\ , \ ``storeFunctionValues = True``\ , \ ``**kwargs``\ ) +`Minimize `__\ (\ ``objectiveFunction``\ , \ ``parameters``\ , \ ``initialGuess = []``\ , \ ``method = 'Nelder-Mead'``\ , \ ``tol = 1e-4``\ , \ ``options = {}``\ , \ ``enforceBounds = True``\ , \ ``debugMode = False``\ , \ ``showProgress = True``\ , \ ``addComputationIndex = False``\ , \ ``storeFunctionValues = True``\ , \ ``**kwargs``\ ) - | \ *function description*\ : - | Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). + | Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). Note that in special cases, you should copy this function and adapt to your needs. - | \ *input*\ : | \ ``objectiveFunction``\ : function, which takes the form parameterFunction(parameterDict) and which returns a value or list (or numpy array) which reflects the size of the objective to be minimized | \ ``parameters``\ : given as a dictionary, consist of name and tuple containing the search range for this parameter (begin, end), e.g. 'mass':(10,50) | \ ``storeFunctionValues``\ : if True, objectiveFunction values are computed (additional costs!) and stored in every iteration into valueList | \ ``initialGuess``\ : initial guess. Array of real elements of size (n,), where 'n' is the number of independent variables. If not provided by the user, initialGuess is computed from bounds provided in parameterDict. | \ ``method``\ : solver that should be used, e.g. 'Nelder-Mead', 'Powell', 'CG' etc. A list of available solvers can be found in the documentation of scipy.optimize.minimize(). - | \ ``tol``\ : tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol. For detailed control, use solver-specific options using the 'options' variable. + | \ ``tol``\ : tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol (but this is usually not the tolerance for loss or parameters1). For detailed control, use solver-specific options using the 'options' variable. | \ ``options``\ : dictionary of solver options. Can be used to set absolute and relative error tolerances. Detailed information can be found in the documentation of scipy.optimize.minimize(). | \ ``enforceBounds``\ : if True, ensures that only parameters within the bounds specified in ParameterDict are used for minimization; this may help to avoid, e.g., negative values, but may lead to non-convergence | \ ``verbose``\ : prints solver information into console, e.g. number of iterations 'nit', number of funcion evaluations 'nfev', status etc. - | \ ``showProgress``\ : if True, shows for every iteration objective function value, number of current iteration, time needed for current iteration, maximum number of iterations until solver option 'maxiter' is reached. + | \ ``showProgress``\ : if True, shows for every iteration objective function value, current iteration number, time needed for current iteration, maximum number of iterations and loss (current value of objective function) | \ ``addComputationIndex``\ : if True, key 'computationIndex' is added for consistency reasons with GeneticOptimizaiton to every parameterDict in the call to parameterFunction(); however, the value is always 0, because no multi threading is used in Minimize(...) | \ ``resultsFile``\ : if provided, the results are stored columnwise into the given file and written after every generation; use resultsMonitor.py to track results in realtime | \ ``useScipyBounds``\ : if True, use scipy.optimize.minimize() option 'bounds' to apply bounds on variable specified in ParameterDict. Note, this option is only used by some specific methods of scipy.optimize.minimize()! method='Nelder-Mead' ignores this option for example! if False, option 'enforceBounds' will be set to False! | \ ``args``\ : extra arguments passed to the objective function and its derivatives (fun, jac and hess functions). - | \ ``jac``\ : method for computing the gradient vector. - | \ ``hess``\ : method for computing the Hessian matrix. - | \ ``hessp``\ : hessian of objective function times an arbitrary vector p. - | \ ``constraints``\ : constraints definition (only for COBYLA, SLSQP and trust-constr). - | \ *output*\ : | returns [optimumParameter, optimumValue, parameterList, valueList], containing the optimum parameter set 'optimumParameter', optimum value 'optimumValue', the whole list of parameters parameterList with according objective values 'valueList' - | \ *author*\ : @@ -216,7 +213,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: ComputeSensitivities ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`ComputeSensitivities `__\ (\ ``parameterFunction``\ , \ ``parameters``\ , \ ``scaledByReference = False``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``parameterFunctionData = dict()``\ , \ ``**kwargs``\ ) +`ComputeSensitivities `__\ (\ ``parameterFunction``\ , \ ``parameters``\ , \ ``scaledByReference = False``\ , \ ``debugMode = False``\ , \ ``addComputationIndex = False``\ , \ ``useMultiProcessing = False``\ , \ ``showProgress = True``\ , \ ``parameterFunctionData = dict()``\ , \ ``**kwargs``\ ) - | \ *function description*\ : | Perform a sensitivity analysis by successively calling the function parameterFunction(parameterList[i]) with a one at a time variation of parameters in the defined increments. @@ -256,7 +253,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: PlotOptimizationResults2D ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`PlotOptimizationResults2D `__\ (\ ``parameterList``\ , \ ``valueList``\ , \ ``xLogScale = False``\ , \ ``yLogScale = False``\ ) +`PlotOptimizationResults2D `__\ (\ ``parameterList``\ , \ ``valueList``\ , \ ``xLogScale = False``\ , \ ``yLogScale = False``\ ) - | \ *function description*\ : | visualize results of optimization for every parameter (2D plots) @@ -281,7 +278,7 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: Function: PlotSensitivityResults ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`PlotSensitivityResults `__\ (\ ``valRef``\ , \ ``valuesSorted``\ , \ ``sensitivity``\ , \ ``fVar = None``\ , \ ``strYAxis = None``\ ) +`PlotSensitivityResults `__\ (\ ``valRef``\ , \ ``valuesSorted``\ , \ ``sensitivity``\ , \ ``fVar = None``\ , \ ``strYAxis = None``\ ) - | \ *function description*\ : | visualize results of Sensitivityanalyis for every parameter (2D plots) diff --git a/docs/RST/pythonUtilities/rigidBodyUtilities.rst b/docs/RST/pythonUtilities/rigidBodyUtilities.rst index 6446af20..dcce7d0a 100644 --- a/docs/RST/pythonUtilities/rigidBodyUtilities.rst +++ b/docs/RST/pythonUtilities/rigidBodyUtilities.rst @@ -241,7 +241,7 @@ Function: RotationVector2RotationMatrix Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `stiffFlyballGovernor2.py `_\ (Ex), \ `explicitLieGroupMBSTest.py `_\ (TM), \ `stiffFlyballGovernor.py `_\ (TM) + \ `chatGPTupdate.py `_\ (Ex), \ `stiffFlyballGovernor2.py `_\ (Ex), \ `explicitLieGroupMBSTest.py `_\ (TM), \ `stiffFlyballGovernor.py `_\ (TM) @@ -1363,7 +1363,7 @@ Class function: \_\_init\_\_ Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `craneReevingSystem.py `_\ (Ex), \ `fourBarMechanism3D.py `_\ (Ex), \ `kinematicTreeAndMBS.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `carRollingDiscTest.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM) + \ `addPrismaticJoint.py `_\ (Ex), \ `addRevoluteJoint.py `_\ (Ex), \ `chatGPTupdate.py `_\ (Ex), \ `craneReevingSystem.py `_\ (Ex), \ `fourBarMechanism3D.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `carRollingDiscTest.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM) .. _sec-module-rigidbodyutilities-class-inertiarodx(rigidbodyinertia): @@ -1432,7 +1432,7 @@ Class function: \_\_init\_\_ Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `graphicsDataExample.py `_\ (Ex), \ `particleClusters.py `_\ (Ex), \ `particlesSilo.py `_\ (Ex), \ `tippeTop.py `_\ (Ex), \ `distanceSensor.py `_\ (TM), \ `generalContactFrictionTests.py `_\ (TM) + \ `graphicsDataExample.py `_\ (Ex), \ `particleClusters.py `_\ (Ex), \ `particlesSilo.py `_\ (Ex), \ `ROSExampleMassPoint.py `_\ (Ex), \ `tippeTop.py `_\ (Ex), \ `distanceSensor.py `_\ (TM), \ `generalContactFrictionTests.py `_\ (TM) .. _sec-module-rigidbodyutilities-class-inertiahollowsphere(rigidbodyinertia): diff --git a/docs/RST/pythonUtilities/robotics.special.rst b/docs/RST/pythonUtilities/robotics.special.rst index baa27550..50ce8e25 100644 --- a/docs/RST/pythonUtilities/robotics.special.rst +++ b/docs/RST/pythonUtilities/robotics.special.rst @@ -136,7 +136,7 @@ Function: MassMatrix Relevant Examples (Ex) and TestModels (TM) with weblink to github: - \ `nMassOscillatorEigenmodes.py `_\ (Ex), \ `shapeOptimization.py `_\ (Ex), \ `solverFunctionsTestEigenvalues.py `_\ (Ex), \ `ACFtest.py `_\ (TM), \ `manualExplicitIntegrator.py `_\ (TM), \ `objectFFRFreducedOrderAccelerations.py `_\ (TM), \ `objectFFRFreducedOrderShowModes.py `_\ (TM), \ `objectFFRFreducedOrderStressModesTest.py `_\ (TM) + \ `shapeOptimization.py `_\ (Ex), \ `solverFunctionsTestEigenvalues.py `_\ (Ex), \ `ACFtest.py `_\ (TM), \ `manualExplicitIntegrator.py `_\ (TM), \ `objectFFRFreducedOrderAccelerations.py `_\ (TM), \ `objectFFRFreducedOrderShowModes.py `_\ (TM), \ `objectFFRFreducedOrderStressModesTest.py `_\ (TM), \ `objectFFRFreducedOrderTest.py `_\ (TM) diff --git a/docs/RST/pythonUtilities/signalProcessing.rst b/docs/RST/pythonUtilities/signalProcessing.rst index c1fe5b3d..9ce133b8 100644 --- a/docs/RST/pythonUtilities/signalProcessing.rst +++ b/docs/RST/pythonUtilities/signalProcessing.rst @@ -84,6 +84,10 @@ Function: ComputeFFT - | \ *date*\ : | 02.04.2020 +Relevant Examples (Ex) and TestModels (TM) with weblink to github: + + \ `nMassOscillatorEigenmodes.py `_\ (Ex) + ---- diff --git a/docs/RST/structures/SimulationSettings.rst b/docs/RST/structures/SimulationSettings.rst index 42aee85d..1a0a181b 100644 --- a/docs/RST/structures/SimulationSettings.rst +++ b/docs/RST/structures/SimulationSettings.rst @@ -1,6 +1,9 @@ +.. _sec-simulationsettingsmain: + + ******************* Simulation settings ******************* @@ -449,7 +452,7 @@ LinearSolverSettings has the following items: * | **ignoreSingularJacobian** [type = bool, default = False]: | \ ``simulationSettings.linearSolverSettings.ignoreSingularJacobian``\ | [ONLY implemented for dense, Eigen matrix mode] False: standard way, fails if jacobian is singular; True: use Eigen's FullPivLU (thus only works with LinearSolverType.EigenDense) which handles over- and underdetermined systems; can often resolve redundant constraints, but MAY ALSO LEAD TO ERRONEOUS RESULTS! -* | **pivotThreshold** [type = PReal, default = 0]: +* | **pivotThreshold** [type = UReal, default = 0]: | \ ``simulationSettings.linearSolverSettings.pivotThreshold``\ | [ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity * | **reuseAnalyzedPattern** [type = bool, default = False]: diff --git a/docs/RST/structures/VisualizationSettings.rst b/docs/RST/structures/VisualizationSettings.rst index 053b0e89..b0ab898f 100644 --- a/docs/RST/structures/VisualizationSettings.rst +++ b/docs/RST/structures/VisualizationSettings.rst @@ -1,6 +1,9 @@ +.. _sec-visualizationsettingsmain: + + ********************** Visualization settings ********************** @@ -404,6 +407,69 @@ VSettingsLoads has the following items: +.. _sec-vsettingssensortraces: + +VSettingsSensorTraces +--------------------- + +Visualization settings for traces of sensors. Note that a large number of time points (influenced by simulationSettings.solutionSettings.sensorsWritePeriod) may lead to slow graphics. + +VSettingsSensorTraces has the following items: + +* | **lineWidth** [type = UFloat, default = 2.]: + | \ ``SC.visualizationSettings.sensorTraces.lineWidth``\ + | line width for traces +* | **listOfPositionSensors** [type = ArrayIndex, default = [], size = -1]: + | \ ``SC.visualizationSettings.sensorTraces.listOfPositionSensors``\ + | list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown +* | **listOfTriadSensors** [type = ArrayIndex, default = [], size = -1]: + | \ ``SC.visualizationSettings.sensorTraces.listOfTriadSensors``\ + | list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position +* | **listOfVectorSensors** [type = ArrayIndex, default = [], size = -1]: + | \ ``SC.visualizationSettings.sensorTraces.listOfVectorSensors``\ + | list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position +* | **positionsShowEvery** [type = PInt, default = 1]: + | \ ``SC.visualizationSettings.sensorTraces.positionsShowEvery``\ + | integer value i; out of available sensor data, show every i-th position +* | **sensorsMbsNumber** [type = Index, default = 0]: + | \ ``SC.visualizationSettings.sensorTraces.sensorsMbsNumber``\ + | number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number +* | **showCurrent** [type = bool, default = True]: + | \ ``SC.visualizationSettings.sensorTraces.showCurrent``\ + | show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable +* | **showFuture** [type = bool, default = False]: + | \ ``SC.visualizationSettings.sensorTraces.showFuture``\ + | show trace future to current visualization state if already computed (e.g. in SolutionViewer) +* | **showPast** [type = bool, default = True]: + | \ ``SC.visualizationSettings.sensorTraces.showPast``\ + | show trace previous to current visualization state +* | **showPositionTrace** [type = bool, default = False]: + | \ ``SC.visualizationSettings.sensorTraces.showPositionTrace``\ + | show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True +* | **showTriads** [type = bool, default = False]: + | \ ``SC.visualizationSettings.sensorTraces.showTriads``\ + | if True, show basis vectors from rotation matrices provided by sensors +* | **showVectors** [type = bool, default = False]: + | \ ``SC.visualizationSettings.sensorTraces.showVectors``\ + | if True, show vector quantities according to description in showPositionTrace +* | **traceColors** [type = ArrayFloat, default = [0.2,0.2,0.2,1., 0.8,0.2,0.2,1., 0.2,0.8,0.2,1., 0.2,0.2,0.8,1., 0.2,0.8,0.8,1., 0.8,0.2,0.8,1., 0.8,0.4,0.1,1.], size = -1]: + | \ ``SC.visualizationSettings.sensorTraces.traceColors``\ + | RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue +* | **triadSize** [type = float, default = 0.1 ]: + | \ ``SC.visualizationSettings.sensorTraces.triadSize``\ + | length of triad axes if shown +* | **triadsShowEvery** [type = PInt, default = 1]: + | \ ``SC.visualizationSettings.sensorTraces.triadsShowEvery``\ + | integer value i; out of available sensor data, show every i-th triad +* | **vectorScaling** [type = float, default = 0.01]: + | \ ``SC.visualizationSettings.sensorTraces.vectorScaling``\ + | scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly +* | **vectorsShowEvery** [type = PInt, default = 1]: + | \ ``SC.visualizationSettings.sensorTraces.vectorsShowEvery``\ + | integer value i; out of available sensor data, show every i-th vector + + + .. _sec-vsettingssensors: VSettingsSensors @@ -413,6 +479,9 @@ Visualization settings for sensors. VSettingsSensors has the following items: +* | **traces** [type = VSettingsSensorTraces]: + | \ ``SC.visualizationSettings.sensors.traces``\ + | settings for showing (position) sensor traces and vector plots in the render window * | **defaultColor** [type = Float4, default = [0.6,0.6,0.1,1.], size = 4]: | \ ``SC.visualizationSettings.sensors.defaultColor``\ | default cRGB color for sensors; 4th value is alpha-transparency diff --git a/docs/RST/trackerlog.rst b/docs/RST/trackerlog.rst index a9bb8518..14bf85cd 100644 --- a/docs/RST/trackerlog.rst +++ b/docs/RST/trackerlog.rst @@ -19,15 +19,102 @@ BUG numbers refer to the according issue numbers. General information on current version: -+ Exudyn version = 1.6.164.dev1, -+ last change = 2023-06-12, -+ Number of issues = 1620, -+ Number of resolved issues = 1444 (164 in current version), ++ Exudyn version = 1.7.0, ++ last change = 2023-07-19, ++ Number of issues = 1650, ++ Number of resolved issues = 1470 (0 in current version), + +*********** +Version 1.7 +*********** + + * Version 1.7.0: resolved Issue 1649: release (release) + - description: switch to new release 1.7 + - date resolved: **2023-07-19 16:07**\ , date raised: 2023-07-19 *********** Version 1.6 *********** + * Version 1.6.189: resolved Issue 1648: ReevingSystemSprings (fix) + - description: adjust test example for treating compression forces + - date resolved: **2023-07-17 12:10**\ , date raised: 2023-07-17 + * Version 1.6.188: resolved Issue 1647: sensorTraces (extension) + - description: add vectors and triads to position traces; show current vector or triad and add some further options for visualization, see visualizationSettings sensors.traces + - **notes:** added triads and vectors, showing traces of motion at sensor points + - date resolved: **2023-07-14 18:34**\ , date raised: 2023-07-14 + * Version 1.6.187: resolved Issue 1640: visualization (extension) + - description: show trace of sensor positions (incl. frames) in render window; settings and list of sensors provided in visualizationSettings.sensors.traces with list of sensors, positionTrace, listOfPositionSensors=[] (empty means all position sensors, listOfVectorSensors=[] which can provide according vector quantities for positions; showVectors, vectorScaling=0.001, showPast=True, showFuture=False, showCurrent=True, lineWidth=2 + - date resolved: **2023-07-14 11:20**\ , date raised: 2023-07-11 + * Version 1.6.186: resolved Issue 1646: ArrayFloat (extension) + - description: C++ add type + - date resolved: **2023-07-13 16:27**\ , date raised: 2023-07-13 + * Version 1.6.185: resolved Issue 1645: ReevingSystemSprings (extension) + - description: add way to remove compression forces in rope + - **notes:** added parameter regularizationForce with tanh regularization for avoidance of compressive spring force + - date resolved: **2023-07-12 16:05**\ , date raised: 2023-07-12 + * Version 1.6.184: resolved Issue 1644: Minimize (extension) + - description: processing.Minimize: improve printout of current error of objective function=loss; only print every 1 second + - date resolved: **2023-07-12 09:29**\ , date raised: 2023-07-12 + * Version 1.6.183: :textred:`resolved BUG 1643` : Minimize + - description: processing.Minimize function has an internal bug, such that it does not work with initialGuess=[] + - date resolved: **2023-07-12 09:29**\ , date raised: 2023-07-12 + * Version 1.6.182: :textred:`resolved BUG 1642` : SolutionViewer + - description: record image not working with visualizationSettings useMultiThreadedRendering=True + - date resolved: **2023-07-11 17:58**\ , date raised: 2023-07-11 + * Version 1.6.181: resolved Issue 1641: SolutionViewer (fix) + - description: github issue#51: graphicsDataUserFunction in SolutionViewer not called; add call to graphicsData user functions in redraw image loop + - date resolved: **2023-07-11 17:16**\ , date raised: 2023-07-11 + * Version 1.6.180: resolved Issue 1638: GeneticOptimization (extension) + - description: add argument parameterFunctionData to GeneticOptimization; same as in ParameterVariation, paramterFunctionData allows to pass additional data to the objective function + - date resolved: **2023-07-09 09:15**\ , date raised: 2023-07-09 + * Version 1.6.179: resolved Issue 1637: add ChatGPT update information (extension) + - description: create Python model Examples/chatGPTupdate.py which includes information that is used by ChatGPT4 to improve abilities to create simple models fully automatic + - date resolved: **2023-06-30 15:01**\ , date raised: 2023-06-30 + * Version 1.6.178: resolved Issue 1636: CreateMassPoint (change) + - description: change args referenceCoordinates to referencePosition, initialCoordinates to initialDisplacement, and initialVelocities to initialVelocity to be consistent with CreateRigidBody (but different from MassPoint itself) + - date resolved: **2023-06-30 14:09**\ , date raised: 2023-06-30 + * Version 1.6.177: resolved Issue 1635: SmartRound2String (extension) + - description: add function to basic utilities to enable simple printing of numbers with few digits, including comma dot and not eliminating small numbers, e.g., 1e-5 stays 1e-5 + - date resolved: **2023-06-30 09:22**\ , date raised: 2023-06-30 + * Version 1.6.176: resolved Issue 1634: create directories (extension) + - description: add automatic creation of directories to FEM SaveToFile, plotting and ParameterVariation + - date resolved: **2023-06-29 10:29**\ , date raised: 2023-06-29 + * Version 1.6.175: :textred:`resolved BUG 1633` : GetInterpolatedSignalValue + - description: timeArray needs to be replaced with timeArrayNew in case of 2D input array + - date resolved: **2023-06-28 21:15**\ , date raised: 2023-06-28 + * Version 1.6.174: resolved Issue 1632: PlotFFT (fix) + - description: matplotlib >= 1.7 complains about ax.grid(b=...) as parameter b has been replaced by visible + - date resolved: **2023-06-27 14:15**\ , date raised: 2023-06-27 + * Version 1.6.173: resolved Issue 1626: mutable args itemInterface (fix) + - description: also copy dictionaries, mainly for visualization (flat level, but this should be sufficient) + - date resolved: **2023-06-21 10:40**\ , date raised: 2023-06-21 + * Version 1.6.172: resolved Issue 1627: mutable default args (change) + - description: complete changes and adaptations for default args in Python functions and item interface; note individual adaptations for lists, vectors, matrices and special lists of lists or matrix containers; for itemInterface, anyway all data is copied into C++; for more information see issues 1536, 1540, 1612, 1624, 1625, 1626 + - date resolved: **2023-06-21 10:15**\ , date raised: 2023-06-21 + * Version 1.6.171: resolved Issue 1625: change to default arg None (change) + - description: change default args for Vector2DList, Vector3DList, Vector6DList, Matrix3DList, to None; ArrayNodeIndex, ArrayMarkerIndex, ArraySensorIndex obtain copy method and are copied now; avoid problem of mutable default args + - date resolved: **2023-06-21 00:26**\ , date raised: 2023-06-20 + * Version 1.6.170: resolved Issue 1624: MatrixContainer (change) + - description: change default values for matrix container to None; avoid problem of mutable default args + - date resolved: **2023-06-20 23:39**\ , date raised: 2023-06-20 + * Version 1.6.169: resolved Issue 1540: mutable args itemInterface (check) + - description: copy lists in itemInterface in order to avoid change of default args by user n=NodePoint();n.referenceCoordinates[0]=42;n1=NodePoint() + - **notes:** simple vectors, matrices and lists are copied with np.array(...) while complex matrix and list of array types are now initialized with None + - date resolved: **2023-06-20 22:13**\ , date raised: 2023-04-28 + * Version 1.6.168: resolved Issue 1620: docu MainSystemExtensions (docu) + - description: reorder MainSystemExtensions with separate section for Create functions and one section for remaining functions + - date resolved: **2023-06-19 22:14**\ , date raised: 2023-06-13 + * Version 1.6.167: :textred:`resolved BUG 1622` : mouse click + - description: fix crash on linux if left / right mouse click on render window (related to OpenGL select window) + - **notes:** occurs on WSL with WSLg; using 'export LIBGL_ALWAYS_SOFTWARE=1' will resolve the problem; put this line into your .bashrc + - date resolved: **2023-06-19 22:11**\ , date raised: 2023-06-19 + * Version 1.6.166: :textred:`resolved BUG 1621` : LinearSolverType + - description: fix crash on linux in function SetLinearSolverType + - date resolved: **2023-06-19 20:27**\ , date raised: 2023-06-19 + * Version 1.6.165: resolved Issue 1623: MouseSelectOpenGL (extension) + - description: add optional debbuging output + - date resolved: **2023-06-19 19:56**\ , date raised: 2023-06-19 * Version 1.6.164: resolved Issue 1267: matrix inverse (extension) - description: add pivot threshold to options, may improve redundant constraints problems - **notes:** only available for EigenDense with ignoreSingularJacobian and EXUdense linear solvers @@ -4690,6 +4777,22 @@ Version 0.1 Open issues *********** + * **open issue 1631:** velocityOffset + - description: add to CartesianSpringDamper, RigidBodySpringDamper + - date raised: 2023-06-26 + + * **open issue 1630:** exudyn module + - description: consider settings instead of putting all variables globally into module + - date raised: 2023-06-23 + + * **open issue 1629:** GetSystemState + - description: extend behavior for returning a dictionary with all data incl. accelerations and possibly alg. accelerations for generalized-alpha solver; check also option to link coords, as in issue 1504 + - date raised: 2023-06-23 + + * **open issue 1628:** pickle MainSystem + - description: consider a pickle method for certain objects; add consistent info in description; MainSystem, SimulationSettings, VisualizationSettings + - date raised: 2023-06-23 + * **open issue 1614:** static members - description: LinearSolver GeneralMatrixEXUdense::FactorizeNew has static ResizableMatrix m, which should be turned into class members; add reset method to free memory at solver finalization - date raised: 2023-06-11 @@ -4714,10 +4817,6 @@ Open issues - description: fully add Jacobian functionality for ODE1 loads and add test for ODE1 loads or recycle one - date raised: 2023-05-01 - * **open issue 1540:** mutable args itemInterface - - description: copy lists in itemInterfacein order to avoid change of default args by user n=NodePoint();n.referenceCoordinates[0]=42;n1=NodePoint() - - date raised: 2023-04-28 - * **open issue 1529:** solver - description: solver functions GetSystemJacobian() and GetSystemMassMatrix() need to be extended with arg sparseTriplets=False; if True, it will return CSR sparse triplets, useful for large matrices, e.g. in eigenvalue computation in linearized system - date raised: 2023-04-26 @@ -5163,7 +5262,7 @@ Open issues - date raised: 2021-06-28 * **open issue 0657:** Delete item - - description: add functionality to delete items, adding specific features to re-index nodes in objects/markers, etc. if a node, object or marker is deleted + - description: add functionality to delete items, adding specific features to re-index nodes in objects/markers, etc. if a node, object or marker is deleted; add MaxItemNumber() function to systemData which returns unique name for items even after deletion - date raised: 2021-05-01 * **open issue 0648:** solver tutorial @@ -5378,6 +5477,10 @@ Open issues Known bugs ********** + * :textred:`open BUG 1639:` SolveDynamic FFRF + - description: repeated call to mbs.SolveDynamic gives divergence; attributed to FFRFreducedOrder model; workaround uses repeated build of model before calling solver again; may be related to FFRF or MarkerSuperElement-internal variables + - date raised: 2023-07-10 + * :textred:`open BUG 1085:` GeneralContact - description: generalContactFrictionTests.py gives considerably different results after t=0.05 seconds between Windows and linux compiled version; may be caused by some initialization problems (bugs...); needs further tests - date raised: 2022-05-11 diff --git a/docs/howTo/WSL.txt b/docs/howTo/WSL.txt index f6b4104d..a869ec93 100644 --- a/docs/howTo/WSL.txt +++ b/docs/howTo/WSL.txt @@ -133,17 +133,12 @@ wsl --shutdown => now conda works! conda create -n venvP36 python=3.6 scipy matplotlib -y -conda create -n venvP37 python=3.7 scipy matplotlib tqdm -y -conda create -n venvP38 python=3.8 scipy matplotlib tqdm -y -conda create -n venvP39 python=3.9 scipy matplotlib tqdm -y -conda create -n venvP310 python=3.10 scipy matplotlib tqdm -y -#not yet available: conda create -n venvP311 python=3.11 scipy matplotlib tqdm -y -python 3.11 workaround (graphics does not work with wsl - even if it works with venvP39 !): -conda create -n venvP311 -conda install -c conda-forge python=3.11 -y -conda install tqdm -y -conda install -c conda-forge numpy -y -conda install -c conda-forge matplotlib -y +conda create -n venvP37 python=3.7 scipy matplotlib psutil tqdm -y +conda create -n venvP38 python=3.8 scipy matplotlib psutil tqdm -y +conda create -n venvP39 python=3.9 scipy matplotlib psutil tqdm -y +conda create -n venvP310 python=3.10 scipy matplotlib psutil tqdm -y +conda create -n venvP311 python=3.11 scipy matplotlib psutil tqdm -y + #install windows terminal https://docs.microsoft.com/en-us/windows/terminal/get-started #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ diff --git a/docs/howTo/ubuntuPythonSetup.txt b/docs/howTo/ubuntuPythonSetup.txt index a04c2686..740cf07c 100644 --- a/docs/howTo/ubuntuPythonSetup.txt +++ b/docs/howTo/ubuntuPythonSetup.txt @@ -47,8 +47,11 @@ sudo apt install gcc-7 g++-7 gcc-8 g++-8 gcc-9 g++-9 ==> question: how to activate gcc-8 or 9 for setuptools: import os -os.environ["CC"] = "gcc-8" #use gcc-8.4 on linux -os.environ["CXX"] = "gcc-8" +os.environ["CC"] = "gcc-7" #use gcc-8.4 on linux +os.environ["CXX"] = "gcc-7" +or select (g++ could also be g++-8 or similar): +export CC=/usr/bin/g++ + #or follow these hints to switch between different gcc versions (UBUNTU20.04?): https://linuxconfig.org/how-to-switch-between-multiple-gcc-and-g-compiler-versions-on-ubuntu-20-04-lts-focal-fossa diff --git a/docs/theDoc/MainSystemCreateExt.tex b/docs/theDoc/MainSystemCreateExt.tex new file mode 100644 index 00000000..65313885 --- /dev/null +++ b/docs/theDoc/MainSystemCreateExt.tex @@ -0,0 +1,643 @@ +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L118}{CreateMassPoint}{}}}\label{sec:mainsystemextensions:CreateMassPoint} +({\it name}= '', {\it referencePosition}= [0.,0.,0.], {\it initialDisplacement}= [0.,0.,0.], {\it initialVelocity}= [0.,0.,0.], {\it physicsMass}= 0, {\it gravity}= [0.,0.,0.], {\it graphicsDataList}= [], {\it drawSize}= -1, {\it color}= [-1.,-1.,-1.,-1.], {\it show}= True, {\it create2D}= False, {\it returnDict}= False) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]helper function to create 2D or 3D mass point object and node, using arguments as in NodePoint and MassPoint +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateMassPoint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for object, node is 'Node:'+name +\item[]{\it referencePosition}: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) +\item[]{\it initialDisplacement}: initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) +\item[]{\it initialVelocity}: initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) +\item[]{\it physicsMass}: mass of mass point +\item[]{\it gravity}: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) +\item[]{\it graphicsDataList}: list of GraphicsData for optional mass visualization +\item[]{\it drawSize}: general drawing size of node +\item[]{\it color}: color of node +\item[]{\it show}: True: if graphicsData list is empty, node is shown, otherwise body is shown; otherwise, nothing is shown +\item[]{\it create2D}: if False, create NodePoint2D and MassPoint2D +\item[]{\it returnDict}: if False, returns object index; if True, returns dict of all information on created object and node +\end{itemize} +\item[--] +{\bf output}: Union[dict, ObjectIndex]; returns mass point object index or dict with all data on request (if returnDict=True) +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + mbs.Assemble() + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.numberOfSteps = 1000 + simulationSettings.timeIntegration.endTime = 2 + mbs.SolveDynamic(simulationSettings = simulationSettings) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateMassPoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/springDamperTutorialNew.py}{\texttt{springDamperTutorialNew.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L247}{CreateRigidBody}{}}}\label{sec:mainsystemextensions:CreateRigidBody} +({\it name}= '', {\it referencePosition}= [0.,0.,0.], {\it referenceRotationMatrix}= np.eye(3), {\it initialVelocity}= [0.,0.,0.], {\it initialAngularVelocity}= [0.,0.,0.], {\it initialDisplacement}= None, {\it initialRotationMatrix}= None, {\it inertia}= None, {\it gravity}= [0.,0.,0.], {\it nodeType}= exudyn.NodeType.RotationEulerParameters, {\it graphicsDataList}= [], {\it drawSize}= -1, {\it color}= [-1.,-1.,-1.,-1.], {\it show}= True, {\it create2D}= False, {\it returnDict}= False) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]helper function to create 3D (or 2D) rigid body object and node; all quantities are global (angular velocity, etc.) +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBody. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for object, node is 'Node:'+name +\item[]{\it referencePosition}: reference position vector for rigid body node (always a 3D vector, no matter if 2D or 3D body) +\item[]{\it referenceRotationMatrix}: reference rotation matrix for rigid body node (always 3D matrix, no matter if 2D or 3D body) +\item[]{\it initialVelocity}: initial translational velocity vector for node (always a 3D vector, no matter if 2D or 3D body) +\item[]{\it initialAngularVelocity}: initial angular velocity vector for node (always a 3D vector, no matter if 2D or 3D body) +\item[]{\it 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] +\item[]{\it 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] +\item[]{\it inertia}: an instance of class RigidBodyInertia, see rigidBodyUtilities; may also be from derived class (InertiaCuboid, InertiaMassPoint, InertiaCylinder, ...) +\item[]{\it gravity}: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) +\item[]{\it graphicsDataList}: list of GraphicsData for rigid body visualization; use graphicsDataUtilities function GraphicsData...(...) +\item[]{\it drawSize}: general drawing size of node +\item[]{\it color}: color of node +\item[]{\it show}: True: if graphicsData list is empty, node is shown, otherwise body is shown; False: nothing is shown +\item[]{\it create2D}: if False, create NodePoint2D and MassPoint2D +\item[]{\it returnDict}: if False, returns object index; if True, returns dict of all information on created object and node +\end{itemize} +\item[--] +{\bf output}: Union[dict, ObjectIndex]; returns rigid body object index (or dict with 'nodeNumber', 'objectNumber' and possibly 'loadNumber' and 'markerBodyMass' if returnDict=True) +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4red)]) + mbs.Assemble() + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.numberOfSteps = 1000 + simulationSettings.timeIntegration.endTime = 2 + mbs.SolveDynamic(simulationSettings = simulationSettings) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateRigidBody see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addPrismaticJoint.py}{\texttt{addPrismaticJoint.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/graphicsDataExample.py}{\texttt{graphicsDataExample.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyTutorial3.py}{\texttt{rigidBodyTutorial3.py}} (Ex), + ... +, +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), + ... + +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L469}{CreateSpringDamper}{}}}\label{sec:mainsystemextensions:CreateSpringDamper} +({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it referenceLength}= None, {\it stiffness}= 0., {\it damping}= 0., {\it force}= 0., {\it velocityOffset}= 0., {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]helper function to create SpringDamper connector, using arguments from ObjectConnectorSpringDamper; similar interface as CreateDistanceConstraint(...) +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateSpringDamper. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name +\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types +\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number +\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number +\item[]{\it referenceLength}: if None, length is computed from reference position of bodies or nodes; if not None, this scalar reference length is used for spring +\item[]{\it stiffness}: scalar stiffness coefficient +\item[]{\it damping}: scalar damping coefficient +\item[]{\it force}: scalar additional force applied +\item[]{\it velocityOffset}: scalar offset: if referenceLength is changed over time, the velocityOffset may be changed accordingly to emulate a reference motion +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it drawSize}: general drawing size of connector +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf output}: ObjectIndex; returns index of newly created object +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + 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() + 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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateSpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/springDamperTutorialNew.py}{\texttt{springDamperTutorialNew.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L605}{CreateCartesianSpringDamper}{}}}\label{sec:mainsystemextensions:CreateCartesianSpringDamper} +({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it stiffness}= [0.,0.,0.], {\it damping}= [0.,0.,0.], {\it offset}= [0.,0.,0.], {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]helper function to create CartesianSpringDamper connector, using arguments from ObjectConnectorCartesianSpringDamper +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateCartesianSpringDamper. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name +\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types +\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number +\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number +\item[]{\it stiffness}: stiffness coefficients (as 3D list or numpy array) +\item[]{\it damping}: damping coefficients (as 3D list or numpy array) +\item[]{\it offset}: offset vector (as 3D list or numpy array) +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it drawSize}: general drawing size of connector +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf output}: ObjectIndex; returns index of newly created object +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + oGround = mbs.AddObject(ObjectGround()) + oSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateCartesianSpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L693}{CreateRigidBodySpringDamper}{}}}\label{sec:mainsystemextensions:CreateRigidBodySpringDamper} +({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it stiffness}= np.zeros((6,6)), {\it damping}= np.zeros((6,6)), {\it offset}= [0.,0.,0.,0.,0.,0.], {\it rotationMatrixJoint}= np.eye(3), {\it useGlobalFrame}= True, {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]helper function to create RigidBodySpringDamper connector, using arguments from ObjectConnectorRigidBodySpringDamper +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBodySpringDamper. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name +\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types +\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number +\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number +\item[]{\it stiffness}: stiffness coefficients (as 6D matrix or numpy array) +\item[]{\it damping}: damping coefficients (as 6D matrix or numpy array) +\item[]{\it offset}: offset vector (as 6D list or numpy array) +\item[]{\it 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 frame +\item[]{\it useGlobalFrame}: if False, the rotationMatrixJoint is defined in the local coordinate system of body0 +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it drawSize}: general drawing size of connector +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf output}: ObjectIndex; returns index of newly created object +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + #TODO +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateRigidBodySpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L837}{CreateRevoluteJoint}{}}}\label{sec:mainsystemextensions:CreateRevoluteJoint} +({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it axis}= [], {\it useGlobalFrame}= True, {\it show}= True, {\it axisRadius}= 0.1, {\it axisLength}= 0.4, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]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 +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRevoluteJoint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name +\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be rigid body or ground object +\item[]{\it position}: 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 body0 +\item[]{\it axis}: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 +\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it axisRadius}: radius of axis for connector graphical representation +\item[]{\it axisLength}: length of axis for connector graphical representation +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf 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 +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4steelblue)]) + 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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateRevoluteJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyTutorial3.py}{\texttt{rigidBodyTutorial3.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/solutionViewerTest.py}{\texttt{solutionViewerTest.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/perf3DRigidBodies.py}{\texttt{perf3DRigidBodies.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L935}{CreatePrismaticJoint}{}}}\label{sec:mainsystemextensions:CreatePrismaticJoint} +({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it axis}= [], {\it useGlobalFrame}= True, {\it show}= True, {\it axisRadius}= 0.1, {\it axisLength}= 0.4, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]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 +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreatePrismaticJoint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name +\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be rigid body or ground object +\item[]{\it position}: 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 body0 +\item[]{\it axis}: a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration +\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it axisRadius}: radius of axis for connector graphical representation +\item[]{\it axisLength}: length of axis for connector graphical representation +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf 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 +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4steelblue)]) + 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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreatePrismaticJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addPrismaticJoint.py}{\texttt{addPrismaticJoint.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1025}{CreateSphericalJoint}{}}}\label{sec:mainsystemextensions:CreateSphericalJoint} +({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it constrainedAxes}= [1,1,1], {\it useGlobalFrame}= True, {\it show}= True, {\it jointRadius}= 0.1, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]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 +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateSphericalJoint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name +\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be mass point, rigid body or ground object +\item[]{\it position}: 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 body0 +\item[]{\it constrainedAxes}: flags, which determines which (global) translation axes are constrained; each entry may only be 0 (=free) axis or 1 (=constrained axis) +\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it jointRadius}: radius of sphere for connector graphical representation +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf 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 +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + 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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateSphericalJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1108}{CreateGenericJoint}{}}}\label{sec:mainsystemextensions:CreateGenericJoint} +({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it rotationMatrixAxes}= np.eye(3), {\it constrainedAxes}= [1,1,1, 1,1,1], {\it useGlobalFrame}= True, {\it show}= True, {\it axesRadius}= 0.1, {\it axesLength}= 0.4, {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]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 +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateGenericJoint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name +\item[]{\it bodyNumber0}: a object number for body0, must be rigid body or ground object +\item[]{\it bodyNumber1}: a object number for body1, must be rigid body or ground object +\item[]{\it position}: 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 body0 +\item[]{\it rotationMatrixAxes}: 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 joint +\item[]{\it constrainedAxes}: 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 rotation0 +\item[]{\it useGlobalFrame}: if False, the position is defined in the local coordinate system of body0, otherwise it is defined in global coordinates +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it axesRadius}: radius of axes for connector graphical representation +\item[]{\it axesLength}: length of axes for connector graphical representation +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf 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 +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + 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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateGenericJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/rigidBodyCOMtest.py}{\texttt{rigidBodyCOMtest.py}} (TM) +\ei + +% +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1211}{CreateDistanceConstraint}{}}}\label{sec:mainsystemextensions:CreateDistanceConstraint} +({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it distance}= None, {\it show}= True, {\it drawSize}= -1., {\it color}= color4default) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]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 +\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateDistanceConstraint. +\end{itemize} +\item[--] +{\bf input}: \vspace{-6pt} +\begin{itemize}[leftmargin=1.2cm] +\setlength{\itemindent}{-0.7cm} +\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name +\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types +\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number +\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number +\item[]{\it distance}: if None, distance is computed from reference position of bodies or nodes; if not None, this distance (which must be always larger than zero) is prescribed between the two positions +\item[]{\it show}: if True, connector visualization is drawn +\item[]{\it drawSize}: general drawing size of node +\item[]{\it color}: color of connector +\end{itemize} +\item[--] +{\bf 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 +\item[--] +{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], + physicsMass=1, drawSize = 0.2) + n1 = mbs.GetObject(m1)['nodeNumber'] + oGround = mbs.AddObject(ObjectGround()) + mbs.CreateDistanceConstraint(bodyOrNodeList=[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) +\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} +% + +% +\noindent For examples on CreateDistanceConstraint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) +\ei + +% diff --git a/docs/theDoc/MainSystemExt.tex b/docs/theDoc/MainSystemExt.tex index 9ddf0b04..4d661a64 100644 --- a/docs/theDoc/MainSystemExt.tex +++ b/docs/theDoc/MainSystemExt.tex @@ -56,644 +56,7 @@ % \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L118}{CreateMassPoint}{}}}\label{sec:mainsystemextensions:CreateMassPoint} -({\it name}= '', {\it referenceCoordinates}= [0.,0.,0.], {\it initialCoordinates}= [0.,0.,0.], {\it initialVelocities}= [0.,0.,0.], {\it physicsMass}= 0, {\it gravity}= [0.,0.,0.], {\it graphicsDataList}= [], {\it drawSize}= -1, {\it color}= [-1.,-1.,-1.,-1.], {\it show}= True, {\it create2D}= False, {\it returnDict}= False) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]helper function to create 2D or 3D mass point object and node, using arguments as in NodePoint and MassPoint -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateMassPoint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for object, node is 'Node:'+name -\item[]{\it referenceCoordinates}: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) -\item[]{\it initialCoordinates}: initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) -\item[]{\it initialVelocities}: initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) -\item[]{\it physicsMass}: mass of mass point -\item[]{\it gravity}: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) -\item[]{\it graphicsDataList}: list of GraphicsData for optional mass visualization -\item[]{\it drawSize}: general drawing size of node -\item[]{\it color}: color of node -\item[]{\it show}: True: if graphicsData list is empty, node is shown, otherwise body is shown; otherwise, nothing is shown -\item[]{\it create2D}: if False, create NodePoint2D and MassPoint2D -\item[]{\it returnDict}: if False, returns object index; if True, returns dict of all information on created object and node -\end{itemize} -\item[--] -{\bf output}: Union[dict, ObjectIndex]; returns mass point object index or dict with all data on request (if returnDict=True) -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], - initialVelocities = [2,5,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - mbs.Assemble() - simulationSettings = exu.SimulationSettings() #takes currently set values or default values - simulationSettings.timeIntegration.numberOfSteps = 1000 - simulationSettings.timeIntegration.endTime = 2 - mbs.SolveDynamic(simulationSettings = simulationSettings) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateMassPoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/springDamperTutorialNew.py}{\texttt{springDamperTutorialNew.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L247}{CreateRigidBody}{}}}\label{sec:mainsystemextensions:CreateRigidBody} -({\it name}= '', {\it referencePosition}= [0.,0.,0.], {\it referenceRotationMatrix}= np.eye(3), {\it initialVelocity}= [0.,0.,0.], {\it initialAngularVelocity}= [0.,0.,0.], {\it initialDisplacement}= None, {\it initialRotationMatrix}= None, {\it inertia}= None, {\it gravity}= [0.,0.,0.], {\it nodeType}= exudyn.NodeType.RotationEulerParameters, {\it graphicsDataList}= [], {\it drawSize}= -1, {\it color}= [-1.,-1.,-1.,-1.], {\it show}= True, {\it create2D}= False, {\it returnDict}= False) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]helper function to create 3D (or 2D) rigid body object and node; all quantities are global (angular velocity, etc.) -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBody. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for object, node is 'Node:'+name -\item[]{\it referencePosition}: reference position vector for rigid body node (always a 3D vector, no matter if 2D or 3D body) -\item[]{\it referenceRotationMatrix}: reference rotation matrix for rigid body node (always 3D matrix, no matter if 2D or 3D body) -\item[]{\it initialVelocity}: initial translational velocity vector for node (always a 3D vector, no matter if 2D or 3D body) -\item[]{\it initialAngularVelocity}: initial angular velocity vector for node (always a 3D vector, no matter if 2D or 3D body) -\item[]{\it 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] -\item[]{\it 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] -\item[]{\it inertia}: an instance of class RigidBodyInertia, see rigidBodyUtilities; may also be from derived class (InertiaCuboid, InertiaMassPoint, InertiaCylinder, ...) -\item[]{\it gravity}: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) -\item[]{\it graphicsDataList}: list of GraphicsData for rigid body visualization; use graphicsDataUtilities function GraphicsData...(...) -\item[]{\it drawSize}: general drawing size of node -\item[]{\it color}: color of node -\item[]{\it show}: True: if graphicsData list is empty, node is shown, otherwise body is shown; False: nothing is shown -\item[]{\it create2D}: if False, create NodePoint2D and MassPoint2D -\item[]{\it returnDict}: if False, returns object index; if True, returns dict of all information on created object and node -\end{itemize} -\item[--] -{\bf output}: Union[dict, ObjectIndex]; returns rigid body object index (or dict with 'nodeNumber', 'objectNumber' and possibly 'loadNumber' and 'markerBodyMass' if returnDict=True) -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4red)]) - mbs.Assemble() - simulationSettings = exu.SimulationSettings() #takes currently set values or default values - simulationSettings.timeIntegration.numberOfSteps = 1000 - simulationSettings.timeIntegration.endTime = 2 - mbs.SolveDynamic(simulationSettings = simulationSettings) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateRigidBody see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addPrismaticJoint.py}{\texttt{addPrismaticJoint.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/graphicsDataExample.py}{\texttt{graphicsDataExample.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyTutorial3.py}{\texttt{rigidBodyTutorial3.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyTutorial3withMarkers.py}{\texttt{rigidBodyTutorial3withMarkers.py}} (Ex), - ... -, -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), - ... - -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L469}{CreateSpringDamper}{}}}\label{sec:mainsystemextensions:CreateSpringDamper} -({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it referenceLength}= None, {\it stiffness}= 0., {\it damping}= 0., {\it force}= 0., {\it velocityOffset}= 0., {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]helper function to create SpringDamper connector, using arguments from ObjectConnectorSpringDamper; similar interface as CreateDistanceConstraint(...) -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateSpringDamper. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name -\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types -\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number -\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number -\item[]{\it referenceLength}: if None, length is computed from reference position of bodies or nodes; if not None, this scalar reference length is used for spring -\item[]{\it stiffness}: scalar stiffness coefficient -\item[]{\it damping}: scalar damping coefficient -\item[]{\it force}: scalar additional force applied -\item[]{\it velocityOffset}: scalar offset: if referenceLength is changed over time, the velocityOffset may be changed accordingly to emulate a reference motion -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it drawSize}: general drawing size of connector -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf output}: ObjectIndex; returns index of newly created object -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2,5,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - 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() - 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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateSpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/springDamperTutorialNew.py}{\texttt{springDamperTutorialNew.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L605}{CreateCartesianSpringDamper}{}}}\label{sec:mainsystemextensions:CreateCartesianSpringDamper} -({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it stiffness}= [0.,0.,0.], {\it damping}= [0.,0.,0.], {\it offset}= [0.,0.,0.], {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]helper function to create CartesianSpringDamper connector, using arguments from ObjectConnectorCartesianSpringDamper -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateCartesianSpringDamper. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name -\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types -\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number -\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number -\item[]{\it stiffness}: stiffness coefficients (as 3D list or numpy array) -\item[]{\it damping}: damping coefficients (as 3D list or numpy array) -\item[]{\it offset}: offset vector (as 3D list or numpy array) -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it drawSize}: general drawing size of connector -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf output}: ObjectIndex; returns index of newly created object -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - oGround = mbs.AddObject(ObjectGround()) - oSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateCartesianSpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L693}{CreateRigidBodySpringDamper}{}}}\label{sec:mainsystemextensions:CreateRigidBodySpringDamper} -({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it stiffness}= np.zeros((6,6)), {\it damping}= np.zeros((6,6)), {\it offset}= [0.,0.,0.,0.,0.,0.], {\it rotationMatrixJoint}= np.eye(3), {\it useGlobalFrame}= True, {\it show}= True, {\it drawSize}= -1, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]helper function to create RigidBodySpringDamper connector, using arguments from ObjectConnectorRigidBodySpringDamper -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBodySpringDamper. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for connector; markers get Marker0:name and Marker1:name -\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types -\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number -\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number -\item[]{\it stiffness}: stiffness coefficients (as 6D matrix or numpy array) -\item[]{\it damping}: damping coefficients (as 6D matrix or numpy array) -\item[]{\it offset}: offset vector (as 6D list or numpy array) -\item[]{\it 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 frame -\item[]{\it useGlobalFrame}: if False, the rotationMatrixJoint is defined in the local coordinate system of body0 -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it drawSize}: general drawing size of connector -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf output}: ObjectIndex; returns index of newly created object -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - #TODO -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateRigidBodySpringDamper see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L837}{CreateRevoluteJoint}{}}}\label{sec:mainsystemextensions:CreateRevoluteJoint} -({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it axis}= [], {\it useGlobalFrame}= True, {\it show}= True, {\it axisRadius}= 0.1, {\it axisLength}= 0.4, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]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 -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateRevoluteJoint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name -\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be rigid body or ground object -\item[]{\it position}: 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 body0 -\item[]{\it axis}: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 -\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it axisRadius}: radius of axis for connector graphical representation -\item[]{\it axisLength}: length of axis for connector graphical representation -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf 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 -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4steelblue)]) - 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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateRevoluteJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyTutorial3.py}{\texttt{rigidBodyTutorial3.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/solutionViewerTest.py}{\texttt{solutionViewerTest.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/perf3DRigidBodies.py}{\texttt{perf3DRigidBodies.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L935}{CreatePrismaticJoint}{}}}\label{sec:mainsystemextensions:CreatePrismaticJoint} -({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it axis}= [], {\it useGlobalFrame}= True, {\it show}= True, {\it axisRadius}= 0.1, {\it axisLength}= 0.4, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]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 -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreatePrismaticJoint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name -\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be rigid body or ground object -\item[]{\it position}: 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 body0 -\item[]{\it axis}: a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration -\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it axisRadius}: radius of axis for connector graphical representation -\item[]{\it axisLength}: length of axis for connector graphical representation -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf 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 -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4steelblue)]) - 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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreatePrismaticJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addPrismaticJoint.py}{\texttt{addPrismaticJoint.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1025}{CreateSphericalJoint}{}}}\label{sec:mainsystemextensions:CreateSphericalJoint} -({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it constrainedAxes}= [1,1,1], {\it useGlobalFrame}= True, {\it show}= True, {\it jointRadius}= 0.1, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]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 -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateSphericalJoint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name -\item[]{\it bodyNumbers}: a list of object numbers for body0 and body1; must be mass point, rigid body or ground object -\item[]{\it position}: 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 body0 -\item[]{\it constrainedAxes}: flags, which determines which (global) translation axes are constrained; each entry may only be 0 (=free) axis or 1 (=constrained axis) -\item[]{\it useGlobalFrame}: if False, the point and axis vectors are defined in the local coordinate system of body0 -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it jointRadius}: radius of sphere for connector graphical representation -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf 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 -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - 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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateSphericalJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1108}{CreateGenericJoint}{}}}\label{sec:mainsystemextensions:CreateGenericJoint} -({\it name}= '', {\it bodyNumbers}= [None, None], {\it position}= [], {\it rotationMatrixAxes}= np.eye(3), {\it constrainedAxes}= [1,1,1, 1,1,1], {\it useGlobalFrame}= True, {\it show}= True, {\it axesRadius}= 0.1, {\it axesLength}= 0.4, {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]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 -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateGenericJoint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name -\item[]{\it bodyNumber0}: a object number for body0, must be rigid body or ground object -\item[]{\it bodyNumber1}: a object number for body1, must be rigid body or ground object -\item[]{\it position}: 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 body0 -\item[]{\it rotationMatrixAxes}: 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 joint -\item[]{\it constrainedAxes}: 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 rotation0 -\item[]{\it useGlobalFrame}: if False, the position is defined in the local coordinate system of body0, otherwise it is defined in global coordinates -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it axesRadius}: radius of axes for connector graphical representation -\item[]{\it axesLength}: length of axes for connector graphical representation -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf 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 -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - 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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateGenericJoint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/computeODE2AEeigenvaluesTest.py}{\texttt{computeODE2AEeigenvaluesTest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/driveTrainTest.py}{\texttt{driveTrainTest.py}} (TM), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/rigidBodyCOMtest.py}{\texttt{rigidBodyCOMtest.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/mainSystemExtensions.py\#L1211}{CreateDistanceConstraint}{}}}\label{sec:mainsystemextensions:CreateDistanceConstraint} -({\it name}= '', {\it bodyOrNodeList}= [None, None], {\it localPosition0}= [0.,0.,0.], {\it localPosition1}= [0.,0.,0.], {\it distance}= None, {\it show}= True, {\it drawSize}= -1., {\it color}= color4default) -\end{flushleft} -\setlength{\itemindent}{0.7cm} -\begin{itemize}[leftmargin=0.7cm] -\item[--] -{\bf function description}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]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 -\item[]- NOTE that this function is added to MainSystem via Python function MainSystemCreateDistanceConstraint. -\end{itemize} -\item[--] -{\bf input}: \vspace{-6pt} -\begin{itemize}[leftmargin=1.2cm] -\setlength{\itemindent}{-0.7cm} -\item[]{\it name}: name string for joint; markers get Marker0:name and Marker1:name -\item[]{\it bodyOrNodeList}: a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types -\item[]{\it localPosition0}: local position (as 3D list or numpy array) on body0, if not a node number -\item[]{\it localPosition1}: local position (as 3D list or numpy array) on body1, if not a node number -\item[]{\it distance}: if None, distance is computed from reference position of bodies or nodes; if not None, this distance (which must be always larger than zero) is prescribed between the two positions -\item[]{\it show}: if True, connector visualization is drawn -\item[]{\it drawSize}: general drawing size of node -\item[]{\it color}: color of connector -\end{itemize} -\item[--] -{\bf 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 -\item[--] -{\bf example}: \vspace{-12pt}\ei\begin{lstlisting}[language=Python, xleftmargin=36pt] - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], - physicsMass=1, drawSize = 0.2) - n1 = mbs.GetObject(m1)['nodeNumber'] - oGround = mbs.AddObject(ObjectGround()) - mbs.CreateDistanceConstraint(bodyOrNodeList=[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) -\end{lstlisting}\vspace{-24pt}\bi\item[]\vspace{-24pt}\vspace{12pt}\end{itemize} -% - -% -\noindent For examples on CreateDistanceConstraint see Relevant Examples (Ex) and TestModels (TM) with weblink to github: -\bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/mainSystemExtensionsTests.py}{\texttt{mainSystemExtensionsTests.py}} (TM) -\ei - -% -\begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L227}{PlotSensor}{}}}\label{sec:mainsystemextensions:PlotSensor} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L230}{PlotSensor}{}}}\label{sec:mainsystemextensions:PlotSensor} ({\it sensorNumbers}= [], {\it components}= 0, {\it xLabel}= 'time (s)', {\it yLabel}= None, {\it labels}= [], {\it colorCodeOffset}= 0, {\it newFigure}= True, {\it closeAll}= False, {\it componentsX}= [], {\it title}= '', {\it figureName}= '', {\it fontSize}= 16, {\it colors}= [], {\it lineStyles}= [], {\it lineWidths}= [], {\it markerStyles}= [], {\it markerSizes}= [], {\it markerDensity}= 0.08, {\it rangeX}= [], {\it rangeY}= [], {\it majorTicksX}= 10, {\it majorTicksY}= 10, {\it offsets}= [], {\it factors}= [], {\it subPlot}= [], {\it sizeInches}= [6.4,4.8], {\it fileName}= '', {\it useXYZcomponents}= True, {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -744,6 +107,8 @@ \item[]{\it [*kwargs]}: \item[]{\it minorTicksXon}: if True, turn minor ticks for x-axis on \item[]{\it minorTicksYon}: if True, turn minor ticks for y-axis on +\item[]{\it logScaleX}: use log scale for x-axis +\item[]{\it logScaleY}: use log scale for y-axis \item[]{\it fileCommentChar}: if exists, defines the comment character in files (\#, %, ...) \item[]{\it fileDelimiterChar}: if exists, defines the character indicating the columns for data (',', ' ', ';', ...) \end{itemize} @@ -964,8 +329,8 @@ SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # @@ -1033,8 +398,8 @@ SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # diff --git a/docs/theDoc/abbreviations.tex b/docs/theDoc/abbreviations.tex index bf67eb34..cd097f7b 100644 --- a/docs/theDoc/abbreviations.tex +++ b/docs/theDoc/abbreviations.tex @@ -24,5 +24,5 @@ \acro{Rot}{rotation} \acro{Rxyz}{rotation parameterization: consecutive rotations around x, y and z-axis (Tait-Bryan)} \acro{STL}{STereoLithography} -\acro{T66}{Pl"ucker transformation} +\acro{T66}{Pl\"ucker transformation} \acro{trig}{triangle (in graphics)} diff --git a/docs/theDoc/bibliographyDoc.bib b/docs/theDoc/bibliographyDoc.bib index 020e0c32..b67d41db 100644 --- a/docs/theDoc/bibliographyDoc.bib +++ b/docs/theDoc/bibliographyDoc.bib @@ -859,3 +859,14 @@ @misc{Exudyn2023 year = {2023}, } +@misc{ManzlRL2023, + doi = {doi.org/10.21203/rs.3.rs-3066420/v1}, + howpublished = {preprint, Research Square, \url{https://www.researchsquare.com/article/rs-3066420/v1}}, + author = {Manzl, Peter and Rogov, Oleg and Gerstmayr, Johannes and Mikkola, Aki and Orzechowski, Grzegorz}, + title = {Reliability Evaluation of Reinforcement Learning Methods for Mechanical Systems with Increasing Complexity}, + publisher = {Research Square}, + year = {2023}, +} + + + diff --git a/docs/theDoc/buildDate.tex b/docs/theDoc/buildDate.tex index d03cbc43..87a5c0d8 100644 --- a/docs/theDoc/buildDate.tex +++ b/docs/theDoc/buildDate.tex @@ -1 +1 @@ -build date and time=2023-06-12 14:55 \ No newline at end of file +build date and time=2023-07-19 18:00 \ No newline at end of file diff --git a/docs/theDoc/gettingStarted.tex b/docs/theDoc/gettingStarted.tex index 9232cfc1..79cbe70c 100644 --- a/docs/theDoc/gettingStarted.tex +++ b/docs/theDoc/gettingStarted.tex @@ -105,17 +105,18 @@ There are several journal papers of the developers which were using \codeName\ (list may be incomplete): \bi - \item A. Zw{\"o}lfer, J. Gerstmayr. A concise nodal-based derivation of the floating frame of reference formulation for displacement-based solid finite elements, Journal of Multibody System Dynamics, Vol. 49(3), pp. 291 -- 313, 2020. \ignoreRST{\cite{ZwoelferGerstmayr2020}} - \item S. Holzinger, J. Sch{\"o}berl, J. Gerstmayr. The equations of motion for a rigid body using non-redundant unified local velocity coordinates. Multibody System Dynamics, Vol. 48, pp. 283 -- 309, 2020. \ignoreRST{\cite{HolzingerSchoeberl2020}} - \item S. Holzinger, J. Gerstmayr. Time integration of rigid bodies modelled with three rotation parameters, Multibody System Dynamics, Vol. 53(5), 2021. \ignoreRST{\cite{Holzinger2021}} - \item A. Zw{\"o}lfer, J. Gerstmayr. The nodal-based floating frame of reference formulation with modal reduction. Acta Mechanica, Vol. 232, pp. 835--851 (2021). \ignoreRST{\cite{ZwoelferGerstmayr2021}} - \item M. Pieber, K. Ntarladima, R. Winkler, J. Gerstmayr. A Hybrid ALE Formulation for the Investigation of the Stability of Pipes Conveying Fluid and Axially Moving Beams, ASME Journal of Computational and Nonlinear Dynamics, 2022. \ignoreRST{\cite{PieberNtarladima2022}} - \item S. Holzinger, M. Schieferle, C. Gutmann, M. Hofer, J. Gerstmayr. Modeling and Parameter Identification for a Flexible Rotor with Impacts. Journal of Computational and Nonlinear Dynamics, 2022. \ignoreRST{\cite{HolzingerSchieferle2022}} - \item R. Neurauter, J. Gerstmayr. A novel motion reconstruction method for inertial sensors with constraints, Multibody System Dynamics, 2022. \cite{NeurauterGerstmayr2023} \item J. Gerstmayr. Exudyn -- A C++ based Python package for flexible multibody systems. Preprint, Research Square, 2023. \ignoreRST{\cite{ Exudyn2023}} \url{https://doi.org/10.21203/rs.3.rs-2693700/v1} + \item P. Manzl, O. Rogov, J. Gerstmayr, A. Mikkola, G. Orzechowski. Reliability Evaluation of Reinforcement Learning Methods for Mechanical Systems with Increasing Complexity. Preprint, Research Square, 2023. \ignoreRST{\cite{ManzlRL2023}} \url{https://doi.org/10.21203/rs.3.rs-3066420/v1} \item S. Holzinger, M. Arnold, J. Gerstmayr. Evaluation and Implementation of Lie Group Integration Methods for Rigid Multibody Systems. Preprint, Research Square, 2023. \ignoreRST{\cite{HolzingerArnoldGerst2023}} \url{https://doi.org/10.21203/rs.3.rs-2715112/v1} \item M. Sereinig, P. Manzl, and J. Gerstmayr. Task Dependent Comfort Zone, a Base Placement Strategy for Autonomous Mobile Manipulators using Manipulability Measures, Robotics and Autonomous Systems, submitted. \cite{Sereinig2023comfortZone} + \item R. Neurauter, J. Gerstmayr. A novel motion reconstruction method for inertial sensors with constraints, Multibody System Dynamics, 2022. \cite{NeurauterGerstmayr2023} + \item M. Pieber, K. Ntarladima, R. Winkler, J. Gerstmayr. A Hybrid ALE Formulation for the Investigation of the Stability of Pipes Conveying Fluid and Axially Moving Beams, ASME Journal of Computational and Nonlinear Dynamics, 2022. \ignoreRST{\cite{PieberNtarladima2022}} + \item S. Holzinger, M. Schieferle, C. Gutmann, M. Hofer, J. Gerstmayr. Modeling and Parameter Identification for a Flexible Rotor with Impacts. Journal of Computational and Nonlinear Dynamics, 2022. \ignoreRST{\cite{HolzingerSchieferle2022}} + \item S. Holzinger, J. Gerstmayr. Time integration of rigid bodies modelled with three rotation parameters, Multibody System Dynamics, Vol. 53(5), 2021. \ignoreRST{\cite{Holzinger2021}} + \item A. Zw{\"o}lfer, J. Gerstmayr. The nodal-based floating frame of reference formulation with modal reduction. Acta Mechanica, Vol. 232, pp. 835--851 (2021). \ignoreRST{\cite{ZwoelferGerstmayr2021}} + \item A. Zw{\"o}lfer, J. Gerstmayr. A concise nodal-based derivation of the floating frame of reference formulation for displacement-based solid finite elements, Journal of Multibody System Dynamics, Vol. 49(3), pp. 291 -- 313, 2020. \ignoreRST{\cite{ZwoelferGerstmayr2020}} + \item S. Holzinger, J. Sch{\"o}berl, J. Gerstmayr. The equations of motion for a rigid body using non-redundant unified local velocity coordinates. Multibody System Dynamics, Vol. 48, pp. 283 -- 309, 2020. \ignoreRST{\cite{HolzingerSchoeberl2020}} \ei \mysubsubsection{Developers of \codeName\ and thanks} @@ -159,7 +160,7 @@ So far (2021-07), we tested \bi \item \mybold{Anaconda 2021-11, 64bit, Python 3.9}\footnote{older Anaconda3 versions can be downloaded via the repository archive \texttt{https://repo.anaconda.com/archive/}} - \item Currently, we work with Python 3.6 - Python 3.10 \mybold{conda environments} on Windows, Linux and MacOS (3.8-3.10). + \item Currently, we work with Python 3.6 - Python 3.11 \mybold{conda environments} on Windows, Linux and MacOS (3.8-3.10). \item \mybold{Spyder 5.1.5} (with Python 3.9.7, 64bit) and \mybold{Spyder 4.1.3} (with Python 3.7.7, 64bit), which is included in the Anaconda installation\footnote{Note that it is important that Spyder, Python and \codeName\ are \mybold{either} 32bit \mybold{or} 64bit and are compiled up to the same minor version, i.e., 3.7.x. There will be a strange .DLL error, if you mix up 32/64bit. It is possible to install both, Anaconda 32bit and Anaconda 64bit -- then you should follow the recommendations of paths as suggested by Anaconda installer.}; Spyder works with all virtual environments \ei Many alternative options exist: @@ -187,7 +188,7 @@ You can install most of these packages using \texttt{pip install numpy} (Windows) or \texttt{pip3 install numpy} (Linux). NOTE: as there is only \texttt{numpy} needed (but not for all sub-packages) and \texttt{numpy} supports many variants, we do not add a particular requirement for installation of depending packages. It is not necessary to install \texttt{scipy} as long as you are not using features of \texttt{scipy}. Same reason for \texttt{tkinter} and \texttt{matplotlib}. -For interaction (right-mouse-click, some key-board commands) you need the Python module \texttt{tkinter}. This is included in regular Anaconda distributions (recommended, see below), but on UBUNTU you need to type alike (do not forget the '3', otherwise it installs for Python2 ...): +For interaction (right-mouse-click, some key-board commands) you need the Python module \texttt{tkinter}. This is included in regular Anaconda distributions (recommended, see below), but on Ubuntu you need to type alike (do not forget the '3', otherwise it installs for Python2 ...): \bi \item[] \texttt{sudo apt-get install python3-tk} \ei @@ -199,52 +200,67 @@ \bi \item \exuUrl{https://pypi.org/project/exudyn}{https://pypi.org/project/exudyn} \ei -As with most other packages, in the regular case (if your binary has been pre-built) you just need to do\footnote{If the index of pypi is not updated, it may help to use \texttt{pip install -i https://pypi.org/project/ exudyn} } +As with most other packages, in the regular case (if your binary has been pre-built) you just need to do \bi \item[] \texttt{pip install exudyn} \ei -On Linux (currently only pre-built for UBUNTU, but should work on many other linux platforms), {\bf update pip to at least 20.3} and use +On Ubuntu/Linux, make sure that pip is installed and up-to-date ({\bf update pip to at least 20.3}; otherwise the manylinux wheels will not be accepted!): +\bi + \item[] \texttt{sudo apt install python3-pip} + \item[] \texttt{python3 -m pip install --upgrade} +\ei +Depending on installation the command may read \texttt{pip3} or \texttt{pip}: \bi \item[] \texttt{pip3 install exudyn} \ei -For pre-releases (use with care!), add '$--$pre' flag: +For pre-releases (use with care!), add \texttt{-{}-pre} flag: \bi - \item[] \texttt{pip install exudyn $--$pre} + \item[] \texttt{pip install exudyn -{}-pre -U} +\ei +The \texttt{-U} (identical to \texttt{--upgrade}) flag ensures that the current installed version is also updated in case of a change of the micro version (e.g., from version 1.6.119 to version 1.6.164), otherwise, it will only update if you switch to a newer minor version. + +In some cases (e.g. for AppleM1 or special Linux versions), your pre-built binary will not work due to some incompatibilities. Then you need to build from source as described in the 'Build and install' sections, \refSection{sec:install:installinstructions:buildwindows}. + +\mysubsubsubsection{Troubleshooting pip install} +Pip install may fail, if your linux version does not support the current manylinux version. +This is known for CentOS or simlilar systems which usually support manylinux2014. In this case, you have to build \codeName\ from source, see \refSection{sec:install:installinstructions:buildubuntu}. + +Sometimes, you install exudyn, but when running python, the \texttt{import exudyn} fails. +In case of several environments, check where your installation goes. To guarantee that the pip install goes to the python call, use: +\bi + \item[] \texttt{python -m pip install exudyn} +\ei +which ensures that the used python is calling its associated pip module. + +If the PyPi index is not updated, it may help to use +\bi + \item[] \texttt{pip install -i https://pypi.org/project/ exudyn} \ei -In some cases (e.g. for AppleM1), your pre-built binary will not work due to some incompatibilities. Then you need to build from source as described in the 'Build and install' sections, \refSection{sec:install:installinstructions:buildwindows}. -% -%%+++++++++++++++++++++++++++++++++++++ -%\mysubsubsection{DEPRECATED: Install with Windows MSI installer} -%A simple way to install \codeName\ on Windows 10 (and maybe also Windows 7) is to use \texttt{.msi} installers in the \texttt{main/dist} directory\footnote{It works better \mybold{if you installed only one Python version} and if you installed Anaconda with the option \mybold{'Register Anaconda as my default Python 3.x'} or similar; in other cases you may to specify some installation directories, etc.}: -%\bi -%\item NOTE (2022-03-18): \texttt{.msi} installers are now only available for selected Python versions; however, wheels can be downloaded directly from \exuUrl{https://pypi.org/project/exudyn}{https://pypi.org/project/exudyn}, see below -%\item For the 64bits Python 3.7 version, double click on (version may differ):\ignoreRST{\\} \texttt{exudyn-1.0.248.win-amd64-py3.7.msi} -%\item Follow the instructions of the installer -%\item If Python / Anaconda is not found by the installer, provide the 'Python directory' as the installation directory of Anaconda3, which usually is installed in:\\ -%\texttt{C:$\backslash$ProgramData$\backslash$Anaconda3} -%\ei %+++++++++++++++++++++++++++++++++++++ -\mysubsubsectionlabel{Install from specific Wheel (UBUNTU and Windows)}{sec:install:installinstructions:wheel} +\mysubsubsectionlabel{Install from specific Wheel (Ubuntu and Windows)}{sec:install:installinstructions:wheel} A way to install the Python package \codeName\ is to use the so-called 'wheels' (file ending \texttt{.whl}). +NOTE that this approach usually is not required; just use the pip installer of the previous section! + +\noindent \mybold{Ubuntu}:\vspace{6pt}\\ Wheels can be downloaded directly from \exuUrl{https://pypi.org/project/exudyn/\#files}{https://pypi.org/project/exudyn/\#files}, for many Python versions and architectures. \vspace{6pt}\\ -For UBUNTU18.04 (which by default uses Python 3.6) this may read (version number 1.0.20 may be different): +For Ubuntu 18.04 (which by default uses Python 3.6) this may read (version number 1.0.20 may be different): \bi \item \texttt{Python 3.6, 64bit}: pip3 install dist$\backslash$exudyn-1.0.20-cp36-cp36-linux\_x86\_64.whl \ei -For UBUNTU20.04 (which by default uses Python 3.8) this may read (version number 1.0.20 may be different): +For Ubuntu 20.04 (which by default uses Python 3.8) this may read (version number 1.0.20 may be different): \bi \item \texttt{Python 3.8, 64bit}: pip3 install dist$\backslash$exudyn-1.0.20-cp38-cp38-linux\_x86\_64.whl \ei NOTE that your installation may have environments with different Python versions, so install that \codeName\ version appropriately! -If the wheel installation does not work on UBUNTU, it is highly recommended to build \codeName\ for your specific system as given in \refSection{sec:install:installinstructions:buildubuntu}. +If the wheel installation does not work on Ubuntu, it is highly recommended to build \codeName\ for your specific system as given in \refSection{sec:install:installinstructions:buildubuntu}. \noindent \mybold{Windows}:\vspace{6pt}\\ First, open an Anaconda prompt: \bi \item EITHER calling: START->Anaconda->... OR go to anaconda/Scripts folder and call activate.bat - \item You can check your Python version then, by running \texttt{python}\footnote{\texttt{python3} under UBUNTU 18.04}, the output reads like: + \item You can check your Python version then, by running \texttt{python}\footnote{\texttt{python3} under Ubuntu 18.04}, the output reads like: \bi \item[] \texttt{Python 3.6.5 $|$Anaconda, Inc.$|$ (default, Mar 29 2018, 13:32:41) $[$MSC v.1900 64 bit (AMD64)$]$ on win32} \item[] ... @@ -369,9 +385,9 @@ %++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ %++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ -\mysubsubsectionlabel{Build and install \codeName\ under UBUNTU?}{sec:install:installinstructions:buildubuntu} +\mysubsubsectionlabel{Build and install \codeName\ under Ubuntu?}{sec:install:installinstructions:buildubuntu} % -Having a new UBUNTU 18.04 standard installation (e.g. using a VM virtual box environment), the following steps need to be done (Python \mybold{3.6} is already installed on UBUNTU18.04, otherwise use \texttt{sudo apt install python3})\footnote{see also the youtube video: \exuUrl{https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg\_jtl6fx}{https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg\_jtl6fx}}: +Having a new Ubuntu 18.04 standard installation (e.g. using a VM virtual box environment), the following steps need to be done (Python \mybold{3.6} is already installed on Ubuntu 18.04, otherwise use \texttt{sudo apt install python3})\footnote{see also the youtube video: \exuUrl{https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg\_jtl6fx}{https://www.youtube.com/playlist?list=PLZduTa9mdcmOh5KVUqatD9GzVg\_jtl6fx}}: \noindent First update ... \plainlststyle @@ -380,7 +396,7 @@ \end{lstlisting} \noindent -Install necessary Python libraries and pip3; \texttt{matplotlib} and\texttt{scipy} are not required for installation but used in \codeName\ examples: +Install necessary Python libraries and pip3; \texttt{matplotlib} and \texttt{scipy} are not required for installation but used in \codeName\ examples: \begin{lstlisting} sudo dpkg --configure -a sudo apt install python3-pip @@ -394,12 +410,22 @@ pip3 install pybind11 \end{lstlisting} +\noindent To have dialogs enabled, you need to install \texttt{Tk}/\texttt{tkinter} (may be already installed in your case). +\texttt{Tk} is installed on Ubuntu via apt-get and should then be available in Python: +\begin{lstlisting} + sudo apt-get install python3-tk +\end{lstlisting} + \noindent -If graphics is used (\texttt{\#define USE\_GLFW\_GRAPHICS} in \texttt{BasicDefinitions.h}), you must install the according GLFW and OpenGL libs: +If graphics is used (\texttt{\#define USE\_GLFW\_GRAPHICS} in \texttt{BasicDefinitions.h}), you must install the according GLFW libs: +\begin{lstlisting} + sudo apt-get install libglfw3 libglfw3-dev +\end{lstlisting} + +In some cases, it may be required to install OpenGL and some of the following libraries: \begin{lstlisting} sudo apt-get install freeglut3 freeglut3-dev sudo apt-get install mesa-common-dev - sudo apt-get install libglfw3 libglfw3-dev sudo apt-get install libx11-dev xorg-dev libglew1.5 libglew1.5-dev libglu1-mesa libglu1-mesa-dev libgl1-mesa-glx libgl1-mesa-dev \end{lstlisting} @@ -415,7 +441,7 @@ \item[] \texttt{python3 pythonDev/Examples/rigid3Dexample.py} \ei -\noindent You can also create a UBUNTU wheel which can be easily installed on the same machine (x64), same operating system (UBUNTU18.04) and with same Python version (e.g., 3.6): +\noindent You can also create a Ubuntu wheel which can be easily installed on the same machine (x64), same operating system (Ubuntu 18.04) and with same Python version (e.g., 3.6): \bi \item[] \texttt{sudo pip3 install wheel} \item[] \texttt{sudo python3 setup.py bdist\_wheel --parallel} @@ -423,12 +449,13 @@ \noindent \mybold{Exudyn under Ubuntu / WSL}: \bi - \item Note that \codeName\ also nicely works under WSL (Windows subsystem for linux; tested for Ubuntu18.04) and an according xserver (VcXsrv). - \item Just set the display variable in your .bashrc file accordingly and you can enjoy the OpenGL windows and settings. + \item Note that \codeName\ also nicely works under WSL (Windows subsystem for linux; tested for Ubuntu 18.04) and an according xserver (VcXsrv). + \item In case of old WSL2, just set the display variable in your .bashrc file accordingly and you can enjoy the OpenGL windows and settings. \item It shall be noted that WSL + xserver works better than on MacOS, even for tkinter, multitasking, etc.! So, if you have troubles with your Mac, use a virtual machine with ubuntu and a xserver, that may do better + \item In case of WSLg (since 2021), only the software-OpenGL works; therefore, you have to set (possibly in .bashrc file): \texttt{export LIBGL\_ALWAYS\_SOFTWARE=0} \ei -\noindent \mybold{Exudyn under Raspberry Pi 4b}: +\noindent \mybold{Exudyn under RaspberryPi 4b}: \bi \item Exudyn also compiles under RaspberryPi 4b, Ubuntu Mate 20.04, Python 3.8; current version should compile out of the box using \texttt{python3 setup.py install} command. \item Performance is quite ok and it is even capable to use all cores (but you should add a fan!) @@ -438,7 +465,7 @@ \noindent \mybold{KNOWN issues for linux builds}: \bi \item Using \mybold{WSL2} (Windows subsystem for linux), there occur some conflicts during build because of incompatible windows and linux file systems and builds will not be copied to the dist folder; workaround: go to explorer, right click on 'build' directory and set all rights for authenticated user to 'full access' - \item \mybold{compiler (gcc,g++) conflicts}: It seems that \codeName works well on UBUNTU18.04 with the original \texttt{Python 3.6.9} and \texttt{gcc-7.5.0} version as well as with UBUNTU20.04 with \texttt{Python 3.8.5} and \texttt{gcc-9.3.0}. Upgrading \texttt{gcc} on a linux system with Python 3.6 to, e.g., \texttt{gcc-8.2} showed us a linker error when loading the \codeName\ module in Python -- there are some common restriction using \texttt{gcc} versions different from those with which the Python version has been built. Starting \texttt{python} or \texttt{python3} on your linux machine shows you the \texttt{gcc} version it had been build with. Check your current \texttt{gcc} version with: \texttt{gcc --version} + \item \mybold{compiler (gcc,g++) conflicts}: It seems that \codeName works well on Ubuntu 18.04 with the original \texttt{Python 3.6.9} and \texttt{gcc-7.5.0} version as well as with Ubuntu 20.04 with \texttt{Python 3.8.5} and \texttt{gcc-9.3.0}. Upgrading \texttt{gcc} on a Linux system with Python 3.6 to, e.g., \texttt{gcc-8.2} showed us a linker error when loading the \codeName\ module in Python -- there are some common restriction using \texttt{gcc} versions different from those with which the Python version has been built. Starting \texttt{python} or \texttt{python3} on your linux machine shows you the \texttt{gcc} version it had been build with. Check your current \texttt{gcc} version with: \texttt{gcc --version} \ei %++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ @@ -448,7 +475,7 @@ \bi \item[] \texttt{pip uninstall exudyn} \ei -\noindent To uninstall under UBUNTU, run: +\noindent To uninstall under Ubuntu, run: \bi \item[] \texttt{sudo pip3 uninstall exudyn} \ei @@ -475,7 +502,7 @@ \item link it to your own code \item NOTE: on Linux systems, you mostly need to replace '$/$' with '$\backslash$' \ei - \item Linux, etc.: not fully supported yet; however, all external libraries are Linux-compatible and thus should run with minimum adaptation efforts. + \item Linux, etc.: Use the build methods described above; Visual Studio Code may allow native Python and C++ debugging; switching to other build mechanisms (CMakeLists or scikit-build-core). \ei % %++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ @@ -657,7 +684,7 @@ \end{lstlisting} % % -\item Typical Python \mybold{import error} message on Linux / UBUNTU if Python modules are missing: +\item Typical Python \mybold{import error} message on Linux / Ubuntu if Python modules are missing: \plainlststyle \begin{lstlisting} Python WARNING [file '/home/johannes/.local/lib/python3.6/site-packages/exudyn/solver.py', line 236]: diff --git a/docs/theDoc/interfaces.tex b/docs/theDoc/interfaces.tex index aac8883c..fb3809da 100644 --- a/docs/theDoc/interfaces.tex +++ b/docs/theDoc/interfaces.tex @@ -48,7 +48,7 @@ %++++++++++++++++++++++++++++++++++++++ -\mysubsection{Simulation settings} +\mysubsectionlabel{Simulation settings}{sec:SimulationSettingsMain} This section includes hierarchical structures for simulation settings, e.g., time integration, static solver, Newton iteration and solution file export. %+++++++++++++++++++++++++++++++++++ @@ -312,7 +312,7 @@ \hline \bf Name & \bf type / function return type & \bf size & \bf default value / function args & \bf description \\ \hline ignoreSingularJacobian & bool & & False & [ONLY implemented for dense, Eigen matrix mode] False: standard way, fails if jacobian is singular; True: use Eigen's FullPivLU (thus only works with LinearSolverType.EigenDense) which handles over- and underdetermined systems; can often resolve redundant constraints, but MAY ALSO LEAD TO ERRONEOUS RESULTS!\\ \hline - pivotThreshold & PReal & & 0 & [ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity\\ \hline + pivotThreshold & UReal & & 0 & [ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity\\ \hline reuseAnalyzedPattern & bool & & False & [ONLY available for sparse matrices] True: the Eigen SparseLU solver offers the possibility to reuse an analyzed pattern of a previous factorization; this may reduce total factorization time by a factor of 2 or 3, depending on the matrix type; however, if the matrix patterns heavily change between computations, this may even slow down performance; this flag is set for SparseMatrices in InitializeSolverData(...) and should be handled with care!\\ \hline showCausingItems & bool & & True & False: no output, if solver fails; True: if redundant equations appear, they are resolved such that according solution variables are set to zero; in case of redundant constraints, this may help, but it may lead to erroneous behaviour; for static problems, this may suppress static motion or resolve problems in case of instabilities, but should in general be considered with care!\\ \hline \end{longtable} @@ -373,7 +373,7 @@ %++++++++++++++++++++++++++++++++++++++ -\mysubsection{Visualization settings} +\mysubsectionlabel{Visualization settings}{sec:VisualizationSettingsMain} This section includes hierarchical structures for visualization settings, e.g., drawing of nodes, bodies, connectors, loads and markers and furthermore openGL, window and save image options. For further information, see \refSection{sec:overview:basics:visualizationsettings}. %+++++++++++++++++++++++++++++++++++ @@ -625,6 +625,40 @@ \end{center} +%+++++++++++++++++++++++++++++++++++ + +\mysubsubsubsection{VSettingsSensorTraces} +\label{sec:VSettingsSensorTraces} +Visualization settings for traces of sensors. Note that a large number of time points (influenced by simulationSettings.solutionSettings.sensorsWritePeriod) may lead to slow graphics. + +\noindent VSettingsSensorTraces has the following items: +%reference manual TABLE +\begin{center} + \footnotesize + \begin{longtable}{| p{4.2cm} | p{2.5cm} | p{0.3cm} | p{3.0cm} | p{6cm} |} + \hline + \bf Name & \bf type / function return type & \bf size & \bf default value / function args & \bf description \\ \hline + lineWidth & UFloat & & 2. & line width for traces\\ \hline + listOfPositionSensors & ArrayIndex & -1 & [] & list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown\\ \hline + listOfTriadSensors & ArrayIndex & -1 & [] & list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position\\ \hline + listOfVectorSensors & ArrayIndex & -1 & [] & list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position\\ \hline + positionsShowEvery & PInt & & 1 & integer value i; out of available sensor data, show every i-th position\\ \hline + sensorsMbsNumber & Index & & 0 & number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number\\ \hline + showCurrent & bool & & True & show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable\\ \hline + showFuture & bool & & False & show trace future to current visualization state if already computed (e.g. in SolutionViewer)\\ \hline + showPast & bool & & True & show trace previous to current visualization state\\ \hline + showPositionTrace & bool & & False & show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True\\ \hline + showTriads & bool & & False & if True, show basis vectors from rotation matrices provided by sensors\\ \hline + showVectors & bool & & False & if True, show vector quantities according to description in showPositionTrace\\ \hline + traceColors & ArrayFloat & -1 & [0.2,0.2,0.2,1., 0.8,0.2,0.2,1., 0.2,0.8,0.2,1., 0.2,0.2,0.8,1., 0.2,0.8,0.8,1., 0.8,0.2,0.8,1., 0.8,0.4,0.1,1.] & \tabnewline RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue\\ \hline + triadSize & float & & 0.1 & length of triad axes if shown\\ \hline + triadsShowEvery & PInt & & 1 & integer value i; out of available sensor data, show every i-th triad\\ \hline + vectorScaling & float & & 0.01 & scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly\\ \hline + vectorsShowEvery & PInt & & 1 & integer value i; out of available sensor data, show every i-th vector\\ \hline + \end{longtable} + \end{center} + + %+++++++++++++++++++++++++++++++++++ \mysubsubsubsection{VSettingsSensors} @@ -638,6 +672,7 @@ \begin{longtable}{| p{4.2cm} | p{2.5cm} | p{0.3cm} | p{3.0cm} | p{6cm} |} \hline \bf Name & \bf type / function return type & \bf size & \bf default value / function args & \bf description \\ \hline + traces & VSettingsSensorTraces & & & settings for showing (position) sensor traces and vector plots in the render window\\ \hline defaultColor & Float4 & 4 & [0.6,0.6,0.1,1.] & \tabnewline default cRGB color for sensors; 4th value is alpha-transparency\\ \hline defaultSize & float & & -1. & global sensor size; if -1.f, sensor size is relative to maxSceneSize\\ \hline drawSimplified & bool & & True & draw sensors with simplified symbols\\ \hline diff --git a/docs/theDoc/introduction.tex b/docs/theDoc/introduction.tex index ee7c1680..3644c602 100644 --- a/docs/theDoc/introduction.tex +++ b/docs/theDoc/introduction.tex @@ -365,7 +365,7 @@ % \mysubsubsectionlabel{Simulation settings}{sec:overview:basics:simulationsettings} -The simulation settings consists of a couple of substructures, e.g., for \texttt{solutionSettings}, \texttt{staticSolver}, \texttt{timeIntegration} as well as a couple of general options -- for details see \refSection{sec:SolutionSettings} and \refSection{sec:SimulationSettings}. +The simulation settings consists of a couple of substructures, e.g., for \texttt{solutionSettings}, \texttt{staticSolver}, \texttt{timeIntegration} as well as a couple of general options -- for details see \refSection{sec:SolutionSettings} and \refSection{sec:SimulationSettingsMain}. Simulation settings are needed for every solver. They contain solver-specific parameters (e.g., the way how load steps are applied), information on how solution files are written, and very specific control parameters, e.g., for the Newton solver. @@ -415,19 +415,25 @@ Furthermore, you can use sensors to record particular information, e.g., the displacement of a body's local position, forces or joint data. For viewing sensor results, use the \texttt{PlotSensor} function of the \texttt{exudyn.plot} tool, see the rigid body and joints tutorial. +Finally, the render window allows to show traces (trajectories) of position sensors, sensor vector quantities (e.g., velocity vectors), +or triads given by rotation matrices. For further information, see the \texttt{sensors.traces} structure of \texttt{VisualizationSettings}, \refSection{sec:VSettingsSensorTraces}. \mysubsubsectionlabel{Renderer and 3D graphics}{sec:overview:basics:renderer} A 3D renderer is attached to the simulation. Visualization is started with \texttt{exu.StartRenderer()}, see the examples and tutorials. -For closing, press key 'Q' or Escape or close the window. -\mybold{Note}: -\bi - \item After \texttt{visualizationSettings.window.reallyQuitTimeLimit} seconds a 'do you really want to quit' dialog opens for safety on pressing 'Q'; if no tkinter is available, you just have to press 'Q' twice. For closing the window, you need to click a second time on the close button of the window after \texttt{reallyQuitTimeLimit} seconds (usually 900 seconds). -\ei +In order to show your model in the render window, you have to provide 3D graphics data to the bodies. Flexible bodies (e.g., FFRF-like) can visualize their meshes. Further items (nodes, markers, ...) can be visualized with default settings, however, often you have to turn on drawing or enlarge default sizes to make items visible. Item number can also be shown. +Finally, since version 1.6.188, sensor traces (trajectories) can be shown in the render window, see the \texttt{VisualizationSettings} in \refSection{sec:VisualizationSettingsMain}. + The renderer uses an OpenGL window of a library called GLFW, which is platform-independent. The renderer is set up in a minimalistic way, just to ensure that you can check that the modeling is correct. -There is no way to contruct models inside the renderer. -Note: Try to avoid huge number of triangles in STL files or by creating large number of complex objects, such as spheres or cylinders. +\noindent \mybold{Note}: +\bi + \item For closing the render window, press key 'Q' or Escape or just close the window. + \item There is no way to contruct models inside the renderer (no 'GUI'). + \item Try to avoid huge number of triangles in STL files or by creating large number of complex objects, such as spheres or cylinders. + \item After \texttt{visualizationSettings.window.reallyQuitTimeLimit} seconds a 'do you really want to quit' dialog opens for safety on pressing 'Q'; if no tkinter is available, you just have to press 'Q' twice. For closing the window, you need to click a second time on the close button of the window after \texttt{reallyQuitTimeLimit} seconds (usually 900 seconds). +\ei + \noindent There are some main features in the renderer, using keyboard and mouse, for details see \refSection{sec:graphicsVisualization}: \bi \item press key H to show help in renderer @@ -443,21 +449,27 @@ \item for further keys, see \refSection{sec:GUI:sec:keyboardInput} or press H in renderer \ei % -Depending on your model (size, place, ...), you may need to adjust the following visualization and \texttt{openGL} parameters in \texttt{visualizationSettings}: +Depending on your model (size, place, ...), you may need to adjust the following visualization and \texttt{openGL} parameters in \texttt{visualizationSettings}, see \refSection{sec:VisualizationSettingsMain}: \bi \item change window size \item light and light position \item shadow (turned off by using 0; turned on by using, e.g., a value of 0.3) and shadow polygon offset; shadow slows down graphics performance by a factor of 2-3, depending on your graphics card \item visibility of nodes, markers, etc. in according bodies, nodes, markers, ..., \texttt{visualizationSettings} \item move camera with a selected marker: adjust \texttt{trackMarker} in \texttt{visualizationSettings.interactive} - \item ... (see e.g. \refSection{sec:VSettingsGeneral}) +\ei +\mybold{NOTE}: changing \texttt{visualizationSettings} is not thread-safe, as it allows direct access to the C++ variables. +In most cases, this is not problematic, e.g., turning on/off some view parameters my just lead to some short-time artifacts if +they are changed during redraw. However, more advanced quantities (e.g., \texttt{trackMarker } or changing strings) may lead to problems, +which is why it is strongly recommended to: +\bi + \item set all \texttt{visualizationSettings} \mybold{before start of renderer} \ei \mysubsubsectionlabel{Visualization settings dialog}{sec:overview:basics:visualizationsettings} % Visualization settings are used for user interaction with the model. E.g., the nodes, markers, loads, etc., can be visualized for every model. There are default values, e.g., for the size of nodes, which may be inappropriate for your model. Therefore, you can adjust those parameters. In some cases, huge models require simpler graphics representation, in order not to slow down performance -- e.g., the number of faces to represent a cylinder should be small if there are 10000s of cylinders drawn. Even computation performance can be slowed down, if visualization takes lots of CPU power. However, visualization is performed in a separate thread, which usually does not influence the computation exhaustively. -Details on visualization settings and its substructures are provided in \refSection{sec:VSettingsGeneral} -- \refSection{sec:VisualizationSettings}. These settings may also be edited by pressing 'V' in the active render window (does not work, if there is no active render loop using, e.g., \texttt{SC.WaitForRenderEngineStopFlag()} or +Details on visualization settings and its substructures are provided in \refSection{sec:VisualizationSettingsMain}. These settings may also be edited by pressing 'V' in the active render window (does not work, if there is no active render loop using, e.g., \texttt{SC.WaitForRenderEngineStopFlag()} or \texttt{mbs.WaitForUserToContinue()} ). The visualization settings dialog is shown exemplarily in \fig{fig_visualizationSettings}. Note that this dialog is automatically created and uses Python's \texttt{tkinter}, which is lightweight, but not very well suited if display scalings are large (e.g., on high resolution laptop screens). If working with Spyder, it is recommended to restart Spyder, if display scaling is changed, in order to adjust scaling not only for Spyder but also for \codeName\ . @@ -525,7 +537,7 @@ \mysubsubsectionlabel{Execute Command and Help}{sec:overview:basics:commandAndHelp} % In addition to the Visualization settings dialog, a simple help window opens upon pressing key 'H'. -It is also possible to execute single Python commands during simulation by pressing 'X', which opens a simple dialog, saying 'Single command (press return to execute'. +It is also possible to execute single Python commands during simulation by pressing 'X', which opens a dialog, saying 'Exudyn Command Window'. Note that the dialog may appear behind the visualization window! This dialog may be very helpful in long running computations or in case that you may evaluate variables for debugging. The Python commands are evaluated in the global python scope, meaning that \texttt{mbs} or other variables of your scripts are available. @@ -545,20 +557,20 @@ \noindent You can also do quite fancy things during simulation, e.g., to deactivate joints (of course this may result in strange behavior): \pythonstyle\begin{lstlisting} -n=mbs.systemData.NumberOfObjects() -for i in range(n): - d = mbs.GetObject(i) - #if 'Joint' in d['objectType']: - if 'activeConnector' in d: - mbs.SetObjectParameter(i, 'activeConnector', False) + n=mbs.systemData.NumberOfObjects() + for i in range(n): + d = mbs.GetObject(i) + #if 'Joint' in d['objectType']: + if 'activeConnector' in d: + mbs.SetObjectParameter(i, 'activeConnector', False) \end{lstlisting} Note that you could also change \texttt{visualizationSettings} in this way, but the Visualization settings dialog is much more convenient. Changing \texttt{simulationSettings} is dangerous and must be treated with care. Some parameters, such as \texttt{simulationSettings.timeIntegration.endTime} are copied into the internal solver's \text{mbs.sys['dynamicSolver'].it} structure. -% -Thus, changing \texttt{simulationSettings.timeIntegration.endTime} has no effect. + +Thus, changing \texttt{simulationSettings.timeIntegration.endTime} has no effect during simulation. As a rule of thumb, all variables that are not stored inside the solvers structures may be adjusted by the \texttt{simulationSettings} passed to the solver (which are then not copied internally); see the C++ code for details. However, behavior may change in future and unexpected behavior or and changing \texttt{simulationSettings} will likely cause crashes if you do not know exactly the behavior, e.g., changing output format from text to binary ... ! Specifically, \texttt{newton} and \texttt{discontinuous} settings cannot be changed on the fly as they are copied internally. @@ -827,8 +839,7 @@ \noindent However, there are many \mybold{ways to speed up \codeName\ in general}: \bi \item for models with more than 50 coordinates, switching to sparse solvers might greatly improve speed: \texttt{simulationSettings.linearSolverType = exu.LinearSolverType.EigenSparse} - \item when preferring dense direct solvers, switching to Eigen's PartialPivLU solver might greatly improve speed: \texttt{simulationSettings.linearSolverType = exu.LinearSolverType.EigenDense}; - however, the flag \texttt{simulationSettings.linearSolverSettings.ignoreSingularJacobian=True} will switch to the much slower (but more robust) Eigen's FullPivLU + \item when preferring dense direct solvers, switching to Eigen's PartialPivLU solver might greatly improve speed: \texttt{simulationSettings.linearSolverType = exu.LinearSolverType.EigenDense}; however, the flag \texttt{simulationSettings.linearSolverSettings.ignoreSingularJacobian=True} will switch to the much slower (but more robust) Eigen's FullPivLU \item try to avoid Python functions or try to speed up Python functions \item instead of user functions in objects or loads (computed in every iteration), some problems would also work if these parameters are only updated in \texttt{mbs.SetPreStepUserFunction(...)} \item Python user functions can be speed up using the Python numba package, using \texttt{@jit} in front of functions (for more options, see \exuUrl{https://numba.pydata.org/numba-doc/dev/user/index.html}{https://numba.pydata.org/numba-doc/dev/user/index.html}); Example given in \texttt{Examples/springDamperUserFunctionNumbaJIT.py} showing speedups of factor 4; more complicated Python functions may see speedups of 10 - 50 diff --git a/docs/theDoc/itemDefinition.tex b/docs/theDoc/itemDefinition.tex index 20aeec6d..3ed057a6 100644 --- a/docs/theDoc/itemDefinition.tex +++ b/docs/theDoc/itemDefinition.tex @@ -341,12 +341,12 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidRotor3DFWBW.py}{\texttt{rigidRotor3DFWBW.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidRotor3Dnutation.py}{\texttt{rigidRotor3Dnutation.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidRotor3Drunup.py}{\texttt{rigidRotor3Drunup.py}} (Examples/) +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rr.py}{\texttt{rr.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/fourBarMechanism3D.py}{\texttt{fourBarMechanism3D.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/gyroStability.py}{\texttt{gyroStability.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/humanRobotInteraction.py}{\texttt{humanRobotInteraction.py}} (Examples/) -\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/leggedRobot.py}{\texttt{leggedRobot.py}} (Examples/) \item ... \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/explicitLieGroupIntegratorPythonTest.py}{\texttt{explicitLieGroupIntegratorPythonTest.py}} (TestModels/) @@ -1540,7 +1540,7 @@ sims=exu.SimulationSettings() sims.timeIntegration.numberOfSteps = 10000000 #many steps to see graphics exu.StartRenderer() #perform zoom all (press 'a' several times) after startup to see the sphere - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) exu.StopRenderer() \end{lstlisting} %%RSTCOMPATIBLE @@ -1673,7 +1673,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -1812,7 +1812,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -1960,7 +1960,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current mass position at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(mass, exu.OutputVariableType.Position, [0,0,0])[0] @@ -2101,7 +2101,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current rotor z-rotation at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(rotor, exu.OutputVariableType.Rotation, [0,0,0]) @@ -2350,6 +2350,7 @@ \bi \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigid3Dexample.py}{\texttt{rigid3Dexample.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigidBodyIMUtest.py}{\texttt{rigidBodyIMUtest.py}} (Examples/) +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rr.py}{\texttt{rr.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/fourBarMechanism3D.py}{\texttt{fourBarMechanism3D.py}} (Examples/) @@ -2359,7 +2360,6 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/mouseInteractionExample.py}{\texttt{mouseInteractionExample.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/multiMbsTest.py}{\texttt{multiMbsTest.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/openVRengine.py}{\texttt{openVRengine.py}} (Examples/) -\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/particleClusters.py}{\texttt{particleClusters.py}} (Examples/) \item ... \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/explicitLieGroupIntegratorPythonTest.py}{\texttt{explicitLieGroupIntegratorPythonTest.py}} (TestModels/) @@ -2514,7 +2514,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -2810,7 +2810,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] @@ -3009,7 +3009,7 @@ which denotes the transformation from joint coordinate (scalar) to rotations and translations. We can compute the local joint angular velocity $\tomega_i$ and translational velocity $\wv_i$, as a 6D vector $\vv^J_i$, from \be - \vv^J_i = \vp{\tomega_i}{\wv_i} = \tPhi_i \, q_i + \vv^J_i = \vp{\tomega_i}{\wv_i} = \tPhi_i \, \dot q_i \ee % The joint coordinates, which can be rotational or translational, are stored in the vector @@ -3210,7 +3210,7 @@ simulationSettings = exu.SimulationSettings() #takes currently set values or default values simulationSettings.timeIntegration.numberOfSteps = 1000 #gives very accurate results - exu.SolveDynamic(mbs, simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! + mbs.SolveDynamic(simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! #check final value of angle: q0 = mbs.GetNodeOutput(nGeneric, exu.OutputVariableType.Coordinates) @@ -4286,7 +4286,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveStatic(mbs) + mbs.SolveStatic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(lastNode, exu.OutputVariableType.Displacement)[0] @@ -5111,7 +5111,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] @@ -6385,7 +6385,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -6619,7 +6619,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[1] @@ -6631,6 +6631,7 @@ \bi \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/mouseInteractionExample.py}{\texttt{mouseInteractionExample.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigid3Dexample.py}{\texttt{rigid3Dexample.py}} (Examples/) +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rr.py}{\texttt{rr.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/sliderCrank3DwithANCFbeltDrive2.py}{\texttt{sliderCrank3DwithANCFbeltDrive2.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFcontactCircle.py}{\texttt{ANCFcontactCircle.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFcontactCircle2.py}{\texttt{ANCFcontactCircle2.py}} (Examples/) @@ -6640,7 +6641,6 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/lavalRotor2Dtest.py}{\texttt{lavalRotor2Dtest.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/NGsolvePistonEngine.py}{\texttt{NGsolvePistonEngine.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/NGsolvePostProcessingStresses.py}{\texttt{NGsolvePostProcessingStresses.py}} (Examples/) -\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/objectFFRFreducedOrderNetgen.py}{\texttt{objectFFRFreducedOrderNetgen.py}} (Examples/) \item ... \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/scissorPrismaticRevolute2D.py}{\texttt{scissorPrismaticRevolute2D.py}} (TestModels/) @@ -6864,7 +6864,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[1] @@ -6874,6 +6874,7 @@ % \noindent For examples on ObjectConnectorRigidBodySpringDamper see Relevant Examples and TestModels with weblink: \bi +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ROSExampleMassPoint.py}{\texttt{ROSExampleMassPoint.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/stiffFlyballGovernor2.py}{\texttt{stiffFlyballGovernor2.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/connectorRigidBodySpringDamperTest.py}{\texttt{connectorRigidBodySpringDamperTest.py}} (TestModels/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/rotatingTableTest.py}{\texttt{rotatingTableTest.py}} (TestModels/) @@ -7055,7 +7056,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[0] @@ -7234,7 +7235,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] @@ -7244,6 +7245,7 @@ % \noindent For examples on ObjectConnectorTorsionalSpringDamper see Relevant Examples and TestModels with weblink: \bi +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ROSExampleTurtle.py}{\texttt{ROSExampleTurtle.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/serialRobotInteractiveLimits.py}{\texttt{serialRobotInteractiveLimits.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/serialRobotKinematicTree.py}{\texttt{serialRobotKinematicTree.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/serialRobotTSD.py}{\texttt{serialRobotTSD.py}} (Examples/) @@ -7417,7 +7419,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, @@ -7879,7 +7881,7 @@ mbs.Assemble() sims = exu.SimulationSettings() sims.timeIntegration.endTime = tEnd - exu.SolveDynamic(mbs, sims, solverType=exu.DynamicSolverType.RK67) + mbs.SolveDynamic(sims, solverType=exu.DynamicSolverType.RK67) #check result at default integration time #expect y=x after one period of orbiting (got: 100000.00000000479) @@ -8128,7 +8130,7 @@ \mysubsubsection{ObjectConnectorReevingSystemSprings} \label{sec:item:ObjectConnectorReevingSystemSprings} -A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by $nr$ rigid body markers $[m_0, \, m_1, \, \ldots, \, m_{nr-1}]$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by $m_{c0}$ and $m_{c1}$ . +A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). NOTE that the spring can undergo tension AND compression (in order to avoid compression, use a PreStepUserFunction to turn off stiffness and damping in this case!). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by $nr$ rigid body markers $[m_0, \, m_1, \, \ldots, \, m_{nr-1}]$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by $m_{c0}$ and $m_{c1}$ . \vspace{12pt}\\ \noindent \mybold{Additional information for ObjectConnectorReevingSystemSprings}: @@ -8155,6 +8157,7 @@ dampingPerLength & UReal & & 0. & axial damping per length [SI:N/(m/s)/m] of rope; the effective damping coefficient of the reeving system is computed as $DA/L$ in which $L$ is the current length of the rope\\ \hline dampingTorsional & UReal & & 0. & torsional damping [SI:Nms] between sheaves; this effect can damp rotations around the rope axis, pairwise between sheaves; this parameter is experimental\\ \hline dampingShear & UReal & & 0. & damping of shear motion [SI:Ns] between sheaves; this effect can damp motion perpendicular to the rope between each pair of sheaves; this parameter is experimental\\ \hline + regularizationForce & Real & & 0.1 & small regularization force [SI:N] in order to avoid large compressive forces; this regularization force can either be $<0$ (using a linear tension/compression spring model) or $>0$, which restricts forces in the rope to be always $\ge -F_{reg}$. Note that smaller forces lead to problems in implicit integrators and smaller time steps. For explicit integrators, this force can be chosen close to zero.\\ \hline referenceLength & Real & & 0. & reference length for computation of roped force\\ \hline sheavesAxes & Vector3DList & & [] & list of local vectors axes of sheaves; vectors refer to rigid body markers given in list of markerNumbers; first and last axes are ignored, as they represent the attachment of the rope ends\\ \hline sheavesRadii & Vector & & [] & radius for each sheave, related to list of markerNumbers and list of sheaveAxes; first and last radii must always be zero.\\ \hline @@ -8186,6 +8189,7 @@ \rowTable{dampingPerLength}{$DA$}{} \rowTable{dampingTorsional}{$DT$}{} \rowTable{dampingShear}{$DS$}{} +\rowTable{regularizationForce}{$F_{reg}$}{} \rowTable{referenceLength}{$L_{ref}$}{} \rowTable{sheavesAxes}{$\lv_a = [\LU{m0}{\av_0},\, \LU{m1}{\av_1},\, \ldots ] in [\Rcal^{3}, ...]$}{} \rowTable{sheavesRadii}{$\lv_r = [r_0,\, r_1,\, \ldots]\tp \in \Rcal^{n}$}{} @@ -8312,10 +8316,21 @@ \dot L_0 = f_0 \cdot \dot q_{m_{c0}} + f_1 \cdot \dot q_{m_{c1}}, \quad \ee while we set $L_0 = L_{ref}$ and $\dot L_0=0$ otherwise. - The force in the reeving system (assumed to be constant all over the rope) reads + The linear force in the reeving system (assumed to be constant all over the rope) is computed as + \be + F_{lin} = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} + \ee + The rope force is computed from \be - F = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} + F = \begin{cases} F_{lin} \quad \mathrm{if} \quad F_{lin} > 0 \\ + F_{reg} \cdot \mathrm{tanh}(F_{lin}/F_{reg})\quad \mathrm{else} + \end{cases} \ee + Which allows small compressive forces $F_{reg}$. + In case that $F_{reg} < 0$, compressive forces are not regularized (linear spring). + The case $F_{reg} = 0$ will be used in future only in combination with a data node, + which allows switching similar as in friction and contact elements. + Note that in case of $L_0=0$, the term $\frac{1}{L_0}$ is replaced by $1000$. However, this case must be avoided by the user by choosing appropriate parameters for the system. @@ -9516,7 +9531,7 @@ sims=exu.SimulationSettings() sims.timeIntegration.generalizedAlpha.spectralRadius=0.7 - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Position)[0] @@ -9735,7 +9750,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[0] @@ -10152,7 +10167,7 @@ sims=exu.SimulationSettings() solverType = exu.DynamicSolverType.RK44 - exu.SolveDynamic(mbs, solverType=solverType, simulationSettings=sims) + mbs.SolveDynamic(solverType=solverType, simulationSettings=sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nODE1, exu.OutputVariableType.Coordinates)[0] @@ -10378,7 +10393,7 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/beltDriveReevingSystem.py}{\texttt{beltDriveReevingSystem.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/beltDrivesComparison.py}{\texttt{beltDrivesComparison.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Examples/) -\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/CMSexampleCourse.py}{\texttt{CMSexampleCourse.py}} (Examples/) +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Examples/) \item ... \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/abaqusImportTest.py}{\texttt{abaqusImportTest.py}} (TestModels/) @@ -10856,7 +10871,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] @@ -11508,6 +11523,7 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/interactiveTutorial.py}{\texttt{interactiveTutorial.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/pendulumVerify.py}{\texttt{pendulumVerify.py}} (Examples/) +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ROSExampleMassPoint.py}{\texttt{ROSExampleMassPoint.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/solutionViewerTest.py}{\texttt{solutionViewerTest.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/SpringDamperMassUserFunction.py}{\texttt{SpringDamperMassUserFunction.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/springDamperTutorialNew.py}{\texttt{springDamperTutorialNew.py}} (Examples/) @@ -11515,7 +11531,6 @@ \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFcantileverTestDyn.py}{\texttt{ANCFcantileverTestDyn.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFcontactCircle.py}{\texttt{ANCFcontactCircle.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFcontactCircle2.py}{\texttt{ANCFcontactCircle2.py}} (Examples/) -\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ANCFmovingRigidbody.py}{\texttt{ANCFmovingRigidbody.py}} (Examples/) \item ... \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/perf3DRigidBodies.py}{\texttt{perf3DRigidBodies.py}} (TestModels/) @@ -11707,7 +11722,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[2] @@ -12181,6 +12196,7 @@ % \noindent For examples on SensorKinematicTree see Relevant Examples and TestModels with weblink: \bi +\item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/serialRobotInverseKinematics.py}{\texttt{serialRobotInverseKinematics.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/serialRobotKinematicTreeDigging.py}{\texttt{serialRobotKinematicTreeDigging.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/stiffFlyballGovernorKT.py}{\texttt{stiffFlyballGovernorKT.py}} (Examples/) \item \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/kinematicTreeAndMBStest.py}{\texttt{kinematicTreeAndMBStest.py}} (TestModels/) @@ -12399,7 +12415,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() if False: from exudyn.plot import PlotSensor diff --git a/docs/theDoc/manual_interfaces.tex b/docs/theDoc/manual_interfaces.tex index 0c5121e4..ed0bf78c 100644 --- a/docs/theDoc/manual_interfaces.tex +++ b/docs/theDoc/manual_interfaces.tex @@ -359,9 +359,9 @@ \end{center} %++++++++++++++++++++ -\mysubsubsection{MainSystem Python extensions} -\label{sec:mainsystem:pythonExtensions} -This section represents [experimental] 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 \texttt{exudyn.mainSystemExtensions} or \texttt{exudyn.utilities} +\mysubsubsection{MainSystem extensions (create)} +\label{sec:mainsystem:pythonExtensionsCreate} +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 \texttt{exudyn.mainSystemExtensions} or \texttt{exudyn.utilities} \pythonstyle \begin{lstlisting}[language=Python, firstnumber=1] @@ -374,16 +374,33 @@ # #create rigid body b1=mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[0.1,0.1,1]), - referencePosition = [1,0,0], - gravity = [0,0,-9.81]) + referencePosition = [1,0,0], + gravity = [0,0,-9.81]) +\end{lstlisting} + +\input{MainSystemCreateExt.tex} + + +%++++++++++++++++++++ +\mysubsubsection{MainSystem extensions (general)} +\label{sec:mainsystem:pythonExtensions} +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 \texttt{exudyn.mainSystemExtensions} or \texttt{exudyn.utilities} + +\pythonstyle +\begin{lstlisting}[language=Python, firstnumber=1] + +#this example sketches the usage +#for complete examples see Examples/ or TestModels/ folders +#create some multibody system (mbs) first: +# ... +# +#compute system degree of freedom: +mbs.ComputeSystemDegreeOfFreedom(verbose=True) # -mbs.Assemble() #call solver function directly from mbs: -mbs.ComputeSystemDegreeOfFreedom() -simulationSettings = exu.SimulationSettings() -mbs.SolveDynamic(simulationSettings) +mbs.SolveDynamic(exu.SimulationSettings()) # -#plot sensor sBody0 directly from mbs: +#plot sensor directly from mbs: mbs.PlotSensor(...) \end{lstlisting} @@ -1039,6 +1056,8 @@ len(data) & return length of the Vector3DList, using len(data) where data is the Vector3DList\\ \hline data[index]= ... & set list item 'index' with data, write: data[index] = ...\\ \hline ... = data[index] & get copy of list item with 'index' as vector\\ \hline + \_\_copy\_\_() & copy method to be used for copy.copy(...); in fact does already deep copy\\ \hline + \_\_deepcopy\_\_() & deepcopy method to be used for copy.copy(...)\\ \hline \_\_repr\_\_() & return the string representation of the Vector3DList data, e.g.: print(data)\\ \hline \end{longtable} \end{center} @@ -1065,6 +1084,8 @@ len(data) & return length of the Vector2DList, using len(data) where data is the Vector2DList\\ \hline data[index]= ... & set list item 'index' with data, write: data[index] = ...\\ \hline ... = data[index] & get copy of list item with 'index' as vector\\ \hline + \_\_copy\_\_() & copy method to be used for copy.copy(...); in fact does already deep copy\\ \hline + \_\_deepcopy\_\_() & deepcopy method to be used for copy.copy(...)\\ \hline \_\_repr\_\_() & return the string representation of the Vector2DList data, e.g.: print(data)\\ \hline \end{longtable} \end{center} @@ -1088,6 +1109,8 @@ len(data) & return length of the Vector6DList, using len(data) where data is the Vector6DList\\ \hline data[index]= ... & set list item 'index' with data, write: data[index] = ...\\ \hline ... = data[index] & get copy of list item with 'index' as vector\\ \hline + \_\_copy\_\_() & copy method to be used for copy.copy(...); in fact does already deep copy\\ \hline + \_\_deepcopy\_\_() & deepcopy method to be used for copy.copy(...)\\ \hline \_\_repr\_\_() & return the string representation of the Vector6DList data, e.g.: print(data)\\ \hline \end{longtable} \end{center} diff --git a/docs/theDoc/pythonUtilitiesDescription.tex b/docs/theDoc/pythonUtilitiesDescription.tex index f5d007a7..1dcbe396 100644 --- a/docs/theDoc/pythonUtilitiesDescription.tex +++ b/docs/theDoc/pythonUtilitiesDescription.tex @@ -233,7 +233,18 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L90}{DiagonalMatrix}{}}}\label{sec:basicUtilities:DiagonalMatrix} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L84}{SmartRound2String}{}}}\label{sec:basicUtilities:SmartRound2String} +({\it x}, {\it prec}= 3) +\end{flushleft} +\setlength{\itemindent}{0.7cm} +\begin{itemize}[leftmargin=0.7cm] +\item[--] +{\bf function description}: round to max number of digits; may give more digits if this is shorter; using in general the format() with '.g' option, but keeping decimal point and using exponent where necessary +\vspace{12pt}\end{itemize} +% +\noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ +\begin{flushleft} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L99}{DiagonalMatrix}{}}}\label{sec:basicUtilities:DiagonalMatrix} ({\it rowsColumns}, {\it value}= 1) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -253,7 +264,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L104}{NormL2}{}}}\label{sec:basicUtilities:NormL2} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L113}{NormL2}{}}}\label{sec:basicUtilities:NormL2} ({\it vector}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -284,7 +295,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L113}{VSum}{}}}\label{sec:basicUtilities:VSum} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L122}{VSum}{}}}\label{sec:basicUtilities:VSum} ({\it vector}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -314,7 +325,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L122}{VAdd}{}}}\label{sec:basicUtilities:VAdd} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L131}{VAdd}{}}}\label{sec:basicUtilities:VAdd} ({\it v0}, {\it v1}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -345,7 +356,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L133}{VSub}{}}}\label{sec:basicUtilities:VSub} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L142}{VSub}{}}}\label{sec:basicUtilities:VSub} ({\it v0}, {\it v1}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -371,7 +382,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L144}{VMult}{}}}\label{sec:basicUtilities:VMult} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L153}{VMult}{}}}\label{sec:basicUtilities:VMult} ({\it v0}, {\it v1}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -386,7 +397,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L154}{ScalarMult}{}}}\label{sec:basicUtilities:ScalarMult} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L163}{ScalarMult}{}}}\label{sec:basicUtilities:ScalarMult} ({\it scalar}, {\it v}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -410,7 +421,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L163}{Normalize}{}}}\label{sec:basicUtilities:Normalize} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L172}{Normalize}{}}}\label{sec:basicUtilities:Normalize} ({\it v}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -435,7 +446,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L179}{Vec2Tilde}{}}}\label{sec:basicUtilities:Vec2Tilde} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L188}{Vec2Tilde}{}}}\label{sec:basicUtilities:Vec2Tilde} ({\it v}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -462,7 +473,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L186}{Tilde2Vec}{}}}\label{sec:basicUtilities:Tilde2Vec} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L195}{Tilde2Vec}{}}}\label{sec:basicUtilities:Tilde2Vec} ({\it m}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -477,7 +488,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L213}{GaussIntegrate}{}}}\label{sec:basicUtilities:GaussIntegrate} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L222}{GaussIntegrate}{}}}\label{sec:basicUtilities:GaussIntegrate} ({\it functionOfX}, {\it integrationOrder}, {\it a}, {\it b}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -499,7 +510,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L249}{LobattoIntegrate}{}}}\label{sec:basicUtilities:LobattoIntegrate} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/basicUtilities.py\#L258}{LobattoIntegrate}{}}}\label{sec:basicUtilities:LobattoIntegrate} ({\it functionOfX}, {\it integrationOrder}, {\it a}, {\it b}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -756,7 +767,7 @@ \item[]Notes: internal CSR matrix storage format contains 3 float numbers per row: [row, column, value], can be converted to scipy csr sparse matrices with function CSRtoScipySparseCSR(...) \ei \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L40}{CompressedRowSparseToDenseMatrix}{}}}\label{sec:FEM:CompressedRowSparseToDenseMatrix} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L43}{CompressedRowSparseToDenseMatrix}{}}}\label{sec:FEM:CompressedRowSparseToDenseMatrix} ({\it sparseData}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -771,7 +782,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L49}{MapSparseMatrixIndices}{}}}\label{sec:FEM:MapSparseMatrixIndices} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L52}{MapSparseMatrixIndices}{}}}\label{sec:FEM:MapSparseMatrixIndices} ({\it matrix}, {\it sorting}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -782,7 +793,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L57}{VectorDiadicUnitMatrix3D}{}}}\label{sec:FEM:VectorDiadicUnitMatrix3D} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L60}{VectorDiadicUnitMatrix3D}{}}}\label{sec:FEM:VectorDiadicUnitMatrix3D} ({\it v}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -793,7 +804,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L64}{CyclicCompareReversed}{}}}\label{sec:FEM:CyclicCompareReversed} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L67}{CyclicCompareReversed}{}}}\label{sec:FEM:CyclicCompareReversed} ({\it list1}, {\it list2}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -804,7 +815,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L73}{AddEntryToCompressedRowSparseArray}{}}}\label{sec:FEM:AddEntryToCompressedRowSparseArray} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L76}{AddEntryToCompressedRowSparseArray}{}}}\label{sec:FEM:AddEntryToCompressedRowSparseArray} ({\it sparseData}, {\it row}, {\it column}, {\it value}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -820,7 +831,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L91}{CSRtoRowsAndColumns}{}}}\label{sec:FEM:CSRtoRowsAndColumns} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L94}{CSRtoRowsAndColumns}{}}}\label{sec:FEM:CSRtoRowsAndColumns} ({\it sparseMatrixCSR}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -831,7 +842,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L97}{CSRtoScipySparseCSR}{}}}\label{sec:FEM:CSRtoScipySparseCSR} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L100}{CSRtoScipySparseCSR}{}}}\label{sec:FEM:CSRtoScipySparseCSR} ({\it sparseMatrixCSR}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -850,7 +861,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L105}{ScipySparseCSRtoCSR}{}}}\label{sec:FEM:ScipySparseCSRtoCSR} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L108}{ScipySparseCSRtoCSR}{}}}\label{sec:FEM:ScipySparseCSRtoCSR} ({\it scipyCSR}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -861,7 +872,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L113}{ResortIndicesOfCSRmatrix}{}}}\label{sec:FEM:ResortIndicesOfCSRmatrix} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L116}{ResortIndicesOfCSRmatrix}{}}}\label{sec:FEM:ResortIndicesOfCSRmatrix} ({\it mXXYYZZ}, {\it numberOfRows}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -877,7 +888,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L131}{ResortIndicesOfNGvector}{}}}\label{sec:FEM:ResortIndicesOfNGvector} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L134}{ResortIndicesOfNGvector}{}}}\label{sec:FEM:ResortIndicesOfNGvector} ({\it vXXYYZZ}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -888,7 +899,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L151}{ResortIndicesExudyn2NGvector}{}}}\label{sec:FEM:ResortIndicesExudyn2NGvector} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L154}{ResortIndicesExudyn2NGvector}{}}}\label{sec:FEM:ResortIndicesExudyn2NGvector} ({\it vXYZXYZ}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -899,7 +910,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L288}{ConvertHexToTrigs}{}}}\label{sec:FEM:ConvertHexToTrigs} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L291}{ConvertHexToTrigs}{}}}\label{sec:FEM:ConvertHexToTrigs} ({\it nodeNumbers}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -919,7 +930,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L299}{ConvertTetToTrigs}{}}}\label{sec:FEM:ConvertTetToTrigs} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L302}{ConvertTetToTrigs}{}}}\label{sec:FEM:ConvertTetToTrigs} ({\it nodeNumbers}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -932,7 +943,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L311}{ConvertDenseToCompressedRowMatrix}{}}}\label{sec:FEM:ConvertDenseToCompressedRowMatrix} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L314}{ConvertDenseToCompressedRowMatrix}{}}}\label{sec:FEM:ConvertDenseToCompressedRowMatrix} ({\it denseMatrix}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -943,7 +954,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L359}{ReadMatrixFromAnsysMMF}{}}}\label{sec:FEM:ReadMatrixFromAnsysMMF} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L362}{ReadMatrixFromAnsysMMF}{}}}\label{sec:FEM:ReadMatrixFromAnsysMMF} ({\it fileName}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -991,7 +1002,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L400}{ReadMatrixDOFmappingVectorFromAnsysTxt}{}}}\label{sec:FEM:ReadMatrixDOFmappingVectorFromAnsysTxt} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L403}{ReadMatrixDOFmappingVectorFromAnsysTxt}{}}}\label{sec:FEM:ReadMatrixDOFmappingVectorFromAnsysTxt} ({\it fileName}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1008,7 +1019,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L456}{ReadNodalCoordinatesFromAnsysTxt}{}}}\label{sec:FEM:ReadNodalCoordinatesFromAnsysTxt} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L459}{ReadNodalCoordinatesFromAnsysTxt}{}}}\label{sec:FEM:ReadNodalCoordinatesFromAnsysTxt} ({\it fileName}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1039,7 +1050,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L535}{ReadElementsFromAnsysTxt}{}}}\label{sec:FEM:ReadElementsFromAnsysTxt} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L538}{ReadElementsFromAnsysTxt}{}}}\label{sec:FEM:ReadElementsFromAnsysTxt} ({\it fileName}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1070,7 +1081,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L958}{CMSObjectComputeNorm}{}}}\label{sec:FEM:CMSObjectComputeNorm} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L961}{CMSObjectComputeNorm}{}}}\label{sec:FEM:CMSObjectComputeNorm} ({\it mbs}, {\it objectNumber}, {\it outputVariableType}, {\it norm}= 'max', {\it nodeNumberList}= []) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1111,7 +1122,7 @@ \vspace{24pt}\end{itemize} % \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L642}{Strain2Stress}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):Strain2Stress} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L645}{Strain2Stress}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):Strain2Stress} ({\it self}, {\it strain}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1121,7 +1132,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L653}{StrainVector2StressVector}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):StrainVector2StressVector} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L656}{StrainVector2StressVector}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):StrainVector2StressVector} ({\it self}, {\it strainVector}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1131,7 +1142,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L657}{StrainVector2StressVector2D}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):StrainVector2StressVector2D} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L660}{StrainVector2StressVector2D}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):StrainVector2StressVector2D} ({\it self}, {\it strainVector2D}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1141,7 +1152,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L666}{LameParameters}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):LameParameters} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L669}{LameParameters}{}}}\label{sec:FEM:KirchhoffMaterial(MaterialBaseClass):LameParameters} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1175,7 +1186,7 @@ this class holds all data for ObjectFFRF user functions \vspace{3pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L749}{\_\_init\_\_}{}}}\label{sec:FEM:ObjectFFRFinterface:__init__} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L752}{\_\_init\_\_}{}}}\label{sec:FEM:ObjectFFRFinterface:__init__} ({\it self}, {\it femInterface}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1191,7 +1202,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L794}{AddObjectFFRF}{}}}\label{sec:FEM:ObjectFFRFinterface:AddObjectFFRF} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L797}{AddObjectFFRF}{}}}\label{sec:FEM:ObjectFFRFinterface:AddObjectFFRF} ({\it self}, {\it exu}, {\it mbs}, {\it positionRef}= [0,0,0], {\it eulerParametersRef}= [1,0,0,0], {\it initialVelocity}= [0,0,0], {\it initialAngularVelocity}= [0,0,0], {\it gravity}= [0,0,0], {\it constrainRigidBodyMotion}= True, {\it massProportionalDamping}= 0, {\it stiffnessProportionalDamping}= 0, {\it color}= [0.1,0.9,0.1,1.]) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1215,7 +1226,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L873}{UFforce}{}}}\label{sec:FEM:ObjectFFRFinterface:UFforce} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L876}{UFforce}{}}}\label{sec:FEM:ObjectFFRFinterface:UFforce} ({\it self}, {\it exu}, {\it mbs}, {\it t}, {\it q}, {\it q\_t}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1225,7 +1236,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L919}{UFmassGenericODE2}{}}}\label{sec:FEM:ObjectFFRFinterface:UFmassGenericODE2} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L922}{UFmassGenericODE2}{}}}\label{sec:FEM:ObjectFFRFinterface:UFmassGenericODE2} ({\it self}, {\it exu}, {\it mbs}, {\it t}, {\it q}, {\it q\_t}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1246,7 +1257,7 @@ this class holds all data for ObjectFFRFreducedOrder user functions \vspace{3pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1030}{\_\_init\_\_}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:__init__} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1033}{\_\_init\_\_}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:__init__} ({\it self}, {\it femInterface}= None, {\it rigidBodyNodeType}= 'NodeType.RotationEulerParameters', {\it roundMassMatrix}= 1e-13, {\it roundStiffnessMatrix}= 1e-13) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1269,7 +1280,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1105}{SaveToFile}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:SaveToFile} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1108}{SaveToFile}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:SaveToFile} ({\it self}, {\it fileName}, {\it fileVersion}= 1) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1286,7 +1297,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1147}{LoadFromFile}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:LoadFromFile} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1156}{LoadFromFile}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:LoadFromFile} ({\it self}, {\it fileName}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1303,7 +1314,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1217}{AddObjectFFRFreducedOrderWithUserFunctions}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:AddObjectFFRFreducedOrderWithUserFunctions} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1226}{AddObjectFFRFreducedOrderWithUserFunctions}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:AddObjectFFRFreducedOrderWithUserFunctions} ({\it self}, {\it exu}, {\it mbs}, {\it positionRef}= [0,0,0], {\it initialVelocity}= [0,0,0], {\it rotationMatrixRef}= [], {\it initialAngularVelocity}= [0,0,0], {\it gravity}= [0,0,0], {\it UFforce}= 0, {\it UFmassMatrix}= 0, {\it massProportionalDamping}= 0, {\it stiffnessProportionalDamping}= 0, {\it color}= [0.1,0.9,0.1,1.], {\it eulerParametersRef}= []) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1337,7 +1348,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1370}{UFmassFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:UFmassFFRFreducedOrder} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1379}{UFmassFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:UFmassFFRFreducedOrder} ({\it self}, {\it exu}, {\it mbs}, {\it t}, {\it qReduced}, {\it qReduced\_t}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1347,7 +1358,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1421}{UFforceFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:UFforceFFRFreducedOrder} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1430}{UFforceFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:UFforceFFRFreducedOrder} ({\it self}, {\it exu}, {\it mbs}, {\it t}, {\it qReduced}, {\it qReduced\_t}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1357,7 +1368,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1504}{AddObjectFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:AddObjectFFRFreducedOrder} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1513}{AddObjectFFRFreducedOrder}{}}}\label{sec:FEM:ObjectFFRFreducedOrderInterface:AddObjectFFRFreducedOrder} ({\it self}, {\it mbs}, {\it positionRef}= [0,0,0], {\it initialVelocity}= [0,0,0], {\it rotationMatrixRef}= [], {\it initialAngularVelocity}= [0,0,0], {\it massProportionalDamping}= 0, {\it stiffnessProportionalDamping}= 0, {\it gravity}= [0,0,0], {\it color}= [0.1,0.9,0.1,1.]) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1412,7 +1423,7 @@ export to EXUDYN objects \vspace{3pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1555}{\_\_init\_\_}{}}}\label{sec:FEM:FEMinterface:__init__} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1564}{\_\_init\_\_}{}}}\label{sec:FEM:FEMinterface:__init__} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1435,7 +1446,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1580}{SaveToFile}{}}}\label{sec:FEM:FEMinterface:SaveToFile} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1589}{SaveToFile}{}}}\label{sec:FEM:FEMinterface:SaveToFile} ({\it self}, {\it fileName}, {\it fileVersion}= 13) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1452,7 +1463,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1610}{LoadFromFile}{}}}\label{sec:FEM:FEMinterface:LoadFromFile} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1625}{LoadFromFile}{}}}\label{sec:FEM:FEMinterface:LoadFromFile} ({\it self}, {\it fileName}, {\it forceVersion}= None) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1474,7 +1485,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1662}{ImportFromAbaqusInputFile}{}}}\label{sec:FEM:FEMinterface:ImportFromAbaqusInputFile} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1677}{ImportFromAbaqusInputFile}{}}}\label{sec:FEM:FEMinterface:ImportFromAbaqusInputFile} ({\it self}, {\it fileName}, {\it typeName}= 'Part', {\it name}= 'Part-1', {\it verbose}= False, {\it createSurfaceTrigs}= True, {\it surfaceTrigsAll}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1503,7 +1514,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1831}{ReadMassMatrixFromAbaqus}{}}}\label{sec:FEM:FEMinterface:ReadMassMatrixFromAbaqus} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1846}{ReadMassMatrixFromAbaqus}{}}}\label{sec:FEM:FEMinterface:ReadMassMatrixFromAbaqus} ({\it self}, {\it fileName}, {\it type}= 'SparseRowColumnValue') \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1521,7 +1532,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1837}{ReadStiffnessMatrixFromAbaqus}{}}}\label{sec:FEM:FEMinterface:ReadStiffnessMatrixFromAbaqus} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1852}{ReadStiffnessMatrixFromAbaqus}{}}}\label{sec:FEM:FEMinterface:ReadStiffnessMatrixFromAbaqus} ({\it self}, {\it fileName}, {\it type}= 'SparseRowColumnValue') \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1531,7 +1542,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1862}{ImportMeshFromNGsolve}{}}}\label{sec:FEM:FEMinterface:ImportMeshFromNGsolve} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L1877}{ImportMeshFromNGsolve}{}}}\label{sec:FEM:FEMinterface:ImportMeshFromNGsolve} ({\it self}, {\it mesh}, {\it density}, {\it youngsModulus}, {\it poissonsRatio}, {\it verbose}= False, {\it computeEigenmodes}= False, {\it meshOrder}= 1, {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1554,7 +1565,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2047}{ComputeEigenmodesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputeEigenmodesNGsolve} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2062}{ComputeEigenmodesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputeEigenmodesNGsolve} ({\it self}, {\it bfM}, {\it bfK}, {\it nModes}, {\it maxEigensolveIterations}= 40, {\it excludeRigidBodyModes}= 0, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1574,7 +1585,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2089}{ComputeHurtyCraigBamptonModesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputeHurtyCraigBamptonModesNGsolve} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2104}{ComputeHurtyCraigBamptonModesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputeHurtyCraigBamptonModesNGsolve} ({\it self}, {\it bfM}, {\it bfK}, {\it boundaryNodesList}, {\it nEigenModes}, {\it maxEigensolveIterations}= 40, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1596,7 +1607,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2230}{ComputePostProcessingModesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputePostProcessingModesNGsolve} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2245}{ComputePostProcessingModesNGsolve}{}}}\label{sec:FEM:FEMinterface:ComputePostProcessingModesNGsolve} ({\it self}, {\it fes}, {\it material}= 0, {\it outputVariableType}= 'OutputVariableType.StressLocal', {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1616,7 +1627,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2305}{GetMassMatrix}{}}}\label{sec:FEM:FEMinterface:GetMassMatrix} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2320}{GetMassMatrix}{}}}\label{sec:FEM:FEMinterface:GetMassMatrix} ({\it self}, {\it sparse}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1626,7 +1637,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2312}{GetStiffnessMatrix}{}}}\label{sec:FEM:FEMinterface:GetStiffnessMatrix} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2327}{GetStiffnessMatrix}{}}}\label{sec:FEM:FEMinterface:GetStiffnessMatrix} ({\it self}, {\it sparse}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1636,7 +1647,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2319}{NumberOfNodes}{}}}\label{sec:FEM:FEMinterface:NumberOfNodes} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2334}{NumberOfNodes}{}}}\label{sec:FEM:FEMinterface:NumberOfNodes} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1646,7 +1657,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2331}{GetNodePositionsAsArray}{}}}\label{sec:FEM:FEMinterface:GetNodePositionsAsArray} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2346}{GetNodePositionsAsArray}{}}}\label{sec:FEM:FEMinterface:GetNodePositionsAsArray} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1661,7 +1672,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2339}{GetNodePositionsMean}{}}}\label{sec:FEM:FEMinterface:GetNodePositionsMean} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2354}{GetNodePositionsMean}{}}}\label{sec:FEM:FEMinterface:GetNodePositionsMean} ({\it self}, {\it nodeNumberList}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1671,7 +1682,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2346}{NumberOfCoordinates}{}}}\label{sec:FEM:FEMinterface:NumberOfCoordinates} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2361}{NumberOfCoordinates}{}}}\label{sec:FEM:FEMinterface:NumberOfCoordinates} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1681,7 +1692,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2354}{GetNodeAtPoint}{}}}\label{sec:FEM:FEMinterface:GetNodeAtPoint} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2369}{GetNodeAtPoint}{}}}\label{sec:FEM:FEMinterface:GetNodeAtPoint} ({\it self}, {\it point}, {\it tolerance}= 1e-5, {\it raiseException}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1696,7 +1707,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2370}{GetNodesInPlane}{}}}\label{sec:FEM:FEMinterface:GetNodesInPlane} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2385}{GetNodesInPlane}{}}}\label{sec:FEM:FEMinterface:GetNodesInPlane} ({\it self}, {\it point}, {\it normal}, {\it tolerance}= 1e-5) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1711,7 +1722,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2386}{GetNodesInCube}{}}}\label{sec:FEM:FEMinterface:GetNodesInCube} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2401}{GetNodesInCube}{}}}\label{sec:FEM:FEMinterface:GetNodesInCube} ({\it self}, {\it pMin}, {\it pMax}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1724,7 +1735,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2401}{GetNodesOnLine}{}}}\label{sec:FEM:FEMinterface:GetNodesOnLine} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2416}{GetNodesOnLine}{}}}\label{sec:FEM:FEMinterface:GetNodesOnLine} ({\it self}, {\it p1}, {\it p2}, {\it tolerance}= 1e-5) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1734,7 +1745,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2407}{GetNodesOnCylinder}{}}}\label{sec:FEM:FEMinterface:GetNodesOnCylinder} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2422}{GetNodesOnCylinder}{}}}\label{sec:FEM:FEMinterface:GetNodesOnCylinder} ({\it self}, {\it p1}, {\it p2}, {\it radius}, {\it tolerance}= 1e-5) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1750,7 +1761,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2435}{GetNodesOnCircle}{}}}\label{sec:FEM:FEMinterface:GetNodesOnCircle} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2450}{GetNodesOnCircle}{}}}\label{sec:FEM:FEMinterface:GetNodesOnCircle} ({\it self}, {\it point}, {\it normal}, {\it r}, {\it tolerance}= 1e-5) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1766,7 +1777,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2455}{GetNodeWeightsFromSurfaceAreas}{}}}\label{sec:FEM:FEMinterface:GetNodeWeightsFromSurfaceAreas} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2470}{GetNodeWeightsFromSurfaceAreas}{}}}\label{sec:FEM:FEMinterface:GetNodeWeightsFromSurfaceAreas} ({\it self}, {\it nodeList}, {\it normalizeWeights}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1788,7 +1799,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2507}{GetSurfaceTriangles}{}}}\label{sec:FEM:FEMinterface:GetSurfaceTriangles} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2522}{GetSurfaceTriangles}{}}}\label{sec:FEM:FEMinterface:GetSurfaceTriangles} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1798,7 +1809,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2517}{VolumeToSurfaceElements}{}}}\label{sec:FEM:FEMinterface:VolumeToSurfaceElements} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2532}{VolumeToSurfaceElements}{}}}\label{sec:FEM:FEMinterface:VolumeToSurfaceElements} ({\it self}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1814,7 +1825,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2646}{GetGyroscopicMatrix}{}}}\label{sec:FEM:FEMinterface:GetGyroscopicMatrix} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2661}{GetGyroscopicMatrix}{}}}\label{sec:FEM:FEMinterface:GetGyroscopicMatrix} ({\it self}, {\it rotationAxis}= 2, {\it sparse}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1824,7 +1835,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2675}{ScaleMassMatrix}{}}}\label{sec:FEM:FEMinterface:ScaleMassMatrix} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2690}{ScaleMassMatrix}{}}}\label{sec:FEM:FEMinterface:ScaleMassMatrix} ({\it self}, {\it factor}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1834,7 +1845,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2679}{ScaleStiffnessMatrix}{}}}\label{sec:FEM:FEMinterface:ScaleStiffnessMatrix} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2694}{ScaleStiffnessMatrix}{}}}\label{sec:FEM:FEMinterface:ScaleStiffnessMatrix} ({\it self}, {\it factor}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1844,7 +1855,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2685}{AddElasticSupportAtNode}{}}}\label{sec:FEM:FEMinterface:AddElasticSupportAtNode} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2700}{AddElasticSupportAtNode}{}}}\label{sec:FEM:FEMinterface:AddElasticSupportAtNode} ({\it self}, {\it nodeNumber}, {\it springStiffness}= [1e8,1e8,1e8]) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1859,7 +1870,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2701}{AddNodeMass}{}}}\label{sec:FEM:FEMinterface:AddNodeMass} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2716}{AddNodeMass}{}}}\label{sec:FEM:FEMinterface:AddNodeMass} ({\it self}, {\it nodeNumber}, {\it addedMass}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1869,7 +1880,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2721}{CreateLinearFEMObjectGenericODE2}{}}}\label{sec:FEM:FEMinterface:CreateLinearFEMObjectGenericODE2} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2736}{CreateLinearFEMObjectGenericODE2}{}}}\label{sec:FEM:FEMinterface:CreateLinearFEMObjectGenericODE2} ({\it self}, {\it mbs}, {\it color}= [0.9,0.4,0.4,1.]) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1881,7 +1892,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2764}{CreateNonlinearFEMObjectGenericODE2NGsolve}{}}}\label{sec:FEM:FEMinterface:CreateNonlinearFEMObjectGenericODE2NGsolve} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2779}{CreateNonlinearFEMObjectGenericODE2NGsolve}{}}}\label{sec:FEM:FEMinterface:CreateNonlinearFEMObjectGenericODE2NGsolve} ({\it self}, {\it mbs}, {\it mesh}, {\it density}, {\it youngsModulus}, {\it poissonsRatio}, {\it meshOrder}= 1, {\it color}= [0.9,0.4,0.4,1.]) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1912,7 +1923,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2870}{ComputeEigenmodes}{}}}\label{sec:FEM:FEMinterface:ComputeEigenmodes} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2885}{ComputeEigenmodes}{}}}\label{sec:FEM:FEMinterface:ComputeEigenmodes} ({\it self}, {\it nModes}, {\it excludeRigidBodyModes}= 0, {\it useSparseSolver}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1931,7 +1942,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2914}{ComputeEigenModesWithBoundaryNodes}{}}}\label{sec:FEM:FEMinterface:ComputeEigenModesWithBoundaryNodes} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2929}{ComputeEigenModesWithBoundaryNodes}{}}}\label{sec:FEM:FEMinterface:ComputeEigenModesWithBoundaryNodes} ({\it self}, {\it boundaryNodes}, {\it nEigenModes}, {\it useSparseSolver}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1949,7 +1960,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L2999}{ComputeHurtyCraigBamptonModes}{}}}\label{sec:FEM:FEMinterface:ComputeHurtyCraigBamptonModes} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3014}{ComputeHurtyCraigBamptonModes}{}}}\label{sec:FEM:FEMinterface:ComputeHurtyCraigBamptonModes} ({\it self}, {\it boundaryNodesList}, {\it nEigenModes}, {\it useSparseSolver}= True, {\it computationMode}= HCBstaticModeSelection.RBE2, {\it boundaryNodesWeights}= [], {\it excludeRigidBodyMotion}= True, {\it RBE3secondMomentOfAreaWeighting}= True, {\it verboseMode}= False, {\it timerTreshold}= 20000) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1974,7 +1985,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3407}{GetEigenFrequenciesHz}{}}}\label{sec:FEM:FEMinterface:GetEigenFrequenciesHz} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3422}{GetEigenFrequenciesHz}{}}}\label{sec:FEM:FEMinterface:GetEigenFrequenciesHz} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -1984,7 +1995,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3467}{ComputePostProcessingModes}{}}}\label{sec:FEM:FEMinterface:ComputePostProcessingModes} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3482}{ComputePostProcessingModes}{}}}\label{sec:FEM:FEMinterface:ComputePostProcessingModes} ({\it self}, {\it material}= 0, {\it outputVariableType}= 'OutputVariableType.StressLocal', {\it numberOfThreads}= 1) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2003,7 +2014,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3585}{ComputeCampbellDiagram}{}}}\label{sec:FEM:FEMinterface:ComputeCampbellDiagram} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3600}{ComputeCampbellDiagram}{}}}\label{sec:FEM:FEMinterface:ComputeCampbellDiagram} ({\it self}, {\it terminalFrequency}, {\it nEigenfrequencies}= 10, {\it frequencySteps}= 25, {\it rotationAxis}= 2, {\it plotDiagram}= False, {\it verbose}= False, {\it useCorotationalFrame}= False, {\it useSparseSolver}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2039,7 +2050,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3770}{CheckConsistency}{}}}\label{sec:FEM:FEMinterface:CheckConsistency} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3785}{CheckConsistency}{}}}\label{sec:FEM:FEMinterface:CheckConsistency} ({\it self}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2049,7 +2060,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3794}{ReadMassMatrixFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadMassMatrixFromAnsys} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3809}{ReadMassMatrixFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadMassMatrixFromAnsys} ({\it self}, {\it fileName}, {\it dofMappingVectorFile}, {\it sparse}= True, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2059,7 +2070,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3808}{ReadStiffnessMatrixFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadStiffnessMatrixFromAnsys} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3823}{ReadStiffnessMatrixFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadStiffnessMatrixFromAnsys} ({\it self}, {\it fileName}, {\it dofMappingVectorFile}, {\it sparse}= True, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2069,7 +2080,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3822}{ReadNodalCoordinatesFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadNodalCoordinatesFromAnsys} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3837}{ReadNodalCoordinatesFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadNodalCoordinatesFromAnsys} ({\it self}, {\it fileName}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2079,7 +2090,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3827}{ReadElementsFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadElementsFromAnsys} +\noindent \textcolor{steelblue}{def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/FEM.py\#L3842}{ReadElementsFromAnsys}{}}}\label{sec:FEM:FEMinterface:ReadElementsFromAnsys} ({\it self}, {\it fileName}, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -2495,8 +2506,9 @@ \bi \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/NGsolveCraigBampton.py}{\texttt{NGsolveCraigBampton.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rigid3Dexample.py}{\texttt{rigid3Dexample.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/genericJointUserFunctionTest.py}{\texttt{genericJointUserFunctionTest.py}} (TM), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/rigidBodyCOMtest.py}{\texttt{rigidBodyCOMtest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/rr.py}{\texttt{rr.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/genericJointUserFunctionTest.py}{\texttt{genericJointUserFunctionTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/rigidBodyCOMtest.py}{\texttt{rigidBodyCOMtest.py}} (TM), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/sphericalJointTest.py}{\texttt{sphericalJointTest.py}} (TM) \ei @@ -2575,7 +2587,7 @@ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/beltDrivesComparison.py}{\texttt{beltDrivesComparison.py}} (Ex), \\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), ... , \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), @@ -2640,10 +2652,10 @@ \noindent For examples on GraphicsDataSphere see Relevant Examples (Ex) and TestModels (TM) with weblink to github: \bi \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/graphicsDataExample.py}{\texttt{graphicsDataExample.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/humanRobotInteraction.py}{\texttt{humanRobotInteraction.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/lugreFrictionTest.py}{\texttt{lugreFrictionTest.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/nMassOscillatorEigenmodes.py}{\texttt{nMassOscillatorEigenmodes.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/humanRobotInteraction.py}{\texttt{humanRobotInteraction.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/lugreFrictionTest.py}{\texttt{lugreFrictionTest.py}} (Ex), ... , \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/connectorGravityTest.py}{\texttt{connectorGravityTest.py}} (TM), @@ -2808,6 +2820,7 @@ \noindent For examples on GraphicsDataFromSTLfile see Relevant Examples (Ex) and TestModels (TM) with weblink to github: \bi \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/humanRobotInteraction.py}{\texttt{humanRobotInteraction.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ROSExampleTurtle.py}{\texttt{ROSExampleTurtle.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/stlFileImport.py}{\texttt{stlFileImport.py}} (Ex) \ei @@ -3137,10 +3150,10 @@ \noindent For examples on GraphicsDataCheckerBoard see Relevant Examples (Ex) and TestModels (TM) with weblink to github: \bi \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/bicycleIftommBenchmark.py}{\texttt{bicycleIftommBenchmark.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/finiteSegmentMethod.py}{\texttt{finiteSegmentMethod.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/flexiblePendulumANCF.py}{\texttt{flexiblePendulumANCF.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/graphicsDataExample.py}{\texttt{graphicsDataExample.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/finiteSegmentMethod.py}{\texttt{finiteSegmentMethod.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/flexiblePendulumANCF.py}{\texttt{flexiblePendulumANCF.py}} (Ex), ... , \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/ANCFoutputTest.py}{\texttt{ANCFoutputTest.py}} (TM), @@ -3311,7 +3324,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/GUI.py\#L640}{EditDictionaryWithTypeInfo}{}}}\label{sec:GUI:EditDictionaryWithTypeInfo} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/GUI.py\#L642}{EditDictionaryWithTypeInfo}{}}}\label{sec:GUI:EditDictionaryWithTypeInfo} ({\it settingsStructure}, {\it exu}= None, {\it dictionaryName}= 'edit') \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4637,7 +4650,7 @@ \item[]Notes: For a list of plot colors useful for matplotlib, see also advancedUtilities.PlotLineCode(...) \ei \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L55}{ParseOutputFileHeader}{}}}\label{sec:plot:ParseOutputFileHeader} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L56}{ParseOutputFileHeader}{}}}\label{sec:plot:ParseOutputFileHeader} ({\it lines}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4650,7 +4663,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L153}{PlotSensorDefaults}{}}}\label{sec:plot:PlotSensorDefaults} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L154}{PlotSensorDefaults}{}}}\label{sec:plot:PlotSensorDefaults} () \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4678,7 +4691,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L227}{PlotSensor}{}}}({\it mbs}, {\it sensorNumbers}= [], {\it components}= 0, {\it xLabel}= 'time (s)', {\it yLabel}= None, {\it labels}= [], {\it colorCodeOffset}= 0, {\it newFigure}= True, {\it closeAll}= False, {\it componentsX}= [], {\it title}= '', {\it figureName}= '', {\it fontSize}= 16, {\it colors}= [], {\it lineStyles}= [], {\it lineWidths}= [], {\it markerStyles}= [], {\it markerSizes}= [], {\it markerDensity}= 0.08, {\it rangeX}= [], {\it rangeY}= [], {\it majorTicksX}= 10, {\it majorTicksY}= 10, {\it offsets}= [], {\it factors}= [], {\it subPlot}= [], {\it sizeInches}= [6.4,4.8], {\it fileName}= '', {\it useXYZcomponents}= True, {\it **kwargs}) +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L230}{PlotSensor}{}}}({\it mbs}, {\it sensorNumbers}= [], {\it components}= 0, {\it xLabel}= 'time (s)', {\it yLabel}= None, {\it labels}= [], {\it colorCodeOffset}= 0, {\it newFigure}= True, {\it closeAll}= False, {\it componentsX}= [], {\it title}= '', {\it figureName}= '', {\it fontSize}= 16, {\it colors}= [], {\it lineStyles}= [], {\it lineWidths}= [], {\it markerStyles}= [], {\it markerSizes}= [], {\it markerDensity}= 0.08, {\it rangeX}= [], {\it rangeY}= [], {\it majorTicksX}= 10, {\it majorTicksY}= 10, {\it offsets}= [], {\it factors}= [], {\it subPlot}= [], {\it sizeInches}= [6.4,4.8], {\it fileName}= '', {\it useXYZcomponents}= True, {\it **kwargs}) \end{flushleft} \bi \item \mybold{NOTE}: this function is directly available in MainSystem (mbs); it should be directly called as mbs.PlotSensor(...). For description of the interface, see the MainSystem Python extensions, \refSection{sec:mainsystemextensions:PlotSensor}. @@ -4686,7 +4699,7 @@ \ei \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L677}{PlotFFT}{}}}\label{sec:plot:PlotFFT} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L685}{PlotFFT}{}}}\label{sec:plot:PlotFFT} ({\it frequency}, {\it data}, {\it xLabel}= 'frequency', {\it yLabel}= 'magnitude', {\it label}= '', {\it freqStart}= 0, {\it freqEnd}= -1, {\it logScaleX}= True, {\it logScaleY}= True, {\it majorGrid}= True, {\it minorGrid}= True) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4712,10 +4725,17 @@ \item[--] {\bf output}: creates plot and returns plot (plt) handle \vspace{12pt}\end{itemize} +% +% +\noindent For examples on PlotFFT see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/nMassOscillatorEigenmodes.py}{\texttt{nMassOscillatorEigenmodes.py}} (Ex) +\ei + % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L727}{FileStripSpaces}{}}}\label{sec:plot:FileStripSpaces} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L735}{FileStripSpaces}{}}}\label{sec:plot:FileStripSpaces} ({\it filename}, {\it outputFilename}, {\it fileCommentChar}= '', {\it removeDoubleChars}= '') \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4737,7 +4757,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L754}{DataArrayFromSensorList}{}}}\label{sec:plot:DataArrayFromSensorList} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L762}{DataArrayFromSensorList}{}}}\label{sec:plot:DataArrayFromSensorList} ({\it mbs}, {\it sensorNumbers}, {\it positionList}= [], {\it time}= '') \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4767,7 +4787,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L781}{LoadImage}{}}}\label{sec:plot:LoadImage} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L789}{LoadImage}{}}}\label{sec:plot:LoadImage} ({\it fileName}, {\it trianglesAsLines}= True, {\it verbose}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4790,7 +4810,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L854}{PlotImage}{}}}\label{sec:plot:PlotImage} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/plot.py\#L862}{PlotImage}{}}}\label{sec:plot:PlotImage} ({\it imageData}, {\it HT}= np.eye(4), {\it axesEqual}= True, {\it plot3D}= False, {\it lineWidths}= 1, {\it lineStyles}= '-', {\it triangleEdgeColors}= 'black', {\it triangleEdgeWidths}= 0.5, {\it removeAxes}= True, {\it orthogonalProjection}= True, {\it title}= '', {\it figureName}= '', {\it fileName}= '', {\it fontSize}= 16, {\it closeAll}= False, {\it azim}= 0., {\it elev}= 0.) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4839,7 +4859,7 @@ \item[]Notes: Parallel processing, which requires multiprocessing library, can lead to considerable speedup (measured speedup factor > 50 on 80 core machine). The progess bar during multiprocessing requires the library tqdm. \ei \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L26}{GetVersionPlatformString}{}}}\label{sec:processing:GetVersionPlatformString} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L27}{GetVersionPlatformString}{}}}\label{sec:processing:GetVersionPlatformString} () \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4857,7 +4877,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L144}{ProcessParameterList}{}}}\label{sec:processing:ProcessParameterList} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L162}{ProcessParameterList}{}}}\label{sec:processing:ProcessParameterList} ({\it parameterFunction}, {\it parameterList}, {\it useMultiProcessing}, {\it clusterHostNames}= [], {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4899,7 +4919,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L374}{ParameterVariation}{}}}\label{sec:processing:ParameterVariation} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L392}{ParameterVariation}{}}}\label{sec:processing:ParameterVariation} ({\it parameterFunction}, {\it parameters}, {\it useLogSpace}= False, {\it debugMode}= False, {\it addComputationIndex}= False, {\it useMultiProcessing}= False, {\it showProgress}= True, {\it parameterFunctionData}= {}, {\it clusterHostNames}= [], {\it numberOfThreads}= None, {\it resultsFile}= '', {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -4957,8 +4977,8 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L524}{GeneticOptimization}{}}}\label{sec:processing:GeneticOptimization} -({\it objectiveFunction}, {\it parameters}, {\it populationSize}= 100, {\it numberOfGenerations}= 10, {\it elitistRatio}= 0.1, {\it crossoverProbability}= 0.25, {\it crossoverAmount}= 0.5, {\it rangeReductionFactor}= 0.7, {\it distanceFactor}= 0.1, {\it childDistribution}= "uniform", {\it distanceFactorGenerations}= -1, {\it debugMode}= False, {\it addComputationIndex}= False, {\it useMultiProcessing}= False, {\it showProgress}= True, {\it clusterHostNames}= [], {\it **kwargs}) +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L543}{GeneticOptimization}{}}}\label{sec:processing:GeneticOptimization} +({\it objectiveFunction}, {\it parameters}, {\it populationSize}= 100, {\it numberOfGenerations}= 10, {\it elitistRatio}= 0.1, {\it crossoverProbability}= 0.25, {\it crossoverAmount}= 0.5, {\it rangeReductionFactor}= 0.7, {\it distanceFactor}= 0.1, {\it childDistribution}= "uniform", {\it distanceFactorGenerations}= -1, {\it debugMode}= False, {\it addComputationIndex}= False, {\it useMultiProcessing}= False, {\it showProgress}= True, {\it clusterHostNames}= [], {\it parameterFunctionData}= {}, {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} \begin{itemize}[leftmargin=0.7cm] @@ -4980,6 +5000,7 @@ \item[]{\it distanceFactor}: children only survive at a certain relative distance of the current range; must be small enough (< 0.5) to allow individuals to survive; ignored if distanceFactor=0; as a rule of thumb, the distanceFactor should be zero in case that there is only one significant minimum, but if there are many local minima, the distanceFactor should be used to search at several different local minima \item[]{\it childDistribution}: string with name of distribution for producing childs: "normal" (Gaussian, with sigma defining range), "uniform" (exactly in range of childs) \item[]{\it distanceFactorGenerations}: number of generations (populations) at which the distance factor is active; the distance factor is used to find several local minima; finally, convergence is speed up without the distance factor +\item[]{\it parameterFunctionData}: dictionary containing additional data passed to the objectiveFunction inside the parameters with dict key 'functionData'; use this e.g. for passing solver parameters or other settings \item[]{\it randomizerInitialization}: initialize randomizer at beginning of optimization in order to get reproducible results, provide any integer in the range between 0 and 2**32 - 1 (default: no initialization) \item[]{\it debugMode}: if True, additional print out is done \item[]{\it addComputationIndex}: if True, key 'computationIndex' is added to every parameterDict in the call to parameterFunction(), which allows to generate independent output files for every parameter, etc. @@ -5015,13 +5036,13 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L888}{Minimize}{}}}\label{sec:processing:Minimize} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L904}{Minimize}{}}}\label{sec:processing:Minimize} ({\it objectiveFunction}, {\it parameters}, {\it initialGuess}= [], {\it method}= 'Nelder-Mead', {\it tol}= 1e-4, {\it options}= {}, {\it enforceBounds}= True, {\it debugMode}= False, {\it showProgress}= True, {\it addComputationIndex}= False, {\it storeFunctionValues}= True, {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} \begin{itemize}[leftmargin=0.7cm] \item[--] -{\bf function description}: Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). +{\bf function description}: Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). Note that in special cases, you should copy this function and adapt to your needs. \item[--] {\bf input}: \vspace{-6pt} \begin{itemize}[leftmargin=1.2cm] @@ -5031,19 +5052,15 @@ \item[]{\it storeFunctionValues}: if True, objectiveFunction values are computed (additional costs!) and stored in every iteration into valueList \item[]{\it initialGuess}: initial guess. Array of real elements of size (n,), where 'n' is the number of independent variables. If not provided by the user, initialGuess is computed from bounds provided in parameterDict. \item[]{\it method}: solver that should be used, e.g. 'Nelder-Mead', 'Powell', 'CG' etc. A list of available solvers can be found in the documentation of scipy.optimize.minimize(). -\item[]{\it tol}: tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol. For detailed control, use solver-specific options using the 'options' variable. +\item[]{\it tol}: tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol (but this is usually not the tolerance for loss or parameters1). For detailed control, use solver-specific options using the 'options' variable. \item[]{\it options}: dictionary of solver options. Can be used to set absolute and relative error tolerances. Detailed information can be found in the documentation of scipy.optimize.minimize(). \item[]{\it enforceBounds}: if True, ensures that only parameters within the bounds specified in ParameterDict are used for minimization; this may help to avoid, e.g., negative values, but may lead to non-convergence \item[]{\it verbose}: prints solver information into console, e.g. number of iterations 'nit', number of funcion evaluations 'nfev', status etc. -\item[]{\it showProgress}: if True, shows for every iteration objective function value, number of current iteration, time needed for current iteration, maximum number of iterations until solver option 'maxiter' is reached. +\item[]{\it showProgress}: if True, shows for every iteration objective function value, current iteration number, time needed for current iteration, maximum number of iterations and loss (current value of objective function) \item[]{\it addComputationIndex}: if True, key 'computationIndex' is added for consistency reasons with GeneticOptimizaiton to every parameterDict in the call to parameterFunction(); however, the value is always 0, because no multi threading is used in Minimize(...) \item[]{\it resultsFile}: if provided, the results are stored columnwise into the given file and written after every generation; use resultsMonitor.py to track results in realtime \item[]{\it useScipyBounds}: if True, use scipy.optimize.minimize() option 'bounds' to apply bounds on variable specified in ParameterDict. Note, this option is only used by some specific methods of scipy.optimize.minimize()! method='Nelder-Mead' ignores this option for example! if False, option 'enforceBounds' will be set to False! \item[]{\it args}: extra arguments passed to the objective function and its derivatives (fun, jac and hess functions). -\item[]{\it jac}: method for computing the gradient vector. -\item[]{\it hess}: method for computing the Hessian matrix. -\item[]{\it hessp}: hessian of objective function times an arbitrary vector p. -\item[]{\it constraints}: constraints definition (only for COBYLA, SLSQP and trust-constr). \end{itemize} \item[--] {\bf output}: returns [optimumParameter, optimumValue, parameterList, valueList], containing the optimum parameter set 'optimumParameter', optimum value 'optimumValue', the whole list of parameters parameterList with according objective values 'valueList' @@ -5063,7 +5080,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1087}{ComputeSensitivities}{}}}\label{sec:processing:ComputeSensitivities} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1106}{ComputeSensitivities}{}}}\label{sec:processing:ComputeSensitivities} ({\it parameterFunction}, {\it parameters}, {\it scaledByReference}= False, {\it debugMode}= False, {\it addComputationIndex}= False, {\it useMultiProcessing}= False, {\it showProgress}= True, {\it parameterFunctionData}= dict(), {\it **kwargs}) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -5108,7 +5125,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1197}{PlotOptimizationResults2D}{}}}\label{sec:processing:PlotOptimizationResults2D} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1216}{PlotOptimizationResults2D}{}}}\label{sec:processing:PlotOptimizationResults2D} ({\it parameterList}, {\it valueList}, {\it xLogScale}= False, {\it yLogScale}= False) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -5140,7 +5157,7 @@ % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} -\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1253}{PlotSensitivityResults}{}}}\label{sec:processing:PlotSensitivityResults} +\noindent {def {\bf \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/exudyn/processing.py\#L1272}{PlotSensitivityResults}{}}}\label{sec:processing:PlotSensitivityResults} ({\it valRef}, {\it valuesSorted}, {\it sensitivity}, {\it fVar}= None, {\it strYAxis}= None) \end{flushleft} \setlength{\itemindent}{0.7cm} @@ -5425,9 +5442,10 @@ % \noindent For examples on RotationVector2RotationMatrix see Relevant Examples (Ex) and TestModels (TM) with weblink to github: \bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/stiffFlyballGovernor2.py}{\texttt{stiffFlyballGovernor2.py}} (Ex), + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/stiffFlyballGovernor2.py}{\texttt{stiffFlyballGovernor2.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/explicitLieGroupMBSTest.py}{\texttt{explicitLieGroupMBSTest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/stiffFlyballGovernor.py}{\texttt{stiffFlyballGovernor.py}} (TM) +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/stiffFlyballGovernor.py}{\texttt{stiffFlyballGovernor.py}} (TM) \ei % @@ -6606,9 +6624,9 @@ \bi \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addPrismaticJoint.py}{\texttt{addPrismaticJoint.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/addRevoluteJoint.py}{\texttt{addRevoluteJoint.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/fourBarMechanism3D.py}{\texttt{fourBarMechanism3D.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/kinematicTreeAndMBS.py}{\texttt{kinematicTreeAndMBS.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/chatGPTupdate.py}{\texttt{chatGPTupdate.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/craneReevingSystem.py}{\texttt{craneReevingSystem.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/fourBarMechanism3D.py}{\texttt{fourBarMechanism3D.py}} (Ex), ... , \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/bricardMechanism.py}{\texttt{bricardMechanism.py}} (TM), @@ -6677,9 +6695,12 @@ \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/graphicsDataExample.py}{\texttt{graphicsDataExample.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/particleClusters.py}{\texttt{particleClusters.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/particlesSilo.py}{\texttt{particlesSilo.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/tippeTop.py}{\texttt{tippeTop.py}} (Ex), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/ROSExampleMassPoint.py}{\texttt{ROSExampleMassPoint.py}} (Ex), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/tippeTop.py}{\texttt{tippeTop.py}} (Ex), + ... +, \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/distanceSensor.py}{\texttt{distanceSensor.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/generalContactFrictionTests.py}{\texttt{generalContactFrictionTests.py}} (TM) +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/generalContactFrictionTests.py}{\texttt{generalContactFrictionTests.py}} (TM) \ei % @@ -8229,14 +8250,14 @@ % \noindent For examples on MassMatrix see Relevant Examples (Ex) and TestModels (TM) with weblink to github: \bi - \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/nMassOscillatorEigenmodes.py}{\texttt{nMassOscillatorEigenmodes.py}} (Ex), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/shapeOptimization.py}{\texttt{shapeOptimization.py}} (Ex), + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/shapeOptimization.py}{\texttt{shapeOptimization.py}} (Ex), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/solverFunctionsTestEigenvalues.py}{\texttt{solverFunctionsTestEigenvalues.py}} (Ex), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/ACFtest.py}{\texttt{ACFtest.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/manualExplicitIntegrator.py}{\texttt{manualExplicitIntegrator.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/ACFtest.py}{\texttt{ACFtest.py}} (TM), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/manualExplicitIntegrator.py}{\texttt{manualExplicitIntegrator.py}} (TM), \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderAccelerations.py}{\texttt{objectFFRFreducedOrderAccelerations.py}} (TM), -\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderShowModes.py}{\texttt{objectFFRFreducedOrderShowModes.py}} (TM), -\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderStressModesTest.py}{\texttt{objectFFRFreducedOrderStressModesTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderShowModes.py}{\texttt{objectFFRFreducedOrderShowModes.py}} (TM), +\\ \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderStressModesTest.py}{\texttt{objectFFRFreducedOrderStressModesTest.py}} (TM), +\exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/TestModels/objectFFRFreducedOrderTest.py}{\texttt{objectFFRFreducedOrderTest.py}} (TM), ... \ei @@ -8458,6 +8479,13 @@ \item[--] {\bf date}: 02.04.2020 \vspace{12pt}\end{itemize} +% +% +\noindent For examples on ComputeFFT see Relevant Examples (Ex) and TestModels (TM) with weblink to github: +\bi + \item \footnotesize \exuUrl{https://github.com/jgerstmayr/EXUDYN/blob/master/main/pythonDev/Examples/nMassOscillatorEigenmodes.py}{\texttt{nMassOscillatorEigenmodes.py}} (Ex) +\ei + % \noindent\rule{8cm}{0.75pt}\vspace{1pt} \\ \begin{flushleft} diff --git a/docs/theDoc/theDoc.pdf b/docs/theDoc/theDoc.pdf index 589eab14..e708a2d0 100644 Binary files a/docs/theDoc/theDoc.pdf and b/docs/theDoc/theDoc.pdf differ diff --git a/docs/theDoc/trackerlog.tex b/docs/theDoc/trackerlog.tex index cddef70f..95818476 100644 --- a/docs/theDoc/trackerlog.tex +++ b/docs/theDoc/trackerlog.tex @@ -9,15 +9,196 @@ \noindent General information on current version: \bi \small - \item Exudyn version = 1.6.164.dev1, - \item last change = 2023-06-12, - \item Number of issues = 1620, - \item Number of resolved issues = 1444 (164 in current version), + \item Exudyn version = 1.7.0, + \item last change = 2023-07-19, + \item Number of issues = 1650, + \item Number of resolved issues = 1470 (0 in current version), \ei \mysubsection{Resolved issues and resolved bugs} \par \noindent The following list contains the issues which have been {\bf RESOLVED} in the according version: \bi \setlength\itemsep{-4pt} \scriptsize + \item[] {\bf Version 1.7.0}: resolved Issue 1649: {\bf release} +(release) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: switch to new release 1.7} + \item date resolved: {\bf 2023-07-19 16:07}, +date raised: 2023-07-19 + \ei + \item[] {\bf Version 1.6.189}: resolved Issue 1648: {\bf ReevingSystemSprings} +(fix) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: adjust test example for treating compression forces} + \item date resolved: {\bf 2023-07-17 12:10}, +date raised: 2023-07-17 + \ei + \item[] {\bf Version 1.6.188}: resolved Issue 1647: {\bf sensorTraces} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add vectors and triads to position traces; show current vector or triad and add some further options for visualization, see visualizationSettings sensors.traces} + \item {\bf notes: added triads and vectors, showing traces of motion at sensor points} + \item date resolved: {\bf 2023-07-14 18:34}, +date raised: 2023-07-14 + \ei + \item[] {\bf Version 1.6.187}: resolved Issue 1640: {\bf visualization} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: show trace of sensor positions (incl. frames) in render window; settings and list of sensors provided in visualizationSettings.sensors.traces with list of sensors, positionTrace, listOfPositionSensors=[] (empty means all position sensors, listOfVectorSensors=[] which can provide according vector quantities for positions; showVectors, vectorScaling=0.001, showPast=True, showFuture=False, showCurrent=True, lineWidth=2} + \item date resolved: {\bf 2023-07-14 11:20}, +date raised: 2023-07-11 + \ei + \item[] {\bf Version 1.6.186}: resolved Issue 1646: {\bf ArrayFloat} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: C++ add type} + \item date resolved: {\bf 2023-07-13 16:27}, +date raised: 2023-07-13 + \ei + \item[] {\bf Version 1.6.185}: resolved Issue 1645: {\bf ReevingSystemSprings} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add way to remove compression forces in rope} + \item {\bf notes: added parameter regularizationForce with tanh regularization for avoidance of compressive spring force} + \item date resolved: {\bf 2023-07-12 16:05}, +date raised: 2023-07-12 + \ei + \item[] {\bf Version 1.6.184}: resolved Issue 1644: {\bf Minimize} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: processing.Minimize: improve printout of current error of objective function=loss; only print every 1 second} + \item date resolved: {\bf 2023-07-12 09:29}, +date raised: 2023-07-12 + \ei + \item[] {\bf Version 1.6.183}: {\bf \color{warningRed} resolved BUG 1643}: {\bf Minimize} +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: processing.Minimize function has an internal bug, such that it does not work with initialGuess=[]} + \item date resolved: {\bf 2023-07-12 09:29}, +date raised: 2023-07-12 + \ei + \item[] {\bf Version 1.6.182}: {\bf \color{warningRed} resolved BUG 1642}: {\bf SolutionViewer} +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: record image not working with visualizationSettings useMultiThreadedRendering=True} + \item date resolved: {\bf 2023-07-11 17:58}, +date raised: 2023-07-11 + \ei + \item[] {\bf Version 1.6.181}: resolved Issue 1641: {\bf SolutionViewer} +(fix) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: github issue\#51: graphicsDataUserFunction in SolutionViewer not called; add call to graphicsData user functions in redraw image loop} + \item date resolved: {\bf 2023-07-11 17:16}, +date raised: 2023-07-11 + \ei + \item[] {\bf Version 1.6.180}: resolved Issue 1638: {\bf GeneticOptimization} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add argument parameterFunctionData to GeneticOptimization; same as in ParameterVariation, paramterFunctionData allows to pass additional data to the objective function} + \item date resolved: {\bf 2023-07-09 09:15}, +date raised: 2023-07-09 + \ei + \item[] {\bf Version 1.6.179}: resolved Issue 1637: {\bf add ChatGPT update information} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: create Python model Examples/chatGPTupdate.py which includes information that is used by ChatGPT4 to improve abilities to create simple models fully automatic} + \item date resolved: {\bf 2023-06-30 15:01}, +date raised: 2023-06-30 + \ei + \item[] {\bf Version 1.6.178}: resolved Issue 1636: {\bf CreateMassPoint} +(change) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: change args referenceCoordinates to referencePosition, initialCoordinates to initialDisplacement, and initialVelocities to initialVelocity to be consistent with CreateRigidBody (but different from MassPoint itself)} + \item date resolved: {\bf 2023-06-30 14:09}, +date raised: 2023-06-30 + \ei + \item[] {\bf Version 1.6.177}: resolved Issue 1635: {\bf SmartRound2String} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add function to basic utilities to enable simple printing of numbers with few digits, including comma dot and not eliminating small numbers, e.g., 1e-5 stays 1e-5} + \item date resolved: {\bf 2023-06-30 09:22}, +date raised: 2023-06-30 + \ei + \item[] {\bf Version 1.6.176}: resolved Issue 1634: {\bf create directories} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add automatic creation of directories to FEM SaveToFile, plotting and ParameterVariation} + \item date resolved: {\bf 2023-06-29 10:29}, +date raised: 2023-06-29 + \ei + \item[] {\bf Version 1.6.175}: {\bf \color{warningRed} resolved BUG 1633}: {\bf GetInterpolatedSignalValue} +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: timeArray needs to be replaced with timeArrayNew in case of 2D input array} + \item date resolved: {\bf 2023-06-28 21:15}, +date raised: 2023-06-28 + \ei + \item[] {\bf Version 1.6.174}: resolved Issue 1632: {\bf PlotFFT} +(fix) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: matplotlib >= 1.7 complains about ax.grid(b=...) as parameter b has been replaced by visible} + \item date resolved: {\bf 2023-06-27 14:15}, +date raised: 2023-06-27 + \ei + \item[] {\bf Version 1.6.173}: resolved Issue 1626: {\bf mutable args itemInterface} +(fix) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: also copy dictionaries, mainly for visualization (flat level, but this should be sufficient)} + \item date resolved: {\bf 2023-06-21 10:40}, +date raised: 2023-06-21 + \ei + \item[] {\bf Version 1.6.172}: resolved Issue 1627: {\bf mutable default args} +(change) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: complete changes and adaptations for default args in Python functions and item interface; note individual adaptations for lists, vectors, matrices and special lists of lists or matrix containers; for itemInterface, anyway all data is copied into C++; for more information see issues 1536, 1540, 1612, 1624, 1625, 1626} + \item date resolved: {\bf 2023-06-21 10:15}, +date raised: 2023-06-21 + \ei + \item[] {\bf Version 1.6.171}: resolved Issue 1625: {\bf change to default arg None} +(change) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: change default args for Vector2DList, Vector3DList, Vector6DList, Matrix3DList, to None; ArrayNodeIndex, ArrayMarkerIndex, ArraySensorIndex obtain copy method and are copied now; avoid problem of mutable default args} + \item date resolved: {\bf 2023-06-21 00:26}, +date raised: 2023-06-20 + \ei + \item[] {\bf Version 1.6.170}: resolved Issue 1624: {\bf MatrixContainer} +(change) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: change default values for matrix container to None; avoid problem of mutable default args} + \item date resolved: {\bf 2023-06-20 23:39}, +date raised: 2023-06-20 + \ei + \item[] {\bf Version 1.6.169}: resolved Issue 1540: {\bf mutable args itemInterface} +(check) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: copy lists in itemInterface in order to avoid change of default args by user n=NodePoint();n.referenceCoordinates[0]=42;n1=NodePoint()} + \item {\bf notes: simple vectors, matrices and lists are copied with np.array(...) while complex matrix and list of array types are now initialized with None} + \item date resolved: {\bf 2023-06-20 22:13}, +date raised: 2023-04-28 + \ei + \item[] {\bf Version 1.6.168}: resolved Issue 1620: {\bf docu MainSystemExtensions} +(docu) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: reorder MainSystemExtensions with separate section for Create functions and one section for remaining functions} + \item date resolved: {\bf 2023-06-19 22:14}, +date raised: 2023-06-13 + \ei + \item[] {\bf Version 1.6.167}: {\bf \color{warningRed} resolved BUG 1622}: {\bf mouse click} +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: fix crash on linux if left / right mouse click on render window (related to OpenGL select window)} + \item {\bf notes: occurs on WSL with WSLg; using 'export LIBGL\_ALWAYS\_SOFTWARE=1' will resolve the problem; put this line into your .bashrc} + \item date resolved: {\bf 2023-06-19 22:11}, +date raised: 2023-06-19 + \ei + \item[] {\bf Version 1.6.166}: {\bf \color{warningRed} resolved BUG 1621}: {\bf LinearSolverType} +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: fix crash on linux in function SetLinearSolverType} + \item date resolved: {\bf 2023-06-19 20:27}, +date raised: 2023-06-19 + \ei + \item[] {\bf Version 1.6.165}: resolved Issue 1623: {\bf MouseSelectOpenGL} +(extension) +\vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} + \item {description: add optional debbuging output} + \item date resolved: {\bf 2023-06-19 19:56}, +date raised: 2023-06-19 + \ei \item[] {\bf Version 1.6.164}: resolved Issue 1267: {\bf matrix inverse} (extension) \vspace{-6pt} \begin{itemize} \setlength\itemsep{-1pt} @@ -7684,6 +7865,11 @@ \ei \mysubsection{Known open bugs} \bi \footnotesize + \item open {\bf BUG 1639}: {\bf SolveDynamic FFRF} + \begin{itemize} \setlength\itemsep{-1pt} + \item {description: repeated call to mbs.SolveDynamic gives divergence; attributed to FFRFreducedOrder model; workaround uses repeated build of model before calling solver again; may be related to FFRF or MarkerSuperElement-internal variables} + \item date raised: 2023-07-10 + \ei \item open {\bf BUG 1085}: {\bf GeneralContact} \begin{itemize} \setlength\itemsep{-1pt} \item {description: generalContactFrictionTests.py gives considerably different results after t=0.05 seconds between Windows and linux compiled version; may be caused by some initialization problems (bugs...); needs further tests} diff --git a/docs/theDoc/tutorial.tex b/docs/theDoc/tutorial.tex index a9b17673..04702763 100644 --- a/docs/theDoc/tutorial.tex +++ b/docs/theDoc/tutorial.tex @@ -476,8 +476,7 @@ \end{lstlisting} \noindent Sometimes it is hard to understand the degree of freedom for the constrained system. Furthermore, we may have added -- by error -- -redundant constraints, which are not solvable or at least cause solver problems. Both can be checked with the command -\texttt{}: +redundant constraints, which are not solvable or at least cause solver problems. Both can be checked with the command: \pythonstyle\begin{lstlisting} mbs.ComputeSystemDegreeOfFreedom(verbose=True) #print out DOF and further information \end{lstlisting} @@ -542,7 +541,7 @@ With \texttt{solutionWritePeriod} you can adjust the frequency which is used to store the solution of the whole model, which may lead to very large files and may slow down simulation, but is used in the \texttt{SolutionViewer()} to reload the solution after simulation. -\noindent In order to improve visualization, there are hundreds of options, see Visualization settings in \refSection{sec:VSettingsGeneral}, some of them used here: +\noindent In order to improve visualization, there are hundreds of options, see Visualization settings in \refSection{sec:VisualizationSettingsMain}, some of them used here: \pythonstyle\begin{lstlisting} SC.visualizationSettings.window.renderWindowSize = [1600,1200] SC.visualizationSettings.openGL.multiSampling = 4 #improved OpenGL rendering diff --git a/docs/theDoc/version.tex b/docs/theDoc/version.tex index 946b2483..851107ff 100644 --- a/docs/theDoc/version.tex +++ b/docs/theDoc/version.tex @@ -1,3 +1,3 @@ % version info automatically generated by tracker; generated by Johannes Gerstmayr -% last modified = 2023-06-12 -Exudyn version = 1.6.164.dev1 (Gillespie) +% last modified = 2023-07-19 +Exudyn version = 1.7.0 (Hall) diff --git a/main/pythonDev/Examples/ROSExampleMassPoint.py b/main/pythonDev/Examples/ROSExampleMassPoint.py new file mode 100644 index 00000000..002aa929 --- /dev/null +++ b/main/pythonDev/Examples/ROSExampleMassPoint.py @@ -0,0 +1,212 @@ +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +# This is an EXUDYN python example how to use ROS and EXUDYN +# +# Details: This example shows how to communicate between an exudyn simulation +# and ROS publisher and subscriber from bash +# To make use of this example, you need to +# install ROS (ROS1 noetic) including rospy (see rosInterface.py) +# prerequisits to use: +# use a bash terminal to start the roscore with: +# roscore +# send force command to add load to the mass point form bash file with: +# rostopic pub -r 100 /cmd_wrench geometry_msgs/WrenchStamped "..." +# Author: Martin Sereinig, Peter Manzl +# Date: 2023-05-31 (created) +# +# 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. +# +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +import numpy as np +import exudyn as exu +from exudyn.utilities import * + +# import needed ROS modules and messages +import rospy +from geometry_msgs.msg import WrenchStamped, Twist +from std_msgs.msg import String + +# import new exudyn ROS interface class +import rosInterface as exuROS + +# here build inherited class and using within a simple exudyn simulation of one mass spring-damper +class MyExudynROSInterface(exuROS.ROSInterface): + def __init__(self): + # use initialisation of super class + # this initialize a rosnode with name + super().__init__(name='exuROSexample3Dmass') + # initialization of all standard publisher done by super class + # self.exuPosePublisher + # self.exuStringPublisher + # self.exuSystemstatePublisher + # self.exuTimePublisher + # self.exuTwistPublisher + + # use standard publisher functions form super class! + # self.PublishPoseUpdate + # self.PublishTwistUpdate + # self.PublishSystemStateUpdate + + # initialize all subscriber + # suitable callback function is auto generated by superclass (using lambda function) + # twist subscriber: cmd_vel + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_vel' # topic to subscribe + self.cmd_vel = Twist() # data type of topic, must be named: self.twistSubscriberTopic + self.myTwistSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,Twist) + + # wrench subscriber: cmd_wrench + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_wrench' # topic to subscribe + self.cmd_wrench = WrenchStamped() # data type of topic, must be named: self.twistSubscriberTopic + self.myWrenchSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,WrenchStamped) + + # string subsriber: my_string + stringSubsrciberBase = '' + stringSubsrciberTopic = 'my_string' # topic to subscribe + self.my_string = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase,stringSubsrciberTopic,String) + + # string subsriber: /exudyn/SimpleString + stringSubsrciberBase2 = 'exudyn/' # namespace of topic + stringSubsrciberTopic2 = 'SimpleString' # topic to subscribe + self.SimpleString = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase2,stringSubsrciberTopic2,String) + + +# test main function +def main(): + + # build exudyn model + SC = exu.SystemContainer() + mbs = SC.AddSystem() + tRes = 0.001 # step size in s + tEnd = 1e5 # simulation time in s + # mass and dimension of sphere + mass = 6 + r = 0.03 + background = GraphicsDataCheckerBoard(point=[-0.5,0,0], + normal=[1, 0, 0], + color=[0.7]*3+[1], + alternatingColor=[0.8]*3+[1]) + + graphicsSphere = GraphicsDataSphere(point=[0,0,0], + radius=r, + color=(1,0,0,1), + nTiles=64) + + origin = [0, 0, 0] + bGround = mbs.AddObject(ObjectGround(referencePosition=origin, + visualization=VObjectGround(graphicsData=[background]))) + + inertiaSphere = InertiaSphere(mass=mass,radius=r) + + # user interaction point + [nUIP, bUIP]=AddRigidBody(mainSys = mbs, + inertia = inertiaSphere, + nodeType = str(exu.NodeType.RotationEulerParameters), + position = [origin[0], origin[1], origin[2]], + rotationMatrix = np.eye(3), + angularVelocity = np.zeros(3), + velocity= [0,0,0], + gravity = [0, 0, 0], + graphicsDataList = [graphicsSphere]) + + # create markers: + mGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bGround, localPosition=[0, 0, 0.])) + mUIP = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bUIP)) + mUIPLoad = mbs.AddLoad(LoadForceVector(markerNumber = mUIP,loadVector =[0,0,0])) + + k = 100 + oSpringDamper = mbs.AddObject(RigidBodySpringDamper(markerNumbers=[mGround, mUIP], + stiffness=np.eye(6)*k, + damping=np.eye(6)*k*5e-2, + visualization={'show': False, 'drawSize': -1, 'color': [-1]*4})) + + + # sensor for position of endpoint of pendulum + sensorPos = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Position)) + sensorOri = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Rotation)) + sensorVelt = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Velocity)) + sensorVelr = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.AngularVelocity)) + + # store sensor value of each step in mbs variable, so that is accessible from user function + mbs.variables['pos'] = sensorPos + mbs.variables['ori'] = sensorOri + mbs.variables['velt'] = sensorVelt + mbs.variables['velr'] = sensorVelr + + # initialize ROS interface from own subclass + myROSInterface = MyExudynROSInterface() + + print('rosversion: ' + str(myROSInterface.myROSversionEnvInt)) + rospy.logdebug('node running and publishing') + + # exudyn PreStepUserFunction + def PreStepUserFunction(mbs, t): + # send position data to ROS + myROSInterface.PublishPoseUpdate(mbs,t) + # send velocity data to ROS + myROSInterface.PublishTwistUpdate(mbs,t) + # send system state data to ROS + myROSInterface.PublishSystemStateUpdate(mbs,t) + + # get string data from ROS /my_string topic, please use: rostopic pub -r 100 /my_string geometry_msgs/WrenchStamped "..." + someMessage = myROSInterface.my_string.data + if someMessage != '' : + print('mystringdata',someMessage) + + # get wrench data from ROS /cmd_wrench topic, please use: rostopic pub -r 100 /cmd_wrench geometry_msgs/WrenchStamped "..." + rosForces = myROSInterface.cmd_wrench.wrench.force + rosTorques = myROSInterface.cmd_wrench.wrench.torque + print('forces from ROS:', rosForces) + print('torques from ROS : ', rosTorques) + + # demo set force to certain value received from ROS /cmd_wrench + newForce = [rosForces.x, rosForces.y, rosForces.z] + mbs.SetLoadParameter(mUIPLoad,'loadVector',newForce) + + return True + + mbs.SetPreStepUserFunction(PreStepUserFunction) + # assemble multi body system with all previous specified properties and components + mbs.Assemble() + # set simulation settings + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.endTime = tEnd + simulationSettings.timeIntegration.numberOfSteps = int(tEnd/tRes) + simulationSettings.timeIntegration.newton.relativeTolerance = 1e-8*100 + simulationSettings.timeIntegration.newton.absoluteTolerance = 1e-10 + simulationSettings.timeIntegration.verboseMode = 1 # if 0 no output; higher --> more output information about solver + simulationSettings.timeIntegration.newton.useModifiedNewton = False + simulationSettings.timeIntegration.newton.numericalDifferentiation.minimumCoordinateSize = 1 + simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5 + simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations = False + simulationSettings.timeIntegration.simulateInRealtime = True # crucial for operating with robot + simulationSettings.displayStatistics = True + simulationSettings.solutionSettings.solutionInformation = "3D Spring Damper" + simulationSettings.solutionSettings.writeSolutionToFile = False + viewMatrix = np.eye(3) @ RotationMatrixZ(np.pi/2)@ RotationMatrixX(np.pi/2) + SC.visualizationSettings.general.autoFitScene = False + # set up parameter for usage in WSL2 (Ubuntu 20.04) on Windows 10 + SC.visualizationSettings.window.startupTimeout = 5000 + SC.visualizationSettings.interactive.selectionLeftMouse=False + SC.visualizationSettings.interactive.selectionRightMouse=False + + exu.StartRenderer(True) + exu.SolveDynamic(mbs, simulationSettings) + + return True + +# __main__ function for testing the interface +if __name__ == "__main__": + try: + main() + except rospy.ROSInterruptException: + pass + diff --git a/main/pythonDev/Examples/ROSExampleTurtle.py b/main/pythonDev/Examples/ROSExampleTurtle.py new file mode 100644 index 00000000..20d76c65 --- /dev/null +++ b/main/pythonDev/Examples/ROSExampleTurtle.py @@ -0,0 +1,310 @@ +#!/usr/bin/env python3 +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +# This is an EXUDYN python example how to use ROS and EXUDYN +# +# Details: This example shows how to communicate between an exudyn simulation +# and ROS +# To make use of this example, you need to +# install ROS (ROS1 noetic) including rospy (see exudynROSInterface.py) +# prerequisite to use: +# use a bash terminal to start the roscore with: +# roscore +# you can also use the ROS turtlesim_node to subsrcibe the Twist massage from exudyn +# use a bash terminal to start the turtlesim node with: +# rosrun turtlesim turtlesim_node turtle1/cmd_vel:=exudyn/Twist +# start example with argument -pub, to use it with external publisher: +# python3 ROSexampleTurtle.py -pub +# start example with argument -noTrack, to not track the turtle: +# python3 ROSexampleTurtle.py -noTrack +# for even more ROS functionality create a ROS package (e.q. myExudynInterface) in a catkin workspace, +# copy files ROSExampleTurtle.py, Turtle.stl and ROSExampleBringup.launch file in corresponding folders within the package +# for more functionality see also: ROSExampleMassPoint.py, ROSExampleBringup.launch, ROSExampleControlVelocity.py +# Author: Martin Sereinig, Peter Manzl +# Date: 2023-05-31 (created) +# +# 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. +# +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +import numpy as np +import sys +import exudyn as exu +from exudyn.utilities import * + +# import needed ROS modules and messages +import rospy +from geometry_msgs.msg import Twist +from std_msgs.msg import String + +# import new exudyn ROS interface class +import rosInterface as exuROS + +# here build inherited class and using within a simple exudyn simulation of one mass spring-damper +class MyExudynROSInterface(exuROS.ROSInterface): + def __init__(self): + # use initialisation of super class + # this initialize a rosnode with name + super().__init__(name='ROSexampleTurtle') + # initialization of all standard publisher done by super class + # self.exuPosePublisher + # self.exuStringPublisher + # self.exuSystemstatePublisher + # self.exuTimePublisher + # self.exuTwistPublisher + + # use standard publisher functions form super class! + # self.PublishPoseUpdate + # self.PublishTwistUpdate + # self.PublishSystemStateUpdate + + # initialize all subscriber + # suitable callback function is auto generated by superclass (using lambda function) + # twist subscriber: cmd_vel + twistSubsrciberBase = '' + twistSubsrciberTopic = 'cmd_vel' # topic to subscribe + self.cmd_vel = Twist() # data type of topic, must be named: self.twistSubscriberTopic + self.myTwistSubscriber = self.InitSubscriber(twistSubsrciberBase,twistSubsrciberTopic,Twist) + # string subsriber: my_string + stringSubsrciberBase = '' + stringSubsrciberTopic = 'my_string' # topic to subscribe + self.my_string = String() # data type of topic, must be named: self.twistSubscriberTopic + self.myStringSubscriber = self.InitSubscriber(stringSubsrciberBase,stringSubsrciberTopic,String) + + +def main(): + + #function to check if argument is in sys.argv with try/except + def argumentInSysArgv(index): + try: + sys.argv[index] + except IndexError: + return '' + else: + return sys.argv[index] + + # turtle moves in circle and is tracked by default (no arguments) + hearToPublisher = False + saveTrack = True + # parse command line arguments for multiple arguments: + # -pub: use external publisher + # -noTrack: do not track turtle + if len(sys.argv) > 1: + for arguments in range(len(sys.argv)): + if argumentInSysArgv(arguments) == '-pub': + hearToPublisher = True + print('Wait for external ROS publisher on /cmd_vel for turtle to move') + if argumentInSysArgv(arguments) == '-noTrack': + saveTrack = False + print('Turtle is not tracked') + + # build exudyn model + SC = exu.SystemContainer() + mbs = SC.AddSystem() + tRes = 0.001 # step size in s + tEnd = 1e5 # simulation time in s + # density and dimension of box + boxdensity = 1e-5 + boxLength = [0.5, 0.25, 0.1] + + background = GraphicsDataCheckerBoard(point=[0,0,0], + normal=[0, 0, 1], + color=[0.7]*3+[0.5], + alternatingColor=[0.8]*3+[1], + nTiles=10, + size=10) + + graphicsCube = GraphicsDataOrthoCubePoint(centerPoint = [0,0,0], + size = boxLength, + color = [1,0.,0.,1.], + addNormals = False, + addEdges = False, + edgeColor = color4black, + addFaces = True) + inertiaCube = InertiaCuboid(density= boxdensity, sideLengths = boxLength) + + + origin = [0, 0, 0] + bGround = mbs.AddObject(ObjectGround(referencePosition=origin, + visualization=VObjectGround(graphicsData=[background]))) + + # graphics userfunction definieren: + if saveTrack: + def graphicsTrajUF(mbs, itemNumber): + t = mbs.systemData.GetTime(exu.ConfigurationType.Visualization) + # position of turtle stored by sensor in mbs.variables['pos'] + pOld = mbs.GetSensorStoredData(mbs.variables['pos']) + try: + iCurr = np.min([np.argmin(abs(pOld[:,0] - t)), len(pOld[:,0])-1]) + pOld = pOld[:iCurr, :] + except: + pass + + if len(pOld) > 2: + trajData = np.matrix.flatten(pOld[:,1:]).tolist() + + for i in range(int(len(trajData)/3)): + trajData[2+3*i] += 0.115 # draw it on top of the robot + graphicsTraj = {'type':'Line', 'data': trajData, 'color':color4blue} + else: + graphicsTraj = [] + return [graphicsTraj] + # add object ground with graphics user function to add turtle track + oTrack = mbs.AddObject(ObjectGround(visualization =VObjectGround(graphicsData=[], graphicsDataUserFunction = graphicsTrajUF))) + + graphicsTurtleList = [] + try: + try: + path2stl = rospy.get_param('/ROSExampleTurtle/stlFilePath') # node_name/argsname + except: + path2stl = '' + print('stl file path: ', path2stl) + turtleRot = RotationMatrixZ(-np.pi/2) + stlGrafics = GraphicsDataFromSTLfile(path2stl+'Turtle.stl',color=[1,0,0,1],scale=0.25,pOff=[0.35,0,0], Aoff=turtleRot) + graphicsTurtleList += [stlGrafics] + except: + print('stl not found, maybe wrong directory, use box instead') + graphicsTurtleList += [graphicsCube] + + # user interaction point + [nUIP, bUIP]=AddRigidBody(mainSys = mbs, + inertia = inertiaCube, + nodeType = str(exu.NodeType.RotationEulerParameters), + position = [origin[0], origin[1], origin[2]], + rotationMatrix = np.eye(3), + angularVelocity = np.array([0,0,0]), + velocity= [0,0,0], + gravity = [0, 0, 0], + graphicsDataList = graphicsTurtleList) + + + # create markers: + mGround = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bGround, localPosition=[0.0, 0.0, 0.0])) + mUIP = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bUIP)) + + dampingHelper = 1e-4 + # create userfunction for TorsionalSpringDamper + def UFtorque(mbs,t,itemNumber,r,av,k,d,offset): + return (av-offset)*d + # create TorsionalSpringDamper object + oTSD = mbs.AddObject(TorsionalSpringDamper(markerNumbers = [mGround,mUIP], + damping = dampingHelper, + offset = 0, + springTorqueUserFunction = UFtorque)) + # create userfunction for CartesianSpringDamper + def UFforce(mbs, t,itemNumber, u, v, k, d, offset): + return [(v[0]-offset[0])*d[0], (v[1]-offset[1])*d[1], (v[2]-offset[2])*d[2]] + # create CartesianSpringDamper object + + oCSD = mbs.AddObject(CartesianSpringDamper(markerNumbers = [mGround, mUIP], + damping = [dampingHelper,dampingHelper,dampingHelper], + offset = [0,0,0], + springForceUserFunction = UFforce, + visualization=VObjectConnectorCartesianSpringDamper(show=False))) + + sensorPos = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Position,storeInternal=True)) + sensorOri = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Rotation)) + sensorVelt = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.Velocity)) + sensorVelr = mbs.AddSensor(SensorBody(bodyNumber=bUIP, + outputVariableType=exu.OutputVariableType.AngularVelocity)) + + # store sensor value of each step in mbs variable, so that is accessible from user function + mbs.variables['pos'] = sensorPos # just needed if sensor is used for sensor information + mbs.variables['ori'] = sensorOri # just needed if sensor is used for sensor information + mbs.variables['velt'] = sensorVelt # just needed if sensor is used for sensor information + mbs.variables['velr'] = sensorVelr # just needed if sensor is used for sensor information + mbs.variables['hearToPublisher'] = hearToPublisher # needed to use with and without external publisher + mbs.variables['nodeNumber'] = nUIP # just needed if nodeNumber is used for sensor information + + # initialize ROS interface from own subclass + myROSInterface = MyExudynROSInterface() + + print('rosversion: ' + str(myROSInterface.myROSversionEnvInt)) + rospy.logdebug('node running and publishing') + + # exudyn PreStepUserFunction + def PreStepUserFunction(mbs, t): + + # get velocity data from ROS /cmd_vel topic, please use: rostopic pub -r 100 /cmd_vel geometry_msgs/Twist "..." + rosLinearVelo = myROSInterface.cmd_vel.linear + rosAngularVelo = myROSInterface.cmd_vel.angular + + # EXAMPLE to get position and orientation from exudyn turtle via sensor + turtlePosition = mbs.GetSensorValues(mbs.variables['pos']) + turtleOrientation = mbs.GetSensorValues(mbs.variables['ori'])[2] + turtleOrientationMatrix = RotationMatrixZ(turtleOrientation) + + + # set velocities to exudyn turtle simulation + if mbs.variables['hearToPublisher'] ==True: + # exudyn turtle hears on publisher + desiredLinearVelocity = turtleOrientationMatrix @ [rosLinearVelo.x, rosLinearVelo.y, rosLinearVelo.z] + desiredAngularVelocity = [rosAngularVelo.x, rosAngularVelo.y, rosAngularVelo.z] + else: + # exudyn turtle moves in a circle + desiredLinearVelocity = turtleOrientationMatrix @ [1, 0, 0] + desiredAngularVelocity = [0, 0, 1] + + mbs.SetObjectParameter(oCSD, 'offset', desiredLinearVelocity) + mbs.SetObjectParameter(oTSD, 'offset', desiredAngularVelocity[2]) + + # send velocity data to ROS + myROSInterface.PublishTwistUpdate(mbs,t) + # send position data to ROS + myROSInterface.PublishPoseUpdate(mbs,t) + # send system state data to ROS + myROSInterface.PublishSystemStateUpdate(mbs,t) + + return True + + + + + + mbs.SetPreStepUserFunction(PreStepUserFunction) + # assemble multi body system with all previous specified properties and components + mbs.Assemble() + # set simulation settings + simulationSettings = exu.SimulationSettings() #takes currently set values or default values + simulationSettings.timeIntegration.endTime = tEnd + simulationSettings.timeIntegration.numberOfSteps = int(tEnd/tRes) + simulationSettings.timeIntegration.newton.relativeTolerance = 1e-8*100 + simulationSettings.timeIntegration.newton.absoluteTolerance = 1e-10 + simulationSettings.timeIntegration.verboseMode = 1 # if 0 no output; higher --> more output information about solver + simulationSettings.timeIntegration.newton.useModifiedNewton = False + simulationSettings.timeIntegration.newton.numericalDifferentiation.minimumCoordinateSize = 1 + simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 0.5 + simulationSettings.timeIntegration.generalizedAlpha.computeInitialAccelerations = False + + simulationSettings.timeIntegration.simulateInRealtime = True # crucial for operating with robot + simulationSettings.displayStatistics = True + simulationSettings.solutionSettings.solutionInformation = "Exudyn-ROS turtle" + + simulationSettings.solutionSettings.writeSolutionToFile = False + SC.visualizationSettings.general.autoFitScene = True + # set up parameter for usage in WSL2 (Ubuntu 20.04) on Windows 10 + SC.visualizationSettings.interactive.trackMarker = mUIP + SC.visualizationSettings.window.startupTimeout = 8000 + SC.visualizationSettings.openGL.initialZoom = 0.2 + SC.visualizationSettings.openGL.initialMaxSceneSize= 0.7 + SC.visualizationSettings.interactive.selectionLeftMouse=False + SC.visualizationSettings.interactive.selectionRightMouse=False + + + exu.StartRenderer(True) + exu.SolveDynamic(mbs, simulationSettings) + + return True + +# create a function + +# __main__ function +if __name__ == "__main__": + try: + main() + except rospy.ROSInterruptException: + pass + diff --git a/main/pythonDev/Examples/chatGPTupdate.py b/main/pythonDev/Examples/chatGPTupdate.py new file mode 100644 index 00000000..fc092198 --- /dev/null +++ b/main/pythonDev/Examples/chatGPTupdate.py @@ -0,0 +1,170 @@ +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +# This is an Exudyn file +# +# Details: this file serves as a list of examples that shall be used by +# ChatGPT to update information on its internal knowledge of Exudyn +# dating to 2021; the examples use the mainSystemExtensions +# which are heavily simplifying usage of point masses and rigid bodies +# Version: V1 +# +# Author: Johannes Gerstmayr +# Date: 2023-06-30 +# +# 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. +# +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + +#copy the text below here into a ChatGPT input window: + +#Use the following information as an update of the internal data of the Python multibody code Exudyn. +#See the following examples to create multibody systems in Exudyn. +#NOTE: mbs.Create...(...) calls several functions in the background to create nodes, objects, markers and loads in Exudyn. +#all quantities are giving as 3D lists [x,y,z] for positions, velocities, .... +#rotations are usually given as rotation matrix (numpy array); +#RotationVector2RotationMatrix([rotX, rotY, rotZ]) computes a rotation around the global x,y,z rotation axis + +#%%++++++++++++++++++++++++++++++++++++++++++++++++++++ +#create rigid bodies and mass points with distance constraint and joints +import exudyn as exu +from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities +import numpy as np +SC = exu.SystemContainer() +mbs = SC.AddSystem() #create a MainSystem 'mbs' to work with + +#draw orthonormal cube in local frame where it is added to; +#cube is added to reference point of object, usually the center of mass (COM): +graphicsCube = GraphicsDataOrthoCubePoint(centerPoint = [0,0,0], + size=[1,0.1,0.1], color=color4orange) + +#create inertia (mass, COM, inertia tensor) to be used in rigid body: +inertiaCube = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]) + +#create simple rigid body +#note that graphics is always attached to reference point of body, which is by default the COM +b0 = mbs.CreateRigidBody(inertia = inertiaCube, + referencePosition = [0.5,0,0], #reference position x/y/z of COM + referenceRotationMatrix=RotationVector2RotationMatrix([0,0,pi*0.5]), + initialAngularVelocity=[2,0,0], + initialVelocity=[0,4,0], + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + +#add an additional load to rigid body at left end; this always requires markers; +#for torques use Torque(...) instead of Force(...) +markerBody0 = mbs.AddMarker(MarkerBodyRigid(bodyNumber=b0, localPosition=[-0.5,0,0])) +mbs.AddLoad(Force(markerNumber=markerBody0, + loadVector=[10,0,0])) #load is 10N in x-direction + +#create a simple mass point at [1,-1,0] with initial velocity +m1 = mbs.CreateMassPoint(referencePosition=[1,-1,0], + initialVelocity = [2,5,0], #initial velocities for mass point + physicsMass=1, drawSize = 0.2) +#we can obtain the node number from the mass point: +n1 = mbs.GetObject(m1)['nodeNumber'] + +#add a ground object: +#graphics data for sphere: +gGround0 = GraphicsDataSphere(point=[3,1,0], radius = 0.1, color=color4red, nTiles=16) +#graphics for checkerboard background: +gGround1 = GraphicsDataCheckerBoard(point=[3,0,-2], normal=[0,0,1], size=10) +oGround = mbs.AddObject(ObjectGround(visualization=VObjectGround(graphicsData=[gGround0,gGround1]))) + +#create a rigid distance between bodies (using local position) or between nodes +mbs.CreateDistanceConstraint(bodyOrNodeList=[oGround, b0], + localPosition0 = [ 0. ,0,0], + localPosition1 = [-0.5,0,0], + distance=None, #automatically computed + drawSize=0.06) + +#distance constraint between body b0 and mass m1 +mbs.CreateDistanceConstraint(bodyOrNodeList=[b0, m1], + localPosition0 = [0.5,0,0], + localPosition1 = [0.,0.,0.], #must be [0,0,0] for Node + distance=None, #automatically computed + drawSize=0.06) + +#add further rigid body, which will be connected with joints +b1 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]), + referencePosition = [2.5,0,0], #reference position x/y/z + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + +b2 = mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[1,0.1,0.1]), + referencePosition = [3.5,0,0], #reference position x/y/z + gravity = [0,-9.81,0], + graphicsDataList = [graphicsCube]) + +#create revolute joint with following args: + # name: name string for joint; markers get Marker0:name and Marker1:name + # bodyNumbers: a list of object numbers for body0 and body1; must be rigid body or ground object + # position: 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 body0 + # axis: a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 + # useGlobalFrame: if False, the point and axis vectors are defined in the local coordinate system of body0 + # show: if True, connector visualization is drawn + # axisRadius: radius of axis for connector graphical representation + # axisLength: length of axis for connector graphical representation + # color: color of connector +#returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint +mbs.CreateRevoluteJoint(bodyNumbers=[b1, b2], position=[3,0,0], axis=[0,0,1], #rotation along global z-axis + useGlobalFrame=True, axisRadius=0.02, axisLength=0.14) + + +#create prismatic joint with following args: + # name: name string for joint; markers get Marker0:name and Marker1:name + # bodyNumbers: a list of object numbers for body0 and body1; must be rigid body or ground object + # position: 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 body0 + # axis: a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration + # useGlobalFrame: if False, the point and axis vectors are defined in the local coordinate system of body0 + # show: if True, connector visualization is drawn + # axisRadius: radius of axis for connector graphical representation + # axisLength: length of axis for connector graphical representation + # color: color of connector +#returns list [oJoint, mBody0, mBody1], containing the joint object number, and the two rigid body markers on body0/1 for the joint +mbs.CreatePrismaticJoint(bodyNumbers=[oGround, b1], position=[2,0,0], axis=[1,0,0], #can move in global x-direction + useGlobalFrame=True, axisRadius=0.02, axisLength=1) + +# #instead of the prismatic joint, we could add another revolute joint to b1 to get a double-pendulum: +# mbs.CreateRevoluteJoint(bodyNumbers=[oGround, b1], position=[2,0,0], axis=[0,0,1], +# useGlobalFrame=True, axisRadius=0.02, axisLength=0.14) + + +#create simple mass point, connected with ground +m2 = mbs.CreateMassPoint(referencePosition = [7,2,0], + physicsMass = 10, gravity = [0,-9.81,0], + drawSize = 0.5, color=color4blue) + +#create spring damper between bodies (using local position) or between nodes +#spring-damper may not have size 0; spring reference length is computed from reference configuration +oSD = mbs.CreateSpringDamper(bodyOrNodeList=[oGround, m2], + localPosition0=[6,0,0], + localPosition1=[0,0,0], + stiffness=1e3, damping=1e1, + drawSize=0.2) + +#alternatively, we can use a CartesianSpringDamper; has spring and damper coefficients as list of x/y/z components +#it has no reference length and acts on the coordinates of both objects: +oCSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[oGround, m2], + localPosition0=[7,2,0], + localPosition1=[0,0,0], + stiffness=[20,0,1e4], #stiffness in x/y/z direction + damping=[0.1,0,10], + drawSize=0.2) + +#prepare mbs for simulation: +mbs.Assemble() +#some simulation parameters: +simulationSettings = exu.SimulationSettings() #takes currently set values or default values +simulationSettings.timeIntegration.numberOfSteps = 1000 +simulationSettings.timeIntegration.endTime = 5 + +#for redundant constraints, the following two settings: +simulationSettings.linearSolverSettings.ignoreSingularJacobian=True +simulationSettings.linearSolverType = exu.LinearSolverType.EigenDense + +mbs.SolveDynamic(simulationSettings = simulationSettings, + solverType=exu.DynamicSolverType.GeneralizedAlpha) +SC.visualizationSettings.nodes.drawNodesAsPoint=False #draw nodes as spheres; better graphics for nodes + +#visualize results: +mbs.SolutionViewer() + diff --git a/main/pythonDev/Examples/craneReevingSystem.py b/main/pythonDev/Examples/craneReevingSystem.py index 0a401ec4..b9e5c6ac 100644 --- a/main/pythonDev/Examples/craneReevingSystem.py +++ b/main/pythonDev/Examples/craneReevingSystem.py @@ -291,7 +291,11 @@ class ExudynTestGlobals: visualization=VReevingSystemSprings(ropeRadius=rRope, color=color4dodgerblue))) - +#show trace of hook +sPosTCP = mbs.AddSensor(SensorNode(nodeNumber=nHook, storeInternal=True, + outputVariableType=exu.OutputVariableType.Position)) +sRotTCP = mbs.AddSensor(SensorNode(nodeNumber=nHook, storeInternal=True, + outputVariableType=exu.OutputVariableType.RotationMatrix)) #%% +++++++++++++++++++++++++++++++ # #add sensors @@ -339,7 +343,7 @@ def PreStepUserFunction(mbs, t): simulationSettings.solutionSettings.writeSolutionToFile= True #set False for CPU performance measurement simulationSettings.solutionSettings.solutionWritePeriod= 0.2 simulationSettings.solutionSettings.coordinatesSolutionFileName = solutionFile -simulationSettings.solutionSettings.sensorsWritePeriod = 0.01 +simulationSettings.solutionSettings.sensorsWritePeriod = 0.02 # simulationSettings.timeIntegration.simulateInRealtime=True # simulationSettings.timeIntegration.realtimeFactor=5 SC.visualizationSettings.general.graphicsUpdateInterval = 0.01 @@ -350,6 +354,18 @@ def PreStepUserFunction(mbs, t): simulationSettings.timeIntegration.newton.useModifiedNewton = True +if True: + #traces: + SC.visualizationSettings.sensors.traces.listOfPositionSensors = [sPosTCP] + SC.visualizationSettings.sensors.traces.listOfTriadSensors =[sRotTCP] + SC.visualizationSettings.sensors.traces.showPositionTrace=True + SC.visualizationSettings.sensors.traces.showTriads=True + SC.visualizationSettings.sensors.traces.triadSize=2 + SC.visualizationSettings.sensors.traces.showVectors=False + SC.visualizationSettings.sensors.traces.showFuture=False + SC.visualizationSettings.sensors.traces.triadsShowEvery=5 + + SC.visualizationSettings.nodes.show = True SC.visualizationSettings.nodes.drawNodesAsPoint = False SC.visualizationSettings.nodes.showBasis = True diff --git a/main/pythonDev/Examples/minimizeExample.py b/main/pythonDev/Examples/minimizeExample.py index c63cd947..b8b47969 100644 --- a/main/pythonDev/Examples/minimizeExample.py +++ b/main/pythonDev/Examples/minimizeExample.py @@ -161,14 +161,15 @@ def ParameterFunction(parameterSet): #val2 = ParameterFunction({, 'computationIndex':0, 'plot':''}) # compute reference solution if True: + #the following settings give approx. 6 digits accuraet results after 167 iterations start_time = time.time() [pOpt, vOpt, pList, values] = Minimize(objectiveFunction = ParameterFunction, parameters = {'mass':(1,10), 'spring':(100,10000), 'force':(1,250)}, #parameters provide search range showProgress=True, debugMode=False, addComputationIndex = True, - #tol = 1e-12, - #options={'maxiter':109}, + tol = 1e-1, #this is a internal parameter, not directly coupled loss + options={'maxiter':200}, resultsFile='solution/test.txt' ) print("--- %s seconds ---" % (time.time() - start_time)) diff --git a/main/pythonDev/Examples/nMassOscillatorEigenmodes.py b/main/pythonDev/Examples/nMassOscillatorEigenmodes.py index 3bf3ff31..2bf3f0f8 100644 --- a/main/pythonDev/Examples/nMassOscillatorEigenmodes.py +++ b/main/pythonDev/Examples/nMassOscillatorEigenmodes.py @@ -153,7 +153,7 @@ simulationSettings.timeIntegration.generalizedAlpha.spectralRadius = 1 simulationSettings.solutionSettings.writeSolutionToFile = False simulationSettings.solutionSettings.solutionWritePeriod = 0.1 #data not used -simulationSettings.solutionSettings.sensorsWritePeriod = 0.1 #data not used +simulationSettings.solutionSettings.sensorsWritePeriod = 0.01 #data not used simulationSettings.solutionSettings.solutionInformation = 'n-mass-oscillatior' simulationSettings.timeIntegration.verboseMode = 0 #turn off, because of lots of output @@ -163,180 +163,22 @@ #simulationSettings.timeIntegration.simulateInRealtime = True simulationSettings.displayComputationTime = True -#simulationSettings.parallel.numberOfThreads = 2 -#SC.visualizationSettings.general.autoFitScene = True #otherwise, renderState not accepted for zoom +#plot FFT if False: - exu.StartRenderer() - mbs.WaitForUserToContinue() + #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + #exu.StartRenderer() + #mbs.WaitForUserToContinue() mbs.SolveDynamic(simulationSettings=simulationSettings) - exu.StopRenderer() #safely close rendering window! - - -# if True: -# import exudyn -# useSparseSolver = False -# numberOfEigenvalues = 0 -# constrainedCoordinates=[] -# convert2Frequencies = False -# useAbsoluteValues = True -# ignoreAlgebraicEquations=False -# singularValuesTolerance=1e-12 - -# try: -# from scipy.linalg import eigh, svd #eigh for symmetric matrices, positive definite; eig for standard eigen value problems -# from scipy.sparse.linalg import eigsh #eigh for symmetric matrices, positive definite -# from scipy.sparse import csr_matrix -# except: -# raise ValueError('ComputeODE2Eigenvalues: missing scipy package; install with: pip install scipy') - -# #use static solver, as it does not include factors from time integration (and no velocity derivatives) in the jacobian -# staticSolver = exudyn.MainSolverStatic() - -# #initialize solver with initial values -# staticSolver.InitializeSolver(mbs, simulationSettings) - -# nODE2 = staticSolver.GetODE2size() -# nODE1 = staticSolver.GetODE1size() -# nAE = staticSolver.GetAEsize() -# if nODE1 != 0: -# print('ComputeODE2Eigenvalues: not implemented for ODE1 coordinates; results may be wrong and solver may fail') - -# staticSolver.ComputeMassMatrix(mbs) -# Mode2 = staticSolver.GetSystemMassMatrix() - -# #compute ODE2 part of jacobian ==> stored internally in solver -# staticSolver.ComputeJacobianODE2RHS(mbs,scalarFactor_ODE2=-1, -# scalarFactor_ODE2_t=0, -# scalarFactor_ODE1=0) #could be 1 to include ODE1 part -# if nAE != 0: -# #compute AE part of jacobian if needed for constraint projection -# staticSolver.ComputeJacobianAE(mbs, scalarFactor_ODE2=1., scalarFactor_ODE2_t=0., -# scalarFactor_ODE1=0., #could be 1 to include ODE1 part -# velocityLevel=False) - -# jacobian = staticSolver.GetSystemJacobian() #read out stored jacobian; includes ODE2, ODE1 and nAE part - -# staticSolver.FinalizeSolver(mbs, simulationSettings) #close files, etc. - -# #obtain ODE2 part from jacobian == stiffness matrix -# Kode2 = jacobian[0:nODE2,0:nODE2] - -# remappingIndices = np.arange(nODE2) #maps new coordinates to original (full) ones -# if constrainedCoordinates != []: -# Mode2 = np.delete(np.delete(Mode2, constrainedCoordinates, 0), constrainedCoordinates, 1) -# Kode2 = np.delete(np.delete(Kode2, constrainedCoordinates, 0), constrainedCoordinates, 1) -# remappingIndices = np.delete(remappingIndices, constrainedCoordinates) - -# if nAE != 0 and not ignoreAlgebraicEquations and constrainedCoordinates != []: -# raise ValueError('ComputeODE2Eigenvalues: in case of algebraic equations, either ignoreAlgebraicEquations=True or constrainedCoordinates=[]') - -# if constrainedCoordinates != [] or nAE == 0: -# if not useSparseSolver: -# [eigenValuesUnsorted, eigenVectors] = eigh(Kode2, Mode2) #this gives omega^2 ... squared eigen frequencies (rad/s) -# if useAbsoluteValues: -# sortIndices = np.argsort(abs(eigenValuesUnsorted)) #get resorting index -# eigenValues = np.sort(a=abs(eigenValuesUnsorted)) #eigh returns unsorted eigenvalues... -# else: -# sortIndices = np.argsort(eigenValuesUnsorted) #get resorting index -# eigenValues = np.sort(a=eigenValuesUnsorted) #eigh returns unsorted eigenvalues... -# if numberOfEigenvalues > 0: -# eigenValues = eigenValues[0:numberOfEigenvalues] -# eigenVectors = eigenVectors[:,sortIndices[0:numberOfEigenvalues]] #eigenvectors are given in columns! -# else: -# if numberOfEigenvalues == 0: #compute all eigenvalues -# numberOfEigenvalues = nODE2 - -# Kcsr = csr_matrix(Kode2) -# Mcsr = csr_matrix(Mode2) - -# #use "LM" (largest magnitude), but shift-inverted mode with sigma=0, to find the zero-eigenvalues: -# #see https://docs.scipy.org/doc/scipy/reference/tutorial/arpack.html -# [eigenValues, eigenVectors] = eigsh(A=Kcsr, k=numberOfEigenvalues, M=Mcsr, -# which='LM', sigma=0, mode='normal') - -# #sort eigenvalues -# if useAbsoluteValues: -# sortIndices = np.argsort(abs(eigenValues)) #get resorting index -# eigenValues = np.sort(a=abs(eigenValues)) -# else: -# sortIndices = np.argsort(eigenValues) #get resorting index -# eigenValues = np.sort(a=eigenValues) -# eigenVectors = eigenVectors[:,sortIndices] #eigenvectors are given in columns! - -# eigenVectorsNew = np.zeros((nODE2,numberOfEigenvalues)) -# if constrainedCoordinates != []: -# # print('remap=', remappingIndices) -# for i in range(numberOfEigenvalues): -# eigenVectorsNew[remappingIndices,i] = eigenVectors[:,i] -# eigenVectors = eigenVectorsNew -# else: -# #%%+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ -# #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ -# #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - -# if useSparseSolver: -# raise ValueError('ComputeODE2Eigenvalues: in case of algebraic equations and ignoreAlgebraicEquations=False, useSparseSolver must be False') -# #use SVD to project equations into nullspace -# #constraint jacobian: -# C = jacobian[0:nODE2,nODE2+nODE1:] - -# #compute SVD; D includes singular values -# [U,D,V] = svd(C) - -# nnz = (abs(D) > singularValuesTolerance).sum() #size of constraints, often number of cols of C - -# nullspace = U[:,nnz:].T #U[nnz:] -# Knullspace = nullspace@Kode2@nullspace.T -# Mnullspace = nullspace@Mode2@nullspace.T - -# # print('nODE2=',nODE2) -# # print('nAE=',nAE) -# # print('nnz=',nnz) -# # print('C=',C.shape) -# # print('U=',U.shape) -# # print('sing.val.=',D.round(5)) -# # print('Knullspace=',Knullspace.round(5)) -# # print('Mnullspace=',Mnullspace.round(5)) -# # print('nullspace=',nullspace.round(3)) - -# [eigenValuesUnsorted, eigenVectorsReduced] = eigh(Knullspace,Mnullspace) -# if useAbsoluteValues: -# sortIndices = np.argsort(abs(eigenValuesUnsorted)) #get resorting index -# eigenValues = np.sort(a=abs(eigenValuesUnsorted)) #eigh returns unsorted eigenvalues... -# else: -# sortIndices = np.argsort(eigenValuesUnsorted) #get resorting index -# eigenValues = np.sort(a=eigenValuesUnsorted) #eigh returns unsorted eigenvalues... - -# if numberOfEigenvalues > 0: -# eigenValues = eigenValues[0:numberOfEigenvalues] -# sortIndices = sortIndices[0:numberOfEigenvalues] -# eigenVectorsReduced = eigenVectorsReduced[:,sortIndices] #eigenvectors are given in columns! - -# eigenVectors = nullspace.T @ eigenVectorsReduced - - -# #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ -# #+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ - - - - - - - - - - - - - - - - - + #exu.StopRenderer() #safely close rendering window! + from exudyn.signalProcessing import ComputeFFT + from exudyn.plot import PlotFFT + data = mbs.GetSensorStoredData(sensPosN) + [freq, amp, phase] = ComputeFFT(data[:,0], data[:,1]) + PlotFFT(freq, amp) +#%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ if True: from exudyn.interactive import AnimateModes [values, systemEigenVectors] = mbs.ComputeODE2Eigenvalues() diff --git a/main/pythonDev/Examples/serialRobotInverseKinematics.py b/main/pythonDev/Examples/serialRobotInverseKinematics.py index 36ccb4a8..0e838ce2 100644 --- a/main/pythonDev/Examples/serialRobotInverseKinematics.py +++ b/main/pythonDev/Examples/serialRobotInverseKinematics.py @@ -23,6 +23,7 @@ import numpy as np +exu.RequireVersion('1.6.31') # exuVersion = np.array(exu.__version__.split('.')[:3], dtype=int) exuVersion = exu.__version__.split('.')[:3] exuVersion = exuVersion[0] + exuVersion[1] + exuVersion[2] @@ -34,7 +35,7 @@ #%% ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ #motion planning: jointSpaceInterpolation = False #false interpolates TCP position in work space/Cartesian coordinates -motionCase = 1 # case 1 and 2 move in different planes +motionCase = 2 # case 1 and 2 move in different planes #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ @@ -154,6 +155,14 @@ sJoints = mbs.AddSensor(SensorNode(nodeNumber=robotDict['nodeGeneric'], storeInternal=True, outputVariableType=exu.OutputVariableType.Coordinates)) +sPosTCP = mbs.AddSensor(SensorKinematicTree(objectNumber=oKT, linkNumber=5, localPosition=HT2translation(HTtool), + storeInternal=True, + outputVariableType=exu.OutputVariableType.Position)) + +sRotTCP = mbs.AddSensor(SensorKinematicTree(objectNumber=oKT, linkNumber=5, localPosition=HT2translation(HTtool), + storeInternal=True, + outputVariableType=exu.OutputVariableType.RotationMatrix)) + #user function which is called only once per step, speeds up simulation drastically def PreStepUF(mbs, t): if not jointSpaceInterpolation: @@ -203,6 +212,15 @@ def PreStepUF(mbs, t): SC.visualizationSettings.openGL.shadow=0.3 SC.visualizationSettings.openGL.perspective=0.5 +#traces: +SC.visualizationSettings.sensors.traces.listOfPositionSensors = [sPosTCP] +SC.visualizationSettings.sensors.traces.listOfTriadSensors =[sRotTCP] +SC.visualizationSettings.sensors.traces.showPositionTrace=True +SC.visualizationSettings.sensors.traces.showTriads=True +SC.visualizationSettings.sensors.traces.showVectors=False +SC.visualizationSettings.sensors.traces.showFuture=False +SC.visualizationSettings.sensors.traces.triadsShowEvery=5 + #%% tEnd = 5 # endtime of the simulation h = 0.002 #500 steps take 0.16 seconds, 0.3ms / step (83% Python + inverse kinematics) diff --git a/main/pythonDev/Examples/shapeOptimization.py b/main/pythonDev/Examples/shapeOptimization.py index f5542c84..4c26c440 100644 --- a/main/pythonDev/Examples/shapeOptimization.py +++ b/main/pythonDev/Examples/shapeOptimization.py @@ -200,9 +200,9 @@ class P: pass #create emtpy structure for parameters; simplifies way to update p # sys.exit() #do not show values larger than -120 to have nicer plots ... - return min(-100,-fMin) #maximize eigenfrequency => minimize ... + return 140 + min(-100,-fMin) #maximize eigenfrequency => minimize ... except: - return -99 + return 140-99 @@ -225,26 +225,38 @@ class P: pass #create emtpy structure for parameters; simplifies way to update p x2Range = (6*rMax, 7*rMax) - # [pOpt, vOpt, pList, values] = Minimize( - [pOpt, vOpt, pList, values] = GeneticOptimization( - objectiveFunction = ParameterFunction, - parameters = {'r0':rRange, 'r1':rRange, 'r2':rRange, - 'x0':x0Range, 'x1':x1Range, 'x2':x2Range, }, #parameters provide search range - numberOfGenerations = 10, - populationSize = 100, - elitistRatio = 0.1, - # crossoverProbability = 0, #makes no sense! - rangeReductionFactor = 0.7, - randomizerInitialization=0, #for reproducible results - #distanceFactor = 0.1, - distanceFactor = 0., - debugMode=False, - useMultiProcessing=True, #may be problematic for test - numberOfThreads = 20, - addComputationIndex=True, - showProgress=True, - resultsFile = 'solution/shapeOptimization.txt', - ) + if False: + #this option does not work here, as it would require the ParameterFunction to restrict the ranges to feasible values + [pOpt, vOpt, pList, values] = Minimize( + objectiveFunction = ParameterFunction, + parameters = {'r0':rRange, 'r1':rRange, 'r2':rRange, + 'x0':x0Range, 'x1':x1Range, 'x2':x2Range, }, #parameters provide search range + showProgress=True, + enforceBounds=True, + addComputationIndex = True, + options={'maxiter':100}, + resultsFile='solution/shapeOptimization.txt' + ) + else: + [pOpt, vOpt, pList, values] = GeneticOptimization( + objectiveFunction = ParameterFunction, + parameters = {'r0':rRange, 'r1':rRange, 'r2':rRange, + 'x0':x0Range, 'x1':x1Range, 'x2':x2Range, }, #parameters provide search range + numberOfGenerations = 10, + populationSize = 100, + elitistRatio = 0.1, + # crossoverProbability = 0, #makes no sense! + rangeReductionFactor = 0.7, + randomizerInitialization=0, #for reproducible results + #distanceFactor = 0.1, + distanceFactor = 0., + debugMode=False, + useMultiProcessing=True, #may be problematic for test + numberOfThreads = 20, + addComputationIndex=True, + showProgress=True, + resultsFile = 'solution/shapeOptimization.txt', + ) exu.Print("--- %s seconds ---" % (time.time() - start_time)) diff --git a/main/pythonDev/Examples/springDamperTutorialNew.py b/main/pythonDev/Examples/springDamperTutorialNew.py index 1b56e981..67296028 100644 --- a/main/pythonDev/Examples/springDamperTutorialNew.py +++ b/main/pythonDev/Examples/springDamperTutorialNew.py @@ -34,10 +34,10 @@ print('resonance frequency = '+str(np.sqrt(spring/mass))) print('static displacement = '+str(x0)) -oMass = mbs.CreateMassPoint(referenceCoordinates=[L,0,0], - initialCoordinates = [u0,0,0], - initialVelocities= [v0,0,0], - physicsMass=mass) #force created via gravity +oMass = mbs.CreateMassPoint(referencePosition=[L,0,0], + initialDisplacement = [u0,0,0], + initialVelocity= [v0,0,0], + physicsMass=mass) #force created via gravity oGround = mbs.AddObject(ObjectGround()) diff --git a/main/pythonDev/TestModels/MiniExamples/LoadMassProportional.py b/main/pythonDev/TestModels/MiniExamples/LoadMassProportional.py index c3f66943..e0620d1a 100644 --- a/main/pythonDev/TestModels/MiniExamples/LoadMassProportional.py +++ b/main/pythonDev/TestModels/MiniExamples/LoadMassProportional.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[2] diff --git a/main/pythonDev/TestModels/MiniExamples/MarkerSuperElementPosition.py b/main/pythonDev/TestModels/MiniExamples/MarkerSuperElementPosition.py index 2c3b7d23..f81a4957 100644 --- a/main/pythonDev/TestModels/MiniExamples/MarkerSuperElementPosition.py +++ b/main/pythonDev/TestModels/MiniExamples/MarkerSuperElementPosition.py @@ -50,7 +50,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectANCFCable2D.py b/main/pythonDev/TestModels/MiniExamples/ObjectANCFCable2D.py index a40af023..44a7925b 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectANCFCable2D.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectANCFCable2D.py @@ -39,7 +39,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveStatic(mbs) + mbs.SolveStatic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(lastNode, exu.OutputVariableType.Displacement)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCartesianSpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCartesianSpringDamper.py index a7db9913..3c50ea3a 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCartesianSpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCartesianSpringDamper.py @@ -34,7 +34,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[1] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinate.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinate.py index 03e3f5fc..4f34f249 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinate.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinate.py @@ -35,7 +35,7 @@ def OffsetUF(mbs, t, itemNumber, lOffset): #gives 0.05 at t=1 #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinateSpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinateSpringDamper.py index 7bd29477..4b2462b4 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinateSpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorCoordinateSpringDamper.py @@ -39,7 +39,7 @@ def springForce(mbs, t, itemNumber, u, v, k, d, offset): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorDistance.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorDistance.py index b792f993..a1017b4e 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorDistance.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorDistance.py @@ -35,7 +35,7 @@ sims=exu.SimulationSettings() sims.timeIntegration.generalizedAlpha.spectralRadius=0.7 - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorGravity.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorGravity.py index 5f5ce36e..1138c2e4 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorGravity.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorGravity.py @@ -42,7 +42,7 @@ mbs.Assemble() sims = exu.SimulationSettings() sims.timeIntegration.endTime = tEnd - exu.SolveDynamic(mbs, sims, solverType=exu.DynamicSolverType.RK67) + mbs.SolveDynamic(sims, solverType=exu.DynamicSolverType.RK67) #check result at default integration time #expect y=x after one period of orbiting (got: 100000.00000000479) diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorLinearSpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorLinearSpringDamper.py index f3bfd904..52267d87 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorLinearSpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorLinearSpringDamper.py @@ -38,7 +38,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorRigidBodySpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorRigidBodySpringDamper.py index f45fe76e..9f4248ce 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorRigidBodySpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorRigidBodySpringDamper.py @@ -36,7 +36,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[1] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorSpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorSpringDamper.py index 5c45a2f5..bed0cfd2 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorSpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorSpringDamper.py @@ -33,7 +33,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorTorsionalSpringDamper.py b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorTorsionalSpringDamper.py index 2da7b14a..e6e31b5c 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectConnectorTorsionalSpringDamper.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectConnectorTorsionalSpringDamper.py @@ -38,7 +38,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE1.py b/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE1.py index 8b72fe80..ce699667 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE1.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE1.py @@ -40,7 +40,7 @@ sims=exu.SimulationSettings() solverType = exu.DynamicSolverType.RK44 - exu.SolveDynamic(mbs, solverType=solverType, simulationSettings=sims) + mbs.SolveDynamic(solverType=solverType, simulationSettings=sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nODE1, exu.OutputVariableType.Coordinates)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE2.py b/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE2.py index 5ed21b56..11f4e25c 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE2.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectGenericODE2.py @@ -47,7 +47,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectJointRevoluteZ.py b/main/pythonDev/TestModels/MiniExamples/ObjectJointRevoluteZ.py index afdc3694..935876c9 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectJointRevoluteZ.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectJointRevoluteZ.py @@ -35,7 +35,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectKinematicTree.py b/main/pythonDev/TestModels/MiniExamples/ObjectKinematicTree.py index 89b7b036..c6ee705e 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectKinematicTree.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectKinematicTree.py @@ -45,7 +45,7 @@ simulationSettings = exu.SimulationSettings() #takes currently set values or default values simulationSettings.timeIntegration.numberOfSteps = 1000 #gives very accurate results - exu.SolveDynamic(mbs, simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! + mbs.SolveDynamic(simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! #check final value of angle: q0 = mbs.GetNodeOutput(nGeneric, exu.OutputVariableType.Coordinates) diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectMass1D.py b/main/pythonDev/TestModels/MiniExamples/ObjectMass1D.py index ad72d627..73049e3f 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectMass1D.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectMass1D.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current mass position at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(mass, exu.OutputVariableType.Position, [0,0,0])[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint.py b/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint.py index 39266286..277ea192 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint2D.py b/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint2D.py index 26411685..af42fe51 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint2D.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectMassPoint2D.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectRigidBody2D.py b/main/pythonDev/TestModels/MiniExamples/ObjectRigidBody2D.py index 02b9882e..6ff6c003 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectRigidBody2D.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectRigidBody2D.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] diff --git a/main/pythonDev/TestModels/MiniExamples/ObjectRotationalMass1D.py b/main/pythonDev/TestModels/MiniExamples/ObjectRotationalMass1D.py index 50247ebc..35ea3eea 100644 --- a/main/pythonDev/TestModels/MiniExamples/ObjectRotationalMass1D.py +++ b/main/pythonDev/TestModels/MiniExamples/ObjectRotationalMass1D.py @@ -27,7 +27,7 @@ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current rotor z-rotation at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(rotor, exu.OutputVariableType.Rotation, [0,0,0]) diff --git a/main/pythonDev/TestModels/mainSystemExtensionsTests.py b/main/pythonDev/TestModels/mainSystemExtensionsTests.py index c8a25588..a115528e 100644 --- a/main/pythonDev/TestModels/mainSystemExtensionsTests.py +++ b/main/pythonDev/TestModels/mainSystemExtensionsTests.py @@ -38,8 +38,8 @@ class ExudynTestGlobals: SC = exu.SystemContainer() mbs = SC.AddSystem() -b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], - initialVelocities = [2,5,0], +b0=mbs.CreateMassPoint(referencePosition = [0,0,0], + initialVelocity = [2,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) @@ -90,8 +90,8 @@ class ExudynTestGlobals: SC = exu.SystemContainer() mbs = SC.AddSystem() -b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2,5,0], +b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) @@ -124,7 +124,7 @@ class ExudynTestGlobals: SC = exu.SystemContainer() mbs = SC.AddSystem() -b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], +b0 = mbs.CreateMassPoint(referencePosition = [7,0,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) @@ -281,8 +281,8 @@ class ExudynTestGlobals: SC = exu.SystemContainer() mbs = SC.AddSystem() -b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], +b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) @@ -366,7 +366,7 @@ class ExudynTestGlobals: gravity = [0,-9.81,0], graphicsDataList = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], color=color4orange)]) -m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], +m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], physicsMass=1, drawSize = 0.2) n1 = mbs.GetObject(m1)['nodeNumber'] diff --git a/main/pythonDev/TestModels/reevingSystemSpringsTest.py b/main/pythonDev/TestModels/reevingSystemSpringsTest.py index 04717ca1..6d9a3fcc 100644 --- a/main/pythonDev/TestModels/reevingSystemSpringsTest.py +++ b/main/pythonDev/TestModels/reevingSystemSpringsTest.py @@ -89,7 +89,8 @@ class ExudynTestGlobals: if i != 0: Lref += NormL2(np.array(pos)-pLast) if i > 0 and i < len(posList)-1: - Lref += r*pi + #note that in this test example, Lref is slightly too long, leading to negative spring forces (compression) if not treated nonlinearly with default settings in ReevingSystemSprings + Lref += r*pi #0.8*r*pi would always lead to tension #mR = mbs.AddMarker(MarkerBodyRigid(bodyNumber=bR, localPosition=[0,-r,0])) #mbs.AddLoad(Force(markerNumber=mR, loadVector=[0,-inertiaRoll.mass*9.81,0])) @@ -122,9 +123,11 @@ class ExudynTestGlobals: stiffness = 1e5 #stiffness per length damping = 0.5*stiffness #dampiung per length oRS=mbs.AddObject(ReevingSystemSprings(markerNumbers=markerList, hasCoordinateMarkers=False, - stiffnessPerLength=stiffness, dampingPerLength=damping, referenceLength = Lref, + stiffnessPerLength=stiffness, dampingPerLength=damping, + referenceLength = Lref, dampingTorsional = 0.01*damping, dampingShear = 0.1*damping, sheavesAxes=sheavesAxes, sheavesRadii=sheavesRadii, + #regularizationForce = -1, #purely linear system visualization=VReevingSystemSprings(ropeRadius=0.05, color=color4dodgerblue))) #%%++++++++++++++++++++++++++++++++++++++++++++++++ @@ -138,6 +141,8 @@ class ExudynTestGlobals: outputVariableType=exu.OutputVariableType.Distance)) sLength_t= mbs.AddSensor(SensorObject(objectNumber=oRS, storeInternal=True, outputVariableType=exu.OutputVariableType.VelocityLocal)) + sForce= mbs.AddSensor(SensorObject(objectNumber=oRS, storeInternal=True, + outputVariableType=exu.OutputVariableType.ForceLocal)) #%%++++++++++++++++++++++++++++++++++++++++++++++++ #simulate: @@ -190,6 +195,7 @@ class ExudynTestGlobals: mbs.PlotSensor(sOmega1, components=[0,1,2], labels=['omega X','omega Y','omega Z']) mbs.PlotSensor(sLength, components=[0], labels=['length']) mbs.PlotSensor(sLength_t, components=[0], labels=['vel']) + mbs.PlotSensor(sForce, components=[0], labels=['force']) diff --git a/main/pythonDev/TestModels/runTestSuiteRefSol.py b/main/pythonDev/TestModels/runTestSuiteRefSol.py index 2b59e8ee..4eb993da 100644 --- a/main/pythonDev/TestModels/runTestSuiteRefSol.py +++ b/main/pythonDev/TestModels/runTestSuiteRefSol.py @@ -65,7 +65,7 @@ def TestExamplesReferenceSolution(): 'pendulumFriction.py':0.39999998776982304, 'plotSensorTest.py':1, 'postNewtonStepContactTest.py':0.057286638346409235, - 'reevingSystemSpringsTest.py':2.213190117855691, + 'reevingSystemSpringsTest.py':2.2155575717433007, #new 2023-07-17 (old solution contained compression forces: 2.213190117855691), 'revoluteJointprismaticJointTest.py':1.2538806799249342, #new 2022-07-11 (CState Parallel); #changed to some analytic Connector jacobians (CartSpringDamper), implicit solver (modified Newton restart, etc.); before 2022-01-18: 1.2538806799243265, 'rigidBodyAsUserFunctionTest.py':8.950865271552148, 'rigidBodyCOMtest.py':3.409431467726291, diff --git a/main/pythonDev/exudyn/FEM.py b/main/pythonDev/exudyn/FEM.py index cdaec041..a6de367b 100644 --- a/main/pythonDev/exudyn/FEM.py +++ b/main/pythonDev/exudyn/FEM.py @@ -20,8 +20,11 @@ StrNodeType2NodeType from exudyn.graphicsDataUtilities import ComputeTriangleArea + import numpy as np #LoadSolutionFile from enum import Enum #for class HCBstaticModeSelection +import os + #convert zero-based sparse matrix data to dense numpy matrix #DEPRECTAED!!!!!!!!!!!!!!!! @@ -1106,6 +1109,12 @@ def SaveToFile(self, fileName, fileVersion = 1 ): fileExtension = '' if len(fileName) < 4 or fileName[-4:]!='.npy': fileExtension = '.npy' + + try: + os.makedirs(os.path.dirname(fileName+fileExtension), exist_ok=True) + except: + pass #makedirs may fail on some systems, but we keep going + with open(fileName+fileExtension, 'wb') as f: np.save(f, np.array([int(fileVersion)])) #array allows to add more data in future @@ -1581,6 +1590,12 @@ def SaveToFile(self, fileName, fileVersion = 13 ): fileExtension = '' if len(fileName) < 4 or fileName[-4:]!='.npy': fileExtension = '.npy' + + try: + os.makedirs(os.path.dirname(fileName+fileExtension), exist_ok=True) + except: + pass #makedirs may fail on some systems, but we keep going + with open(fileName+fileExtension, 'wb') as f: if fileVersion>0: dataVersion = np.array([int(fileVersion)]) diff --git a/main/pythonDev/exudyn/GUI.py b/main/pythonDev/exudyn/GUI.py index a83b882d..f2b26ee2 100644 --- a/main/pythonDev/exudyn/GUI.py +++ b/main/pythonDev/exudyn/GUI.py @@ -217,7 +217,9 @@ def ConvertString2Value(value, vType, vSize, dictionaryTypesT): if str(iValue) == value: return [iValue, errorMsg] - if len(vSize) == 2 or (len(vSize)==1 and vSize[0] > 1): #must be matrix + if (len(vSize) == 2 or #must be matrix + (len(vSize)==1 and vSize[0] > 1) or #must be vector with fixed size + (len(vSize)==1 and vSize[0] == -1) ): #array / vector with undefined size return [ast.literal_eval(value), errorMsg] #print("Error in ConvertString2Value: unknown type",vType, "value=", value) diff --git a/main/pythonDev/exudyn/__init__.py b/main/pythonDev/exudyn/__init__.py index 070870e2..75222c59 100644 --- a/main/pythonDev/exudyn/__init__.py +++ b/main/pythonDev/exudyn/__init__.py @@ -141,7 +141,8 @@ def RequireVersion(requiredVersionString): isOk = False if not isOk: #print("EXUDYN version "+requiredVersionString+" required, but only " + GetVersionString() + " available") - raise RuntimeError("EXUDYN version "+requiredVersionString+" required, but only " + GetVersionString() + " available") + raise RuntimeError("EXUDYN version "+requiredVersionString+" required, but only " + GetVersionString() + + " available!\nYou can install the latest development version with:\npip install -U exudyn --pre\n\n") #do not import itemInterface here, as it would go into exu. scope diff --git a/main/pythonDev/exudyn/__init__.pyi b/main/pythonDev/exudyn/__init__.pyi index 37b1e4ec..fd409f0c 100644 --- a/main/pythonDev/exudyn/__init__.pyi +++ b/main/pythonDev/exudyn/__init__.pyi @@ -585,7 +585,28 @@ class VSettingsLoads: showNumbers: bool +class VSettingsSensorTraces: + lineWidth: float + listOfPositionSensors: ArrayIndex + listOfTriadSensors: ArrayIndex + listOfVectorSensors: ArrayIndex + positionsShowEvery: int + sensorsMbsNumber: int + showCurrent: bool + showFuture: bool + showPast: bool + showPositionTrace: bool + showTriads: bool + showVectors: bool + traceColors: ArrayFloat + triadSize: float + triadsShowEvery: int + vectorScaling: float + vectorsShowEvery: int + + class VSettingsSensors: + traces: VSettingsSensorTraces defaultColor: Tuple[float,float,float,float] defaultSize: float drawSimplified: bool @@ -1449,7 +1470,7 @@ class MainSystem: def SolutionViewer(self, solution=None, rowIncrement=1, timeout=0.04, runOnStart=True, runMode=2, fontSize=12, title='', checkRenderEngineStopFlag=True) -> None: ... @overload - def CreateMassPoint(self, name='', referenceCoordinates=[0.,0.,0.], initialCoordinates=[0.,0.,0.], initialVelocities=[0.,0.,0.], physicsMass=0, gravity=[0.,0.,0.], graphicsDataList=[], drawSize=-1, color=[-1.,-1.,-1.,-1.], show=True, create2D=False, returnDict=False) -> Union[dict, ObjectIndex]: ... + def CreateMassPoint(self, 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) -> Union[dict, ObjectIndex]: ... @overload def CreateRigidBody(self, 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=[], drawSize=-1, color=[-1.,-1.,-1.,-1.], show=True, create2D=False, returnDict=False) -> Union[dict, ObjectIndex]: ... diff --git a/main/pythonDev/exudyn/basicUtilities.py b/main/pythonDev/exudyn/basicUtilities.py index 04bfb63d..5613bd9f 100644 --- a/main/pythonDev/exudyn/basicUtilities.py +++ b/main/pythonDev/exudyn/basicUtilities.py @@ -80,6 +80,15 @@ def ClearWorkspace(): import matplotlib.pyplot as plt plt.close('all') +#**function: round to max number of digits; may give more digits if this is shorter; using in general the format() with '.g' option, but keeping decimal point and using exponent where necessary +def SmartRound2String(x, prec=3): + s = ("{:.0"+str(prec)+"g}").format(x) + if abs(x) > 1 and x != int(x) and '.' not in s and 'e' not in s: + s = s+'.' + if x == int(x) and len(s) > len(str(x)): + s = str(x) + return s + #**function: create a diagonal or identity matrix; used for interface.py, avoiding the need for numpy diff --git a/main/pythonDev/exudyn/interactive.py b/main/pythonDev/exudyn/interactive.py index b8c4000b..2d2e78fc 100644 --- a/main/pythonDev/exudyn/interactive.py +++ b/main/pythonDev/exudyn/interactive.py @@ -856,32 +856,21 @@ def UFviewer(mbs, dialog): # mbs.systemData.SetTime(t, exudyn.ConfigurationType.Visualization) SetSolutionState(mainSystem, mbs.sys['solutionViewerSolution'], i, exudyn.ConfigurationType.Visualization) - #exudyn.DoRendererIdleTasks(timeout) - # SC.visualizationSettings.contour.reduceRange = False mbs.SendRedrawSignal() - exudyn.DoRendererIdleTasks() #as there is no simulation, we must do this for graphicsDataUserFunctions - # if mbs.sys['modeShapeSaveImages'] == 0: - # SC.RedrawAndSaveImage() #create images for animation - # else: - # SC.visualizationSettings.exportImages.saveImageFileCounter = 0 #for next mode ... + exudyn.DoRendererIdleTasks() #as there is no simulation, we must do this for singlethreaded renderer to draw graphicsDataUserFunctions dialog.period = mbs.sys['solutionViewerPeriod'] if mbs.sys['solutionViewerRunModus'] < 2: mbs.sys['solutionViewerStep'] += mbs.sys['solutionViewerRowIncrement'] - # print("step=", mbs.sys['solutionViewerStep']) #first variable is scale, which contains step dialog.variableList[0][0].set(mbs.sys['solutionViewerStep']) - # for var in dialog.variableList: - # #self.mbs.sys[var[1]] = var[0].get() - # print(var[1],'=', var[0].get()) if mbs.sys['solutionViewerSaveImages'] == 0: + #in single-threaded renderer, this causes 2x redraw, so we could save the above exudyn.DoRendererIdleTasks() then ...! SC.RedrawAndSaveImage() #create images for animation - # else: #do not reset image counter to allow creating of multi-view images, slow motion, etc. - # SC.visualizationSettings.exportImages.saveImageFileCounter = 0 # if mbs.sys['solutionViewerStep']>mbs.sys['solutionViewerNSteps']-1.: #or (mbs.sys['solutionViewerRunModus'] and mbs.sys['solutionViewerStep']==mbs.sys['solutionViewerNSteps']-1.): diff --git a/main/pythonDev/exudyn/itemInterface.py b/main/pythonDev/exudyn/itemInterface.py index 6092188b..087d5ede 100644 --- a/main/pythonDev/exudyn/itemInterface.py +++ b/main/pythonDev/exudyn/itemInterface.py @@ -6,7 +6,20 @@ #item interface diagonal matrix creator import exudyn #for exudyn.InvalidIndex() and other exudyn native structures needed in RigidBodySpringDamper - +import numpy as np +import copy + +#helper function for level-1 copy of dicts (for visualization default args!) +#visualization dictionaries (which may be huge, are only flat copied, which is sufficient) +def CopyDictLevel1(originalDict): + if isinstance(originalDict,dict): #copy only required if default dict is used + copyDict = {} + for key, value in originalDict.items(): + copyDict[key] = copy.copy(value) + return copyDict + else: + return originalDict #fast track for everything else + #helper function diagonal matrices, not needing numpy def IIDiagMatrix(rowsColumns, value): m = [] @@ -47,7 +60,7 @@ class VNodePoint: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -59,10 +72,10 @@ def __repr__(self): class NodePoint: def __init__(self, name = '', referenceCoordinates = [0.,0.,0.], initialCoordinates = [0.,0.,0.], initialVelocities = [0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'Point' @@ -84,7 +97,7 @@ class VNodePoint2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -96,10 +109,10 @@ def __repr__(self): class NodePoint2D: def __init__(self, name = '', referenceCoordinates = [0.,0.], initialCoordinates = [0.,0.], initialVelocities = [0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'Point2D' @@ -121,7 +134,7 @@ class VNodeRigidBodyEP: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -133,11 +146,11 @@ def __repr__(self): class NodeRigidBodyEP: def __init__(self, name = '', referenceCoordinates = [0.,0.,0., 0.,0.,0.,0.], initialCoordinates = [0.,0.,0., 0.,0.,0.,0.], initialVelocities = [0.,0.,0., 0.,0.,0.,0.], addConstraintEquation = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) self.addConstraintEquation = addConstraintEquation - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'RigidBodyEP' @@ -160,7 +173,7 @@ class VNodeRigidBodyRxyz: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -172,10 +185,10 @@ def __repr__(self): class NodeRigidBodyRxyz: def __init__(self, name = '', referenceCoordinates = [0.,0.,0., 0.,0.,0.], initialCoordinates = [0.,0.,0., 0.,0.,0.], initialVelocities = [0.,0.,0., 0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'RigidBodyRxyz' @@ -197,7 +210,7 @@ class VNodeRigidBodyRotVecLG: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -209,10 +222,10 @@ def __repr__(self): class NodeRigidBodyRotVecLG: def __init__(self, name = '', referenceCoordinates = [0.,0.,0., 0.,0.,0.], initialCoordinates = [0.,0.,0., 0.,0.,0.], initialVelocities = [0.,0.,0., 0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'RigidBodyRotVecLG' @@ -234,7 +247,7 @@ class VNodeRigidBodyRotVecDataLG: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -246,10 +259,10 @@ def __repr__(self): class NodeRigidBodyRotVecDataLG: def __init__(self, name = '', referenceCoordinates = [0.,0.,0., 0.,0.,0.], initialCoordinates = [0.,0.,0., 0.,0.,0.], initialVelocities = [0.,0.,0., 0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'RigidBodyRotVecDataLG' @@ -271,7 +284,7 @@ class VNodeRigidBody2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -283,10 +296,10 @@ def __repr__(self): class NodeRigidBody2D: def __init__(self, name = '', referenceCoordinates = [0.,0.,0.], initialCoordinates = [0.,0.,0.], initialVelocities = [0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'RigidBody2D' @@ -316,10 +329,10 @@ def __repr__(self): class Node1D: def __init__(self, name = '', referenceCoordinates = [0.], initialCoordinates = [0.], initialVelocities = [0.], visualization = {'show': False}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', '1D' @@ -335,7 +348,7 @@ class VNodePoint2DSlope1: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -347,10 +360,10 @@ def __repr__(self): class NodePoint2DSlope1: def __init__(self, name = '', referenceCoordinates = [0.,0.,1.,0.], initialCoordinates = [0.,0.,0.,0.], initialVelocities = [0.,0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'Point2DSlope1' @@ -372,7 +385,7 @@ class VNodePoint3DSlope1: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -384,10 +397,10 @@ def __repr__(self): class NodePoint3DSlope1: def __init__(self, name = '', referenceCoordinates = [0.,0.,0.,1.,0.,0.], initialCoordinates = [0.,0.,0.,0.,0.,0.], initialVelocities = [0.,0.,0.,0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'Point3DSlope1' @@ -409,7 +422,7 @@ class VNodePoint3DSlope23: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -421,10 +434,10 @@ def __repr__(self): class NodePoint3DSlope23: def __init__(self, name = '', referenceCoordinates = [0.,0.,0.,1.,0.,0.,1.,0.,0.], initialCoordinates = [0.,0.,0.,0.,0.,0.,0.,0.,0.], initialVelocities = [0.,0.,0.,0.,0.,0.,0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialVelocities = initialVelocities - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialVelocities = np.array(initialVelocities) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'Point3DSlope23' @@ -454,11 +467,11 @@ def __repr__(self): class NodeGenericODE2: def __init__(self, name = '', referenceCoordinates = [], initialCoordinates = [], initialCoordinates_t = [], numberOfODE2Coordinates = 0, visualization = {'show': False}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates - self.initialCoordinates_t = initialCoordinates_t + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) + self.initialCoordinates_t = np.array(initialCoordinates_t) self.numberOfODE2Coordinates = CheckForValidPInt(numberOfODE2Coordinates,"numberOfODE2Coordinates","NodeGenericODE2") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'GenericODE2' @@ -483,10 +496,10 @@ def __repr__(self): class NodeGenericODE1: def __init__(self, name = '', referenceCoordinates = [], initialCoordinates = [], numberOfODE1Coordinates = 0, visualization = {'show': False}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) self.numberOfODE1Coordinates = CheckForValidPInt(numberOfODE1Coordinates,"numberOfODE1Coordinates","NodeGenericODE1") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'GenericODE1' @@ -510,10 +523,10 @@ def __repr__(self): class NodeGenericAE: def __init__(self, name = '', referenceCoordinates = [], initialCoordinates = [], numberOfAECoordinates = 0, visualization = {'show': False}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.initialCoordinates = initialCoordinates + self.referenceCoordinates = np.array(referenceCoordinates) + self.initialCoordinates = np.array(initialCoordinates) self.numberOfAECoordinates = CheckForValidPInt(numberOfAECoordinates,"numberOfAECoordinates","NodeGenericAE") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'GenericAE' @@ -537,9 +550,9 @@ def __repr__(self): class NodeGenericData: def __init__(self, name = '', initialCoordinates = [], numberOfDataCoordinates = 0, visualization = {'show': False}): self.name = name - self.initialCoordinates = initialCoordinates + self.initialCoordinates = np.array(initialCoordinates) self.numberOfDataCoordinates = CheckForValidUInt(numberOfDataCoordinates,"numberOfDataCoordinates","NodeGenericData") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'GenericData' @@ -554,7 +567,7 @@ class VNodePointGround: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -566,8 +579,8 @@ def __repr__(self): class NodePointGround: def __init__(self, name = '', referenceCoordinates = [0.,0.,0.], visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.referenceCoordinates = referenceCoordinates - self.visualization = visualization + self.referenceCoordinates = np.array(referenceCoordinates) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'nodeType', 'PointGround' @@ -589,8 +602,8 @@ class VObjectGround: def __init__(self, show = True, graphicsDataUserFunction = 0, color = [-1.,-1.,-1.,-1.], graphicsData = []): self.show = show self.graphicsDataUserFunction = graphicsDataUserFunction - self.color = color - self.graphicsData = graphicsData + self.color = np.array(color) + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -603,9 +616,9 @@ def __repr__(self): class ObjectGround: def __init__(self, name = '', referencePosition = [0.,0.,0.], referenceRotation = IIDiagMatrix(rowsColumns=3,value=1), visualization = {'show': True, 'graphicsDataUserFunction': 0, 'color': [-1.,-1.,-1.,-1.], 'graphicsData': []}): self.name = name - self.referencePosition = referencePosition - self.referenceRotation = referenceRotation - self.visualization = visualization + self.referencePosition = np.array(referencePosition) + self.referenceRotation = np.array(referenceRotation) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'Ground' @@ -622,7 +635,7 @@ def __repr__(self): class VObjectMassPoint: def __init__(self, show = True, graphicsData = []): self.show = show - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -635,7 +648,7 @@ def __init__(self, name = '', physicsMass = 0., nodeNumber = exudyn.InvalidIndex self.name = name self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectMassPoint") self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'MassPoint' @@ -654,7 +667,7 @@ def __repr__(self): class VObjectMassPoint2D: def __init__(self, show = True, graphicsData = []): self.show = show - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -667,7 +680,7 @@ def __init__(self, name = '', physicsMass = 0., nodeNumber = exudyn.InvalidIndex self.name = name self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectMassPoint2D") self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'MassPoint2D' @@ -686,7 +699,7 @@ def __repr__(self): class VObjectMass1D: def __init__(self, show = True, graphicsData = []): self.show = show - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -699,9 +712,9 @@ def __init__(self, name = '', physicsMass = 0., nodeNumber = exudyn.InvalidIndex self.name = name self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectMass1D") self.nodeNumber = nodeNumber - self.referencePosition = referencePosition - self.referenceRotation = referenceRotation - self.visualization = visualization + self.referencePosition = np.array(referencePosition) + self.referenceRotation = np.array(referenceRotation) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'Mass1D' @@ -722,7 +735,7 @@ def __repr__(self): class VObjectRotationalMass1D: def __init__(self, show = True, graphicsData = []): self.show = show - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -735,9 +748,9 @@ def __init__(self, name = '', physicsInertia = 0., nodeNumber = exudyn.InvalidIn self.name = name self.physicsInertia = CheckForValidUReal(physicsInertia,"physicsInertia","ObjectRotationalMass1D") self.nodeNumber = nodeNumber - self.referencePosition = referencePosition - self.referenceRotation = referenceRotation - self.visualization = visualization + self.referencePosition = np.array(referencePosition) + self.referenceRotation = np.array(referenceRotation) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'RotationalMass1D' @@ -759,7 +772,7 @@ class VObjectRigidBody: def __init__(self, show = True, graphicsDataUserFunction = 0, graphicsData = []): self.show = show self.graphicsDataUserFunction = graphicsDataUserFunction - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -772,10 +785,10 @@ class ObjectRigidBody: def __init__(self, name = '', physicsMass = 0., physicsInertia = [0.,0.,0., 0.,0.,0.], physicsCenterOfMass = [0.,0.,0.], nodeNumber = exudyn.InvalidIndex(), visualization = {'show': True, 'graphicsDataUserFunction': 0, 'graphicsData': []}): self.name = name self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectRigidBody") - self.physicsInertia = physicsInertia - self.physicsCenterOfMass = physicsCenterOfMass + self.physicsInertia = np.array(physicsInertia) + self.physicsCenterOfMass = np.array(physicsCenterOfMass) self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'RigidBody' @@ -798,7 +811,7 @@ class VObjectRigidBody2D: def __init__(self, show = True, graphicsDataUserFunction = 0, graphicsData = []): self.show = show self.graphicsDataUserFunction = graphicsDataUserFunction - self.graphicsData = graphicsData + self.graphicsData = copy.copy(graphicsData) def __iter__(self): yield 'show', self.show @@ -813,7 +826,7 @@ def __init__(self, name = '', physicsMass = 0., physicsInertia = 0., nodeNumber self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectRigidBody2D") self.physicsInertia = CheckForValidUReal(physicsInertia,"physicsInertia","ObjectRigidBody2D") self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'RigidBody2D' @@ -834,8 +847,8 @@ def __repr__(self): class VObjectGenericODE2: def __init__(self, show = True, color = [-1.,-1.,-1.,-1.], triangleMesh = [], showNodes = False, graphicsDataUserFunction = 0): self.show = show - self.color = color - self.triangleMesh = triangleMesh + self.color = np.array(color) + self.triangleMesh = np.array(triangleMesh) self.showNodes = showNodes self.graphicsDataUserFunction = graphicsDataUserFunction @@ -849,17 +862,17 @@ def __iter__(self): def __repr__(self): return str(dict(self)) class ObjectGenericODE2: - def __init__(self, name = '', nodeNumbers = [], massMatrix = [], stiffnessMatrix = [], dampingMatrix = [], forceVector = [], forceUserFunction = 0, massMatrixUserFunction = 0, jacobianUserFunction = 0, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False, 'graphicsDataUserFunction': 0}): + def __init__(self, name = '', nodeNumbers = [], massMatrix = None, stiffnessMatrix = None, dampingMatrix = None, forceVector = [], forceUserFunction = 0, massMatrixUserFunction = 0, jacobianUserFunction = 0, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False, 'graphicsDataUserFunction': 0}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.massMatrix = massMatrix self.stiffnessMatrix = stiffnessMatrix self.dampingMatrix = dampingMatrix - self.forceVector = forceVector + self.forceVector = np.array(forceVector) self.forceUserFunction = forceUserFunction self.massMatrixUserFunction = massMatrixUserFunction self.jacobianUserFunction = jacobianUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'GenericODE2' @@ -892,11 +905,11 @@ def __repr__(self): class ObjectGenericODE1: def __init__(self, name = '', nodeNumbers = [], systemMatrix = [], rhsVector = [], rhsUserFunction = 0, visualization = {'show': True}): self.name = name - self.nodeNumbers = nodeNumbers - self.systemMatrix = systemMatrix - self.rhsVector = rhsVector + self.nodeNumbers = copy.copy(nodeNumbers) + self.systemMatrix = np.array(systemMatrix) + self.rhsVector = np.array(rhsVector) self.rhsUserFunction = rhsUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'GenericODE1' @@ -914,8 +927,8 @@ def __init__(self, show = True, showLinks = True, showJoints = True, color = [-1 self.show = show self.showLinks = showLinks self.showJoints = showJoints - self.color = color - self.graphicsDataList = graphicsDataList + self.color = np.array(color) + self.graphicsDataList = copy.copy(graphicsDataList) def __iter__(self): yield 'show', self.show @@ -927,27 +940,27 @@ def __iter__(self): def __repr__(self): return str(dict(self)) class ObjectKinematicTree: - def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), gravity = [0.,0.,0.], baseOffset = [0.,0.,0.], jointTypes = [], linkParents = [], jointTransformations = [], jointOffsets = [], linkInertiasCOM = [], linkCOMs = [], linkMasses = [], linkForces = [], linkTorques = [], jointForceVector = [], jointPositionOffsetVector = [], jointVelocityOffsetVector = [], jointPControlVector = [], jointDControlVector = [], forceUserFunction = 0, visualization = {'show': True, 'showLinks': True, 'showJoints': True, 'color': [-1.,-1.,-1.,-1.], 'graphicsDataList': []}): + def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), gravity = [0.,0.,0.], baseOffset = [0.,0.,0.], jointTypes = [], linkParents = [], jointTransformations = None, jointOffsets = None, linkInertiasCOM = None, linkCOMs = None, linkMasses = [], linkForces = None, linkTorques = None, jointForceVector = [], jointPositionOffsetVector = [], jointVelocityOffsetVector = [], jointPControlVector = [], jointDControlVector = [], forceUserFunction = 0, visualization = {'show': True, 'showLinks': True, 'showJoints': True, 'color': [-1.,-1.,-1.,-1.], 'graphicsDataList': []}): self.name = name self.nodeNumber = nodeNumber - self.gravity = gravity - self.baseOffset = baseOffset - self.jointTypes = jointTypes - self.linkParents = linkParents + self.gravity = np.array(gravity) + self.baseOffset = np.array(baseOffset) + self.jointTypes = copy.copy(jointTypes) + self.linkParents = copy.copy(linkParents) self.jointTransformations = jointTransformations self.jointOffsets = jointOffsets self.linkInertiasCOM = linkInertiasCOM self.linkCOMs = linkCOMs - self.linkMasses = linkMasses + self.linkMasses = np.array(linkMasses) self.linkForces = linkForces self.linkTorques = linkTorques - self.jointForceVector = jointForceVector - self.jointPositionOffsetVector = jointPositionOffsetVector - self.jointVelocityOffsetVector = jointVelocityOffsetVector - self.jointPControlVector = jointPControlVector - self.jointDControlVector = jointDControlVector + self.jointForceVector = np.array(jointForceVector) + self.jointPositionOffsetVector = np.array(jointPositionOffsetVector) + self.jointVelocityOffsetVector = np.array(jointVelocityOffsetVector) + self.jointPControlVector = np.array(jointPControlVector) + self.jointDControlVector = np.array(jointDControlVector) self.forceUserFunction = forceUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'KinematicTree' @@ -985,8 +998,8 @@ def __repr__(self): class VObjectFFRF: def __init__(self, show = True, color = [-1.,-1.,-1.,-1.], triangleMesh = [], showNodes = False): self.show = show - self.color = color - self.triangleMesh = triangleMesh + self.color = np.array(color) + self.triangleMesh = np.array(triangleMesh) self.showNodes = showNodes def __iter__(self): @@ -998,18 +1011,18 @@ def __iter__(self): def __repr__(self): return str(dict(self)) class ObjectFFRF: - def __init__(self, name = '', nodeNumbers = [], massMatrixFF = [], stiffnessMatrixFF = [], dampingMatrixFF = [], forceVector = [], forceUserFunction = 0, massMatrixUserFunction = 0, computeFFRFterms = True, objectIsInitialized = False, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False}): + def __init__(self, name = '', nodeNumbers = [], massMatrixFF = None, stiffnessMatrixFF = None, dampingMatrixFF = None, forceVector = [], forceUserFunction = 0, massMatrixUserFunction = 0, computeFFRFterms = True, objectIsInitialized = False, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.massMatrixFF = massMatrixFF self.stiffnessMatrixFF = stiffnessMatrixFF self.dampingMatrixFF = dampingMatrixFF - self.forceVector = forceVector + self.forceVector = np.array(forceVector) self.forceUserFunction = forceUserFunction self.massMatrixUserFunction = massMatrixUserFunction self.computeFFRFterms = computeFFRFterms self.objectIsInitialized = objectIsInitialized - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'FFRF' @@ -1033,8 +1046,8 @@ def __repr__(self): class VObjectFFRFreducedOrder: def __init__(self, show = True, color = [-1.,-1.,-1.,-1.], triangleMesh = [], showNodes = False): self.show = show - self.color = color - self.triangleMesh = triangleMesh + self.color = np.array(color) + self.triangleMesh = np.array(triangleMesh) self.showNodes = showNodes def __iter__(self): @@ -1046,31 +1059,31 @@ def __iter__(self): def __repr__(self): return str(dict(self)) class ObjectFFRFreducedOrder: - def __init__(self, name = '', nodeNumbers = [], massMatrixReduced = [], stiffnessMatrixReduced = [], dampingMatrixReduced = [], forceUserFunction = 0, massMatrixUserFunction = 0, computeFFRFterms = True, modeBasis = [], outputVariableModeBasis = [], outputVariableTypeModeBasis = 0, referencePositions = [], objectIsInitialized = False, physicsMass = 0., physicsInertia = IIDiagMatrix(rowsColumns=3,value=1), physicsCenterOfMass = [0.,0.,0.], mPsiTildePsi = [], mPsiTildePsiTilde = [], mPhitTPsi = [], mPhitTPsiTilde = [], mXRefTildePsi = [], mXRefTildePsiTilde = [], physicsCenterOfMassTilde = IIDiagMatrix(rowsColumns=3,value=0), visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False}): + def __init__(self, name = '', nodeNumbers = [], massMatrixReduced = None, stiffnessMatrixReduced = None, dampingMatrixReduced = None, forceUserFunction = 0, massMatrixUserFunction = 0, computeFFRFterms = True, modeBasis = [], outputVariableModeBasis = [], outputVariableTypeModeBasis = 0, referencePositions = [], objectIsInitialized = False, physicsMass = 0., physicsInertia = IIDiagMatrix(rowsColumns=3,value=1), physicsCenterOfMass = [0.,0.,0.], mPsiTildePsi = [], mPsiTildePsiTilde = [], mPhitTPsi = [], mPhitTPsiTilde = [], mXRefTildePsi = [], mXRefTildePsiTilde = [], physicsCenterOfMassTilde = IIDiagMatrix(rowsColumns=3,value=0), visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.], 'triangleMesh': [], 'showNodes': False}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.massMatrixReduced = massMatrixReduced self.stiffnessMatrixReduced = stiffnessMatrixReduced self.dampingMatrixReduced = dampingMatrixReduced self.forceUserFunction = forceUserFunction self.massMatrixUserFunction = massMatrixUserFunction self.computeFFRFterms = computeFFRFterms - self.modeBasis = modeBasis - self.outputVariableModeBasis = outputVariableModeBasis + self.modeBasis = np.array(modeBasis) + self.outputVariableModeBasis = np.array(outputVariableModeBasis) self.outputVariableTypeModeBasis = outputVariableTypeModeBasis - self.referencePositions = referencePositions + self.referencePositions = np.array(referencePositions) self.objectIsInitialized = objectIsInitialized self.physicsMass = CheckForValidUReal(physicsMass,"physicsMass","ObjectFFRFreducedOrder") - self.physicsInertia = physicsInertia - self.physicsCenterOfMass = physicsCenterOfMass - self.mPsiTildePsi = mPsiTildePsi - self.mPsiTildePsiTilde = mPsiTildePsiTilde - self.mPhitTPsi = mPhitTPsi - self.mPhitTPsiTilde = mPhitTPsiTilde - self.mXRefTildePsi = mXRefTildePsi - self.mXRefTildePsiTilde = mXRefTildePsiTilde - self.physicsCenterOfMassTilde = physicsCenterOfMassTilde - self.visualization = visualization + self.physicsInertia = np.array(physicsInertia) + self.physicsCenterOfMass = np.array(physicsCenterOfMass) + self.mPsiTildePsi = np.array(mPsiTildePsi) + self.mPsiTildePsiTilde = np.array(mPsiTildePsiTilde) + self.mPhitTPsi = np.array(mPhitTPsi) + self.mPhitTPsiTilde = np.array(mPhitTPsiTilde) + self.mXRefTildePsi = np.array(mXRefTildePsi) + self.mXRefTildePsiTilde = np.array(mXRefTildePsiTilde) + self.physicsCenterOfMassTilde = np.array(physicsCenterOfMassTilde) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'FFRFreducedOrder' @@ -1112,7 +1125,7 @@ class VObjectANCFCable2D: def __init__(self, show = True, drawHeight = 0., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawHeight = drawHeight - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1133,9 +1146,9 @@ def __init__(self, name = '', physicsLength = 0., physicsMassPerLength = 0., phy self.physicsReferenceAxialStrain = physicsReferenceAxialStrain self.physicsReferenceCurvature = physicsReferenceCurvature self.strainIsRelativeToReference = strainIsRelativeToReference - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.useReducedOrderIntegration = useReducedOrderIntegration - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ANCFCable2D' @@ -1165,7 +1178,7 @@ class VObjectALEANCFCable2D: def __init__(self, show = True, drawHeight = 0., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawHeight = drawHeight - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1188,10 +1201,10 @@ def __init__(self, name = '', physicsLength = 0., physicsMassPerLength = 0., phy self.physicsReferenceCurvature = physicsReferenceCurvature self.physicsUseCouplingTerms = physicsUseCouplingTerms self.physicsAddALEvariation = physicsAddALEvariation - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.useReducedOrderIntegration = useReducedOrderIntegration self.strainIsRelativeToReference = strainIsRelativeToReference - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ALEANCFCable2D' @@ -1224,7 +1237,7 @@ class VObjectANCFBeam: def __init__(self, show = True, sectionGeometry = exudyn.BeamSectionGeometry(), color = [-1.,-1.,-1.,-1.]): self.show = show self.sectionGeometry = sectionGeometry - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1236,11 +1249,11 @@ def __repr__(self): class ObjectANCFBeam: def __init__(self, name = '', nodeNumbers = [exudyn.InvalidIndex(), exudyn.InvalidIndex()], physicsLength = 0., sectionData = exudyn.BeamSection(), crossSectionPenaltyFactor = [1.,1.,1.], visualization = {'show': True, 'sectionGeometry': exudyn.BeamSectionGeometry(), 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.physicsLength = CheckForValidPReal(physicsLength,"physicsLength","ObjectANCFBeam") self.sectionData = sectionData - self.crossSectionPenaltyFactor = crossSectionPenaltyFactor - self.visualization = visualization + self.crossSectionPenaltyFactor = np.array(crossSectionPenaltyFactor) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ANCFBeam' @@ -1263,7 +1276,7 @@ class VObjectBeamGeometricallyExact2D: def __init__(self, show = True, drawHeight = 0., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawHeight = drawHeight - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1275,7 +1288,7 @@ def __repr__(self): class ObjectBeamGeometricallyExact2D: def __init__(self, name = '', nodeNumbers = [exudyn.InvalidIndex(), exudyn.InvalidIndex()], physicsLength = 0., physicsMassPerLength = 0., physicsCrossSectionInertia = 0., physicsBendingStiffness = 0., physicsAxialStiffness = 0., physicsShearStiffness = 0., physicsBendingDamping = 0., physicsAxialDamping = 0., physicsShearDamping = 0., physicsReferenceCurvature = 0., includeReferenceRotations = False, visualization = {'show': True, 'drawHeight': 0., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.physicsLength = CheckForValidUReal(physicsLength,"physicsLength","ObjectBeamGeometricallyExact2D") self.physicsMassPerLength = CheckForValidUReal(physicsMassPerLength,"physicsMassPerLength","ObjectBeamGeometricallyExact2D") self.physicsCrossSectionInertia = CheckForValidUReal(physicsCrossSectionInertia,"physicsCrossSectionInertia","ObjectBeamGeometricallyExact2D") @@ -1287,7 +1300,7 @@ def __init__(self, name = '', nodeNumbers = [exudyn.InvalidIndex(), exudyn.Inval self.physicsShearDamping = CheckForValidUReal(physicsShearDamping,"physicsShearDamping","ObjectBeamGeometricallyExact2D") self.physicsReferenceCurvature = physicsReferenceCurvature self.includeReferenceRotations = includeReferenceRotations - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'BeamGeometricallyExact2D' @@ -1318,7 +1331,7 @@ class VObjectBeamGeometricallyExact: def __init__(self, show = True, sectionGeometry = exudyn.BeamSectionGeometry(), color = [-1.,-1.,-1.,-1.]): self.show = show self.sectionGeometry = sectionGeometry - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1330,10 +1343,10 @@ def __repr__(self): class ObjectBeamGeometricallyExact: def __init__(self, name = '', nodeNumbers = [exudyn.InvalidIndex(), exudyn.InvalidIndex()], physicsLength = 0., sectionData = exudyn.BeamSection(), visualization = {'show': True, 'sectionGeometry': exudyn.BeamSectionGeometry(), 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.physicsLength = CheckForValidPReal(physicsLength,"physicsLength","ObjectBeamGeometricallyExact") self.sectionData = sectionData - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'BeamGeometricallyExact' @@ -1355,7 +1368,7 @@ class VObjectConnectorSpringDamper: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1367,7 +1380,7 @@ def __repr__(self): class ObjectConnectorSpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], referenceLength = 0., stiffness = 0., damping = 0., force = 0., velocityOffset = 0., activeConnector = True, springForceUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.referenceLength = CheckForValidPReal(referenceLength,"referenceLength","ObjectConnectorSpringDamper") self.stiffness = CheckForValidUReal(stiffness,"stiffness","ObjectConnectorSpringDamper") self.damping = CheckForValidUReal(damping,"damping","ObjectConnectorSpringDamper") @@ -1375,7 +1388,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.velocityOffset = velocityOffset self.activeConnector = activeConnector self.springForceUserFunction = springForceUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorSpringDamper' @@ -1402,7 +1415,7 @@ class VObjectConnectorCartesianSpringDamper: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1414,13 +1427,13 @@ def __repr__(self): class ObjectConnectorCartesianSpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], stiffness = [0.,0.,0.], damping = [0.,0.,0.], offset = [0.,0.,0.], springForceUserFunction = 0, activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.stiffness = stiffness - self.damping = damping - self.offset = offset + self.markerNumbers = copy.copy(markerNumbers) + self.stiffness = np.array(stiffness) + self.damping = np.array(damping) + self.offset = np.array(offset) self.springForceUserFunction = springForceUserFunction self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorCartesianSpringDamper' @@ -1445,7 +1458,7 @@ class VObjectConnectorRigidBodySpringDamper: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1457,17 +1470,17 @@ def __repr__(self): class ObjectConnectorRigidBodySpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), stiffness = IIDiagMatrix(rowsColumns=6,value=0.), damping = IIDiagMatrix(rowsColumns=6,value=0.), rotationMarker0 = IIDiagMatrix(rowsColumns=3,value=1), rotationMarker1 = IIDiagMatrix(rowsColumns=3,value=1), offset = [0.,0.,0.,0.,0.,0.], activeConnector = True, springForceTorqueUserFunction = 0, postNewtonStepUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber - self.stiffness = stiffness - self.damping = damping - self.rotationMarker0 = rotationMarker0 - self.rotationMarker1 = rotationMarker1 - self.offset = offset + self.stiffness = np.array(stiffness) + self.damping = np.array(damping) + self.rotationMarker0 = np.array(rotationMarker0) + self.rotationMarker1 = np.array(rotationMarker1) + self.offset = np.array(offset) self.activeConnector = activeConnector self.springForceTorqueUserFunction = springForceTorqueUserFunction self.postNewtonStepUserFunction = postNewtonStepUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorRigidBodySpringDamper' @@ -1497,7 +1510,7 @@ def __init__(self, show = True, drawSize = -1., drawAsCylinder = False, color = self.show = show self.drawSize = drawSize self.drawAsCylinder = drawAsCylinder - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1510,16 +1523,16 @@ def __repr__(self): class ObjectConnectorLinearSpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], stiffness = 0., damping = 0., axisMarker0 = [1,0,0], offset = 0., velocityOffset = 0., force = 0., activeConnector = True, springForceUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'drawAsCylinder': False, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.stiffness = stiffness self.damping = damping - self.axisMarker0 = axisMarker0 + self.axisMarker0 = np.array(axisMarker0) self.offset = offset self.velocityOffset = velocityOffset self.force = force self.activeConnector = activeConnector self.springForceUserFunction = springForceUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorLinearSpringDamper' @@ -1548,7 +1561,7 @@ class VObjectConnectorTorsionalSpringDamper: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1560,18 +1573,18 @@ def __repr__(self): class ObjectConnectorTorsionalSpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), stiffness = 0., damping = 0., rotationMarker0 = IIDiagMatrix(rowsColumns=3,value=1), rotationMarker1 = IIDiagMatrix(rowsColumns=3,value=1), offset = 0., velocityOffset = 0., torque = 0., activeConnector = True, springTorqueUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.stiffness = stiffness self.damping = damping - self.rotationMarker0 = rotationMarker0 - self.rotationMarker1 = rotationMarker1 + self.rotationMarker0 = np.array(rotationMarker0) + self.rotationMarker1 = np.array(rotationMarker1) self.offset = offset self.velocityOffset = velocityOffset self.torque = torque self.activeConnector = activeConnector self.springTorqueUserFunction = springTorqueUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorTorsionalSpringDamper' @@ -1601,7 +1614,7 @@ class VObjectConnectorCoordinateSpringDamper: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1613,13 +1626,13 @@ def __repr__(self): class ObjectConnectorCoordinateSpringDamper: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], stiffness = 0., damping = 0., offset = 0., activeConnector = True, springForceUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.stiffness = stiffness self.damping = damping self.offset = offset self.activeConnector = activeConnector self.springForceUserFunction = springForceUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorCoordinateSpringDamper' @@ -1644,7 +1657,7 @@ class VObjectConnectorCoordinateSpringDamperExt: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1656,7 +1669,7 @@ def __repr__(self): class ObjectConnectorCoordinateSpringDamperExt: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), stiffness = 0., damping = 0., offset = 0., velocityOffset = 0., factor0 = 1., factor1 = 1., fDynamicFriction = 0., fStaticFrictionOffset = 0., stickingStiffness = 0., stickingDamping = 0., exponentialDecayStatic = 1.e-3, fViscousFriction = 0., frictionProportionalZone = 0., limitStopsUpper = 0., limitStopsLower = 0., limitStopsStiffness = 0., limitStopsDamping = 0., useLimitStops = False, activeConnector = True, springForceUserFunction = 0, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.stiffness = stiffness self.damping = damping @@ -1678,7 +1691,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.useLimitStops = useLimitStops self.activeConnector = activeConnector self.springForceUserFunction = springForceUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorCoordinateSpringDamperExt' @@ -1719,7 +1732,7 @@ class VObjectConnectorGravity: def __init__(self, show = False, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1731,13 +1744,13 @@ def __repr__(self): class ObjectConnectorGravity: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], gravitationalConstant = 6.67430e-11, mass0 = 0., mass1 = 0., minDistanceRegularization = 0., activeConnector = True, visualization = {'show': False, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.gravitationalConstant = gravitationalConstant self.mass0 = CheckForValidUReal(mass0,"mass0","ObjectConnectorGravity") self.mass1 = CheckForValidUReal(mass1,"mass1","ObjectConnectorGravity") self.minDistanceRegularization = CheckForValidUReal(minDistanceRegularization,"minDistanceRegularization","ObjectConnectorGravity") self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorGravity' @@ -1768,8 +1781,8 @@ def __init__(self, show = True, cylinderRadius = 0.05, rodRadius = 0.03, pistonR self.rodMountRadius = rodMountRadius self.baseMountRadius = baseMountRadius self.baseMountLength = baseMountLength - self.colorCylinder = colorCylinder - self.colorPiston = colorPiston + self.colorCylinder = np.array(colorCylinder) + self.colorPiston = np.array(colorPiston) def __iter__(self): yield 'show', self.show @@ -1788,8 +1801,8 @@ def __repr__(self): class ObjectConnectorHydraulicActuatorSimple: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumbers = [], offsetLength = 0., strokeLength = 0., chamberCrossSection0 = 0., chamberCrossSection1 = 0., hoseVolume0 = 0., hoseVolume1 = 0., valveOpening0 = 0., valveOpening1 = 0., actuatorDamping = 0., oilBulkModulus = 0., cylinderBulkModulus = 0., hoseBulkModulus = 0., nominalFlow = 0., systemPressure = 0., tankPressure = 0., useChamberVolumeChange = False, activeConnector = True, visualization = {'show': True, 'cylinderRadius': 0.05, 'rodRadius': 0.03, 'pistonRadius': 0.04, 'pistonLength': 0.001, 'rodMountRadius': 0.0, 'baseMountRadius': 0.0, 'baseMountLength': 0.0, 'colorCylinder': [-1.,-1.,-1.,-1.], 'colorPiston': [0.8,0.8,0.8,1.]}): self.name = name - self.markerNumbers = markerNumbers - self.nodeNumbers = nodeNumbers + self.markerNumbers = copy.copy(markerNumbers) + self.nodeNumbers = copy.copy(nodeNumbers) self.offsetLength = CheckForValidUReal(offsetLength,"offsetLength","ObjectConnectorHydraulicActuatorSimple") self.strokeLength = CheckForValidPReal(strokeLength,"strokeLength","ObjectConnectorHydraulicActuatorSimple") self.chamberCrossSection0 = CheckForValidPReal(chamberCrossSection0,"chamberCrossSection0","ObjectConnectorHydraulicActuatorSimple") @@ -1807,7 +1820,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.tankPressure = tankPressure self.useChamberVolumeChange = useChamberVolumeChange self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorHydraulicActuatorSimple' @@ -1852,7 +1865,7 @@ class VObjectConnectorReevingSystemSprings: def __init__(self, show = True, ropeRadius = 0.001, color = [-1.,-1.,-1.,-1.]): self.show = show self.ropeRadius = ropeRadius - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1862,20 +1875,21 @@ def __iter__(self): def __repr__(self): return str(dict(self)) class ObjectConnectorReevingSystemSprings: - def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], hasCoordinateMarkers = False, coordinateFactors = [1,1], stiffnessPerLength = 0., dampingPerLength = 0., dampingTorsional = 0., dampingShear = 0., referenceLength = 0., sheavesAxes = [], sheavesRadii = [], activeConnector = True, visualization = {'show': True, 'ropeRadius': 0.001, 'color': [-1.,-1.,-1.,-1.]}): + def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], hasCoordinateMarkers = False, coordinateFactors = [1,1], stiffnessPerLength = 0., dampingPerLength = 0., dampingTorsional = 0., dampingShear = 0., regularizationForce = 0.1, referenceLength = 0., sheavesAxes = None, sheavesRadii = [], activeConnector = True, visualization = {'show': True, 'ropeRadius': 0.001, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.hasCoordinateMarkers = hasCoordinateMarkers - self.coordinateFactors = coordinateFactors + self.coordinateFactors = np.array(coordinateFactors) self.stiffnessPerLength = CheckForValidUReal(stiffnessPerLength,"stiffnessPerLength","ObjectConnectorReevingSystemSprings") self.dampingPerLength = CheckForValidUReal(dampingPerLength,"dampingPerLength","ObjectConnectorReevingSystemSprings") self.dampingTorsional = CheckForValidUReal(dampingTorsional,"dampingTorsional","ObjectConnectorReevingSystemSprings") self.dampingShear = CheckForValidUReal(dampingShear,"dampingShear","ObjectConnectorReevingSystemSprings") + self.regularizationForce = regularizationForce self.referenceLength = referenceLength self.sheavesAxes = sheavesAxes - self.sheavesRadii = sheavesRadii + self.sheavesRadii = np.array(sheavesRadii) self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorReevingSystemSprings' @@ -1887,6 +1901,7 @@ def __iter__(self): yield 'dampingPerLength', self.dampingPerLength yield 'dampingTorsional', self.dampingTorsional yield 'dampingShear', self.dampingShear + yield 'regularizationForce', self.regularizationForce yield 'referenceLength', self.referenceLength yield 'sheavesAxes', self.sheavesAxes yield 'sheavesRadii', self.sheavesRadii @@ -1905,7 +1920,7 @@ class VObjectConnectorDistance: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1917,10 +1932,10 @@ def __repr__(self): class ObjectConnectorDistance: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], distance = 0., activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.distance = CheckForValidPReal(distance,"distance","ObjectConnectorDistance") self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorDistance' @@ -1942,7 +1957,7 @@ class VObjectConnectorCoordinate: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1954,14 +1969,14 @@ def __repr__(self): class ObjectConnectorCoordinate: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], offset = 0., factorValue1 = 1., velocityLevel = False, offsetUserFunction = 0, offsetUserFunction_t = 0, activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.offset = offset self.factorValue1 = factorValue1 self.velocityLevel = velocityLevel self.offsetUserFunction = offsetUserFunction self.offsetUserFunction_t = offsetUserFunction_t self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorCoordinate' @@ -1986,7 +2001,7 @@ def __repr__(self): class VObjectConnectorCoordinateVector: def __init__(self, show = True, color = [-1.,-1.,-1.,-1.]): self.show = show - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -1997,17 +2012,17 @@ def __repr__(self): class ObjectConnectorCoordinateVector: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], scalingMarker0 = [], scalingMarker1 = [], quadraticTermMarker0 = [], quadraticTermMarker1 = [], offset = [], velocityLevel = False, constraintUserFunction = 0, jacobianUserFunction = 0, activeConnector = True, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.scalingMarker0 = scalingMarker0 - self.scalingMarker1 = scalingMarker1 - self.quadraticTermMarker0 = quadraticTermMarker0 - self.quadraticTermMarker1 = quadraticTermMarker1 - self.offset = offset + self.markerNumbers = copy.copy(markerNumbers) + self.scalingMarker0 = np.array(scalingMarker0) + self.scalingMarker1 = np.array(scalingMarker1) + self.quadraticTermMarker0 = np.array(quadraticTermMarker0) + self.quadraticTermMarker1 = np.array(quadraticTermMarker1) + self.offset = np.array(offset) self.velocityLevel = velocityLevel self.constraintUserFunction = constraintUserFunction self.jacobianUserFunction = jacobianUserFunction self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorCoordinateVector' @@ -2035,7 +2050,7 @@ class VObjectConnectorRollingDiscPenalty: def __init__(self, show = True, discWidth = 0.1, color = [-1.,-1.,-1.,-1.]): self.show = show self.discWidth = discWidth - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2047,21 +2062,21 @@ def __repr__(self): class ObjectConnectorRollingDiscPenalty: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), discRadius = 0., discAxis = [1,0,0], planeNormal = [0,0,1], dryFrictionAngle = 0., contactStiffness = 0., contactDamping = 0., dryFriction = [0,0], dryFrictionProportionalZone = 0., viscousFriction = [0,0], rollingFrictionViscous = 0., useLinearProportionalZone = False, activeConnector = True, visualization = {'show': True, 'discWidth': 0.1, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.discRadius = CheckForValidPReal(discRadius,"discRadius","ObjectConnectorRollingDiscPenalty") - self.discAxis = discAxis - self.planeNormal = planeNormal + self.discAxis = np.array(discAxis) + self.planeNormal = np.array(planeNormal) self.dryFrictionAngle = dryFrictionAngle self.contactStiffness = CheckForValidUReal(contactStiffness,"contactStiffness","ObjectConnectorRollingDiscPenalty") self.contactDamping = CheckForValidUReal(contactDamping,"contactDamping","ObjectConnectorRollingDiscPenalty") - self.dryFriction = dryFriction + self.dryFriction = np.array(dryFriction) self.dryFrictionProportionalZone = dryFrictionProportionalZone - self.viscousFriction = viscousFriction + self.viscousFriction = np.array(viscousFriction) self.rollingFrictionViscous = rollingFrictionViscous self.useLinearProportionalZone = useLinearProportionalZone self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ConnectorRollingDiscPenalty' @@ -2093,7 +2108,7 @@ def __repr__(self): class VObjectContactConvexRoll: def __init__(self, show = True, color = [-1.,-1.,-1.,-1.]): self.show = show - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2104,7 +2119,7 @@ def __repr__(self): class ObjectContactConvexRoll: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), contactStiffness = 0., contactDamping = 0., dynamicFriction = 0., staticFrictionOffset = 0., viscousFriction = 0., exponentialDecayStatic = 1e-3, frictionProportionalZone = 1e-3, rollLength = 0., coefficientsHull = [], rBoundingSphere = 0, activeConnector = True, visualization = {'show': True, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.contactStiffness = contactStiffness self.contactDamping = contactDamping @@ -2114,10 +2129,10 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.exponentialDecayStatic = CheckForValidPReal(exponentialDecayStatic,"exponentialDecayStatic","ObjectContactConvexRoll") self.frictionProportionalZone = CheckForValidUReal(frictionProportionalZone,"frictionProportionalZone","ObjectContactConvexRoll") self.rollLength = CheckForValidUReal(rollLength,"rollLength","ObjectContactConvexRoll") - self.coefficientsHull = coefficientsHull + self.coefficientsHull = np.array(coefficientsHull) self.rBoundingSphere = CheckForValidUReal(rBoundingSphere,"rBoundingSphere","ObjectContactConvexRoll") self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ContactConvexRoll' @@ -2144,7 +2159,7 @@ class VObjectContactCoordinate: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2156,13 +2171,13 @@ def __repr__(self): class ObjectContactCoordinate: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), contactStiffness = 0., contactDamping = 0., offset = 0., activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.contactStiffness = CheckForValidUReal(contactStiffness,"contactStiffness","ObjectContactCoordinate") self.contactDamping = CheckForValidUReal(contactDamping,"contactDamping","ObjectContactCoordinate") self.offset = offset self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ContactCoordinate' @@ -2184,7 +2199,7 @@ def __init__(self, show = True, showContactCircle = True, drawSize = -1., color self.show = show self.showContactCircle = showContactCircle self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2197,7 +2212,7 @@ def __repr__(self): class ObjectContactCircleCable2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), numberOfContactSegments = 3, contactStiffness = 0., contactDamping = 0., circleRadius = 0., offset = 0., activeConnector = True, visualization = {'show': True, 'showContactCircle': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.numberOfContactSegments = numberOfContactSegments self.contactStiffness = CheckForValidUReal(contactStiffness,"contactStiffness","ObjectContactCircleCable2D") @@ -2205,7 +2220,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.circleRadius = CheckForValidUReal(circleRadius,"circleRadius","ObjectContactCircleCable2D") self.offset = offset self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ContactCircleCable2D' @@ -2230,7 +2245,7 @@ def __init__(self, show = True, showContactCircle = True, drawSize = -1., color self.show = show self.showContactCircle = showContactCircle self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2243,7 +2258,7 @@ def __repr__(self): class ObjectContactFrictionCircleCable2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), numberOfContactSegments = 3, contactStiffness = 0., contactDamping = 0., frictionVelocityPenalty = 0., frictionStiffness = 0., frictionCoefficient = 0., circleRadius = 0., useSegmentNormals = True, activeConnector = True, visualization = {'show': True, 'showContactCircle': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.numberOfContactSegments = CheckForValidPInt(numberOfContactSegments,"numberOfContactSegments","ObjectContactFrictionCircleCable2D") self.contactStiffness = CheckForValidUReal(contactStiffness,"contactStiffness","ObjectContactFrictionCircleCable2D") @@ -2254,7 +2269,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.circleRadius = CheckForValidUReal(circleRadius,"circleRadius","ObjectContactFrictionCircleCable2D") self.useSegmentNormals = useSegmentNormals self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ContactFrictionCircleCable2D' @@ -2282,7 +2297,7 @@ def __init__(self, show = True, axesRadius = 0.1, axesLength = 0.4, color = [-1. self.show = show self.axesRadius = axesRadius self.axesLength = axesLength - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2295,16 +2310,16 @@ def __repr__(self): class ObjectJointGeneric: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], constrainedAxes = [1,1,1,1,1,1], rotationMarker0 = IIDiagMatrix(rowsColumns=3,value=1), rotationMarker1 = IIDiagMatrix(rowsColumns=3,value=1), activeConnector = True, offsetUserFunctionParameters = [0.,0.,0.,0.,0.,0.], offsetUserFunction = 0, offsetUserFunction_t = 0, alternativeConstraints = False, visualization = {'show': True, 'axesRadius': 0.1, 'axesLength': 0.4, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.constrainedAxes = constrainedAxes - self.rotationMarker0 = rotationMarker0 - self.rotationMarker1 = rotationMarker1 + self.markerNumbers = copy.copy(markerNumbers) + self.constrainedAxes = copy.copy(constrainedAxes) + self.rotationMarker0 = np.array(rotationMarker0) + self.rotationMarker1 = np.array(rotationMarker1) self.activeConnector = activeConnector - self.offsetUserFunctionParameters = offsetUserFunctionParameters + self.offsetUserFunctionParameters = np.array(offsetUserFunctionParameters) self.offsetUserFunction = offsetUserFunction self.offsetUserFunction_t = offsetUserFunction_t self.alternativeConstraints = alternativeConstraints - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointGeneric' @@ -2334,7 +2349,7 @@ def __init__(self, show = True, axisRadius = 0.1, axisLength = 0.4, color = [-1. self.show = show self.axisRadius = axisRadius self.axisLength = axisLength - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2347,11 +2362,11 @@ def __repr__(self): class ObjectJointRevoluteZ: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], rotationMarker0 = IIDiagMatrix(rowsColumns=3,value=1), rotationMarker1 = IIDiagMatrix(rowsColumns=3,value=1), activeConnector = True, visualization = {'show': True, 'axisRadius': 0.1, 'axisLength': 0.4, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.rotationMarker0 = rotationMarker0 - self.rotationMarker1 = rotationMarker1 + self.markerNumbers = copy.copy(markerNumbers) + self.rotationMarker0 = np.array(rotationMarker0) + self.rotationMarker1 = np.array(rotationMarker1) self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointRevoluteZ' @@ -2376,7 +2391,7 @@ def __init__(self, show = True, axisRadius = 0.1, axisLength = 0.4, color = [-1. self.show = show self.axisRadius = axisRadius self.axisLength = axisLength - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2389,11 +2404,11 @@ def __repr__(self): class ObjectJointPrismaticX: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], rotationMarker0 = IIDiagMatrix(rowsColumns=3,value=1), rotationMarker1 = IIDiagMatrix(rowsColumns=3,value=1), activeConnector = True, visualization = {'show': True, 'axisRadius': 0.1, 'axisLength': 0.4, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.rotationMarker0 = rotationMarker0 - self.rotationMarker1 = rotationMarker1 + self.markerNumbers = copy.copy(markerNumbers) + self.rotationMarker0 = np.array(rotationMarker0) + self.rotationMarker1 = np.array(rotationMarker1) self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointPrismaticX' @@ -2417,7 +2432,7 @@ class VObjectJointSpherical: def __init__(self, show = True, jointRadius = 0.1, color = [-1.,-1.,-1.,-1.]): self.show = show self.jointRadius = jointRadius - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2429,10 +2444,10 @@ def __repr__(self): class ObjectJointSpherical: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], constrainedAxes = [1,1,1], activeConnector = True, visualization = {'show': True, 'jointRadius': 0.1, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.constrainedAxes = constrainedAxes + self.markerNumbers = copy.copy(markerNumbers) + self.constrainedAxes = copy.copy(constrainedAxes) self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointSpherical' @@ -2454,7 +2469,7 @@ class VObjectJointRollingDisc: def __init__(self, show = True, discWidth = 0.1, color = [-1.,-1.,-1.,-1.]): self.show = show self.discWidth = discWidth - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2466,13 +2481,13 @@ def __repr__(self): class ObjectJointRollingDisc: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], constrainedAxes = [1,1,1], activeConnector = True, discRadius = 0, discAxis = [1,0,0], planeNormal = [0,0,1], visualization = {'show': True, 'discWidth': 0.1, 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.constrainedAxes = constrainedAxes + self.markerNumbers = copy.copy(markerNumbers) + self.constrainedAxes = copy.copy(constrainedAxes) self.activeConnector = activeConnector self.discRadius = CheckForValidPReal(discRadius,"discRadius","ObjectJointRollingDisc") - self.discAxis = discAxis - self.planeNormal = planeNormal - self.visualization = visualization + self.discAxis = np.array(discAxis) + self.planeNormal = np.array(planeNormal) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointRollingDisc' @@ -2497,7 +2512,7 @@ class VObjectJointRevolute2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2509,9 +2524,9 @@ def __repr__(self): class ObjectJointRevolute2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointRevolute2D' @@ -2532,7 +2547,7 @@ class VObjectJointPrismatic2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2544,12 +2559,12 @@ def __repr__(self): class ObjectJointPrismatic2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], axisMarker0 = [1.,0.,0.], normalMarker1 = [0.,1.,0.], constrainRotation = True, activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.axisMarker0 = axisMarker0 - self.normalMarker1 = normalMarker1 + self.markerNumbers = copy.copy(markerNumbers) + self.axisMarker0 = np.array(axisMarker0) + self.normalMarker1 = np.array(normalMarker1) self.constrainRotation = constrainRotation self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointPrismatic2D' @@ -2573,7 +2588,7 @@ class VObjectJointSliding2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2585,15 +2600,15 @@ def __repr__(self): class ObjectJointSliding2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], slidingMarkerNumbers = [], slidingMarkerOffsets = [], nodeNumber = exudyn.InvalidIndex(), classicalFormulation = True, constrainRotation = False, axialForce = 0, activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.slidingMarkerNumbers = slidingMarkerNumbers - self.slidingMarkerOffsets = slidingMarkerOffsets + self.markerNumbers = copy.copy(markerNumbers) + self.slidingMarkerNumbers = copy.copy(slidingMarkerNumbers) + self.slidingMarkerOffsets = np.array(slidingMarkerOffsets) self.nodeNumber = nodeNumber self.classicalFormulation = classicalFormulation self.constrainRotation = constrainRotation self.axialForce = axialForce self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointSliding2D' @@ -2620,7 +2635,7 @@ class VObjectJointALEMoving2D: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2632,15 +2647,15 @@ def __repr__(self): class ObjectJointALEMoving2D: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], slidingMarkerNumbers = [], slidingMarkerOffsets = [], slidingOffset = 0., nodeNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], usePenaltyFormulation = False, penaltyStiffness = 0., activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers - self.slidingMarkerNumbers = slidingMarkerNumbers - self.slidingMarkerOffsets = slidingMarkerOffsets + self.markerNumbers = copy.copy(markerNumbers) + self.slidingMarkerNumbers = copy.copy(slidingMarkerNumbers) + self.slidingMarkerOffsets = np.array(slidingMarkerOffsets) self.slidingOffset = slidingOffset - self.nodeNumbers = nodeNumbers + self.nodeNumbers = copy.copy(nodeNumbers) self.usePenaltyFormulation = usePenaltyFormulation self.penaltyStiffness = penaltyStiffness self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'JointALEMoving2D' @@ -2667,7 +2682,7 @@ class VObjectContactFrictionCircleCable2DOld: def __init__(self, show = True, drawSize = -1., color = [-1.,-1.,-1.,-1.]): self.show = show self.drawSize = drawSize - self.color = color + self.color = np.array(color) def __iter__(self): yield 'show', self.show @@ -2679,7 +2694,7 @@ def __repr__(self): class ObjectContactFrictionCircleCable2DOld: def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.InvalidIndex() ], nodeNumber = exudyn.InvalidIndex(), numberOfContactSegments = 3, contactStiffness = 0., contactDamping = 0., frictionVelocityPenalty = 0., frictionStiffness = 0., frictionCoefficient = 0., circleRadius = 0., offset = 0., activeConnector = True, visualization = {'show': True, 'drawSize': -1., 'color': [-1.,-1.,-1.,-1.]}): self.name = name - self.markerNumbers = markerNumbers + self.markerNumbers = copy.copy(markerNumbers) self.nodeNumber = nodeNumber self.numberOfContactSegments = CheckForValidPInt(numberOfContactSegments,"numberOfContactSegments","ObjectContactFrictionCircleCable2DOld") self.contactStiffness = CheckForValidUReal(contactStiffness,"contactStiffness","ObjectContactFrictionCircleCable2DOld") @@ -2690,7 +2705,7 @@ def __init__(self, name = '', markerNumbers = [ exudyn.InvalidIndex(), exudyn.In self.circleRadius = CheckForValidUReal(circleRadius,"circleRadius","ObjectContactFrictionCircleCable2DOld") self.offset = offset self.activeConnector = activeConnector - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'objectType', 'ContactFrictionCircleCable2DOld' @@ -2727,7 +2742,7 @@ class MarkerBodyMass: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.bodyNumber = bodyNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'BodyMass' @@ -2750,8 +2765,8 @@ class MarkerBodyPosition: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), localPosition = [0.,0.,0.], visualization = {'show': True}): self.name = name self.bodyNumber = bodyNumber - self.localPosition = localPosition - self.visualization = visualization + self.localPosition = np.array(localPosition) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'BodyPosition' @@ -2775,8 +2790,8 @@ class MarkerBodyRigid: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), localPosition = [0.,0.,0.], visualization = {'show': True}): self.name = name self.bodyNumber = bodyNumber - self.localPosition = localPosition - self.visualization = visualization + self.localPosition = np.array(localPosition) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'BodyRigid' @@ -2800,7 +2815,7 @@ class MarkerNodePosition: def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodePosition' @@ -2823,7 +2838,7 @@ class MarkerNodeRigid: def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodeRigid' @@ -2847,7 +2862,7 @@ def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), coordinate = e self.name = name self.nodeNumber = nodeNumber self.coordinate = CheckForValidUInt(coordinate,"coordinate","MarkerNodeCoordinate") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodeCoordinate' @@ -2871,7 +2886,7 @@ class MarkerNodeCoordinates: def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.nodeNumber = nodeNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodeCoordinates' @@ -2895,7 +2910,7 @@ def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), coordinate = e self.name = name self.nodeNumber = nodeNumber self.coordinate = CheckForValidUInt(coordinate,"coordinate","MarkerNodeODE1Coordinate") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodeODE1Coordinate' @@ -2920,7 +2935,7 @@ def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), rotationCoordi self.name = name self.nodeNumber = nodeNumber self.rotationCoordinate = CheckForValidUInt(rotationCoordinate,"rotationCoordinate","MarkerNodeRotationCoordinate") - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'NodeRotationCoordinate' @@ -2946,9 +2961,9 @@ class MarkerSuperElementPosition: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), meshNodeNumbers = [], weightingFactors = [], visualization = {'show': True, 'showMarkerNodes': True}): self.name = name self.bodyNumber = bodyNumber - self.meshNodeNumbers = meshNodeNumbers - self.weightingFactors = weightingFactors - self.visualization = visualization + self.meshNodeNumbers = copy.copy(meshNodeNumbers) + self.weightingFactors = np.array(weightingFactors) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'SuperElementPosition' @@ -2976,12 +2991,12 @@ class MarkerSuperElementRigid: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), offset = [0.,0.,0.], meshNodeNumbers = [], weightingFactors = [], useAlternativeApproach = True, rotationsExponentialMap = 2, visualization = {'show': True, 'showMarkerNodes': True}): self.name = name self.bodyNumber = bodyNumber - self.offset = offset - self.meshNodeNumbers = meshNodeNumbers - self.weightingFactors = weightingFactors + self.offset = np.array(offset) + self.meshNodeNumbers = copy.copy(meshNodeNumbers) + self.weightingFactors = np.array(weightingFactors) self.useAlternativeApproach = useAlternativeApproach self.rotationsExponentialMap = rotationsExponentialMap - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'SuperElementRigid' @@ -3011,8 +3026,8 @@ def __init__(self, name = '', objectNumber = exudyn.InvalidIndex(), linkNumber = self.name = name self.objectNumber = objectNumber self.linkNumber = CheckForValidUInt(linkNumber,"linkNumber","MarkerKinematicTreeRigid") - self.localPosition = localPosition - self.visualization = visualization + self.localPosition = np.array(localPosition) + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'KinematicTreeRigid' @@ -3037,7 +3052,7 @@ class MarkerObjectODE2Coordinates: def __init__(self, name = '', objectNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.objectNumber = objectNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'ObjectODE2Coordinates' @@ -3062,7 +3077,7 @@ def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), numberOfSegmen self.bodyNumber = bodyNumber self.numberOfSegments = CheckForValidPInt(numberOfSegments,"numberOfSegments","MarkerBodyCable2DShape") self.verticalOffset = verticalOffset - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'BodyCable2DShape' @@ -3087,7 +3102,7 @@ class MarkerBodyCable2DCoordinates: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), visualization = {'show': True}): self.name = name self.bodyNumber = bodyNumber - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'markerType', 'BodyCable2DCoordinates' @@ -3112,10 +3127,10 @@ class LoadForceVector: def __init__(self, name = '', markerNumber = exudyn.InvalidIndex(), loadVector = [0.,0.,0.], bodyFixed = False, loadVectorUserFunction = 0, visualization = {'show': True}): self.name = name self.markerNumber = markerNumber - self.loadVector = loadVector + self.loadVector = np.array(loadVector) self.bodyFixed = bodyFixed self.loadVectorUserFunction = loadVectorUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'loadType', 'ForceVector' @@ -3145,10 +3160,10 @@ class LoadTorqueVector: def __init__(self, name = '', markerNumber = exudyn.InvalidIndex(), loadVector = [0.,0.,0.], bodyFixed = False, loadVectorUserFunction = 0, visualization = {'show': True}): self.name = name self.markerNumber = markerNumber - self.loadVector = loadVector + self.loadVector = np.array(loadVector) self.bodyFixed = bodyFixed self.loadVectorUserFunction = loadVectorUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'loadType', 'TorqueVector' @@ -3178,9 +3193,9 @@ class LoadMassProportional: def __init__(self, name = '', markerNumber = exudyn.InvalidIndex(), loadVector = [0.,0.,0.], loadVectorUserFunction = 0, visualization = {'show': True}): self.name = name self.markerNumber = markerNumber - self.loadVector = loadVector + self.loadVector = np.array(loadVector) self.loadVectorUserFunction = loadVectorUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'loadType', 'MassProportional' @@ -3211,7 +3226,7 @@ def __init__(self, name = '', markerNumber = exudyn.InvalidIndex(), load = 0., l self.markerNumber = markerNumber self.load = load self.loadUserFunction = loadUserFunction - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'loadType', 'Coordinate' @@ -3242,7 +3257,7 @@ def __init__(self, name = '', nodeNumber = exudyn.InvalidIndex(), writeToFile = self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'Node' @@ -3273,7 +3288,7 @@ def __init__(self, name = '', objectNumber = exudyn.InvalidIndex(), writeToFile self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'Object' @@ -3300,12 +3315,12 @@ class SensorBody: def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), localPosition = [0.,0.,0.], writeToFile = True, fileName = '', outputVariableType = 0, storeInternal = False, visualization = {'show': True}): self.name = name self.bodyNumber = bodyNumber - self.localPosition = localPosition + self.localPosition = np.array(localPosition) self.writeToFile = writeToFile self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'Body' @@ -3338,7 +3353,7 @@ def __init__(self, name = '', bodyNumber = exudyn.InvalidIndex(), meshNodeNumber self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'SuperElement' @@ -3367,12 +3382,12 @@ def __init__(self, name = '', objectNumber = exudyn.InvalidIndex(), linkNumber = self.name = name self.objectNumber = objectNumber self.linkNumber = CheckForValidUInt(linkNumber,"linkNumber","SensorKinematicTree") - self.localPosition = localPosition + self.localPosition = np.array(localPosition) self.writeToFile = writeToFile self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'KinematicTree' @@ -3405,7 +3420,7 @@ def __init__(self, name = '', markerNumber = exudyn.InvalidIndex(), writeToFile self.fileName = fileName self.outputVariableType = outputVariableType self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'Marker' @@ -3435,7 +3450,7 @@ def __init__(self, name = '', loadNumber = exudyn.InvalidIndex(), writeToFile = self.writeToFile = writeToFile self.fileName = fileName self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'Load' @@ -3460,13 +3475,13 @@ def __repr__(self): class SensorUserFunction: def __init__(self, name = '', sensorNumbers = [], factors = [], writeToFile = True, fileName = '', sensorUserFunction = 0, storeInternal = False, visualization = {'show': True}): self.name = name - self.sensorNumbers = sensorNumbers - self.factors = factors + self.sensorNumbers = copy.copy(sensorNumbers) + self.factors = np.array(factors) self.writeToFile = writeToFile self.fileName = fileName self.sensorUserFunction = sensorUserFunction self.storeInternal = storeInternal - self.visualization = visualization + self.visualization = CopyDictLevel1(visualization) def __iter__(self): yield 'sensorType', 'UserFunction' diff --git a/main/pythonDev/exudyn/mainSystemExtensions.py b/main/pythonDev/exudyn/mainSystemExtensions.py index 7d148235..11d4a65a 100644 --- a/main/pythonDev/exudyn/mainSystemExtensions.py +++ b/main/pythonDev/exudyn/mainSystemExtensions.py @@ -85,9 +85,9 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr #**input: # mbs: the MainSystem where items are created # name: name string for object, node is 'Node:'+name -# referenceCoordinates: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) -# initialCoordinates: initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) -# initialVelocities: initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) +# referencePosition: 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 point # gravity: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) # graphicsDataList: list of GraphicsData for optional mass visualization @@ -105,8 +105,8 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], -# initialVelocities = [2,5,0], +# b0=mbs.CreateMassPoint(referencePosition = [0,0,0], +# initialVelocity = [2,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -117,9 +117,9 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr # mbs.SolveDynamic(simulationSettings = simulationSettings) def MainSystemCreateMassPoint(mbs, name = '', - referenceCoordinates = [0.,0.,0.], - initialCoordinates = [0.,0.,0.], - initialVelocities = [0.,0.,0.], + referencePosition = [0.,0.,0.], + initialDisplacement = [0.,0.,0.], + initialVelocity = [0.,0.,0.], physicsMass=0, gravity = [0.,0.,0.], graphicsDataList = [], @@ -133,12 +133,12 @@ def MainSystemCreateMassPoint(mbs, if not exudyn.__useExudynFast: if not isinstance(name, str): RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='name', received = name, expectedType = ExpectedType.String) - if not IsVector(referenceCoordinates, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='referenceCoordinates', received = referenceCoordinates, expectedType = ExpectedType.Vector, dim=3) - if not IsVector(initialCoordinates, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialCoordinates', received = initialCoordinates, expectedType = ExpectedType.Vector, dim=3) - if not IsVector(initialVelocities, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialVelocities', received = initialVelocities, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(referencePosition, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='referencePosition', received = referencePosition, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(initialDisplacement, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialDisplacement', received = initialDisplacement, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(initialVelocity, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialVelocity', received = initialVelocity, expectedType = ExpectedType.Vector, dim=3) if not IsVector(gravity, 3): RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='gravity', received = gravity, expectedType = ExpectedType.Vector, dim=3) @@ -162,9 +162,9 @@ def MainSystemCreateMassPoint(mbs, if not create2D: nodeNumber = mbs.AddNode(eii.NodePoint(name = nodeName, - referenceCoordinates = referenceCoordinates, - initialCoordinates=initialCoordinates, - initialVelocities=initialVelocities, + referenceCoordinates = referencePosition, + initialCoordinates=initialDisplacement, + initialVelocities=initialVelocity, visualization = eii.VNodePoint(show = show and (graphicsDataList == []), drawSize = drawSize, color = color), )) bodyNumber = mbs.AddObject(eii.MassPoint(name = name, @@ -174,9 +174,9 @@ def MainSystemCreateMassPoint(mbs, graphicsData = graphicsDataList) )) else: nodeNumber = mbs.AddNode(eii.NodePoint2D(name = nodeName, - referenceCoordinates = referenceCoordinates[0:2], - initialCoordinates=initialCoordinates[0:2], - initialVelocities=initialVelocities[0:2], + referenceCoordinates = referencePosition[0:2], + initialCoordinates=initialDisplacement[0:2], + initialVelocities=initialVelocity[0:2], visualization = eii.VNodePoint2D(show = show and (graphicsDataList == []), drawSize = drawSize, color = color), )) bodyNumber = mbs.AddObject(eii.MassPoint2D(name = name, @@ -447,8 +447,8 @@ def AngularVelocity2RotationVector_t(angularVelocity, rotMatrix): # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], -# initialVelocities = [2,5,0], +# b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], +# initialVelocity = [2,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -583,7 +583,7 @@ def MainSystemCreateSpringDamper(mbs, # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], +# b0 = mbs.CreateMassPoint(referencePosition = [7,0,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -1185,7 +1185,7 @@ def MainSystemCreateGenericJoint(mbs, name='', bodyNumbers=[None, None], # gravity = [0,-9.81,0], # graphicsDataList = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], # color=color4orange)]) -# m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], +# m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], # physicsMass=1, drawSize = 0.2) # n1 = mbs.GetObject(m1)['nodeNumber'] # diff --git a/main/pythonDev/exudyn/plot.py b/main/pythonDev/exudyn/plot.py index d14db063..d5097c04 100644 --- a/main/pythonDev/exudyn/plot.py +++ b/main/pythonDev/exudyn/plot.py @@ -16,6 +16,7 @@ import exudyn #for sensor index from exudyn.advancedUtilities import PlotLineCode import copy +import os #++++++++++++++++++++++++++++++++ #this structure helps to define default values, that are then always used! @@ -193,6 +194,8 @@ def PlotSensorDefaults(): # [*kwargs]: # minorTicksXon: if True, turn minor ticks for x-axis on # minorTicksYon: if True, turn minor ticks for y-axis on +# logScaleX: use log scale for x-axis +# logScaleY: use log scale for y-axis # fileCommentChar: 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 @@ -242,7 +245,7 @@ def PlotSensor(mbs, sensorNumbers=[], components=0, xLabel='time (s)', yLabel=No for key in kwargs: - if (key!='minorTicksXon' and key!='minorTicksYon' and key!='sizeInches' + if (key!='minorTicksXon' and key!='minorTicksYon' and key!='fileCommentChar' and key!='fileDelimiterChar' and key!='logScaleX' and key!='logScaleY'): raise ValueError('PlotSensor: invalid argument: '+key) @@ -656,6 +659,11 @@ def PlotSensor(mbs, sensorNumbers=[], components=0, xLabel='time (s)', yLabel=No plt.show() if fileName != '': + try: + os.makedirs(os.path.dirname(fileName), exist_ok=True) + except: + pass #makedirs may fail on some systems, but we keep going + plt.savefig(fileName) return [plt, fig, ax, line] @@ -708,8 +716,8 @@ def PlotFFT(frequency, data, plt.xscale('log') if logScaleY: plt.yscale('log') - ax.grid(b=True, which='major', color='k', linestyle='-') - ax.grid(b=True, which='minor', color='k', linestyle=':') + ax.grid(visible=True, which='major', color='k', linestyle='-') + ax.grid(visible=True, which='minor', color='k', linestyle=':') ax.minorticks_on() plt.tight_layout() @@ -990,6 +998,10 @@ def PlotImage(imageData, HT = np.eye(4), axesEqual=True, plot3D=False, lineWidth plt.show() if fileName != '': + try: + os.makedirs(os.path.dirname(fileName), exist_ok=True) + except: + pass #makedirs may fail on some systems, but we keep going plt.savefig(fileName) diff --git a/main/pythonDev/exudyn/processing.py b/main/pythonDev/exudyn/processing.py index 4917c4ef..0ee4dcc0 100644 --- a/main/pythonDev/exudyn/processing.py +++ b/main/pythonDev/exudyn/processing.py @@ -17,6 +17,7 @@ import sys import time from copy import deepcopy #, copy +import os from exudyn.advancedUtilities import IsInteger #%%+++++++++++++++++++++++++++++++++++++++++++ @@ -62,6 +63,17 @@ def SingleIndex2SubIndices(i, subIndexRanges): return iRanges +#%%+++++++++++++++++++++++++++++++++++++++++++++++++++++ +#*function: internal function; add computation Index and parameterFunctionData to dictionry entry +# +def AddComputationIndexAndFunctionData(ind, cnt, addComputationIndex, parameterFunctionData): + if addComputationIndex: + ind['computationIndex'] = cnt + if bool(parameterFunctionData): # if dict is not empty + ind['functionData'] = parameterFunctionData + return + + #%%+++++++++++++++++++++++++++++++++++++++++++ #function: internal output function for ParameterVariation and GeneticOptimization # write header or values to output file and increase counter @@ -69,6 +81,12 @@ def WriteToFile(resultsFile, parameters, currentGeneration, values, globalCnt, w if resultsFile != '': #print('write to file') if writeHeader: + try: + #check only added in case of writeHeader to reduce overheads; may fail, if no header is written (but why...?) + os.makedirs(os.path.dirname(resultsFile), exist_ok=True) + except: + pass #makedirs may fail on some systems, but we keep going + file = open(resultsFile, 'w') file.write('#EXUDYN '+fileType+' results file:'+resultsFile+'\n') file.write('#results stored columnwise for every parameter and individual\n') @@ -505,6 +523,7 @@ def ParameterVariation(parameterFunction, parameters, # distanceFactor: children only survive at a certain relative distance of the current range; must be small enough (< 0.5) to allow individuals to survive; ignored if distanceFactor=0; as a rule of thumb, the distanceFactor should be zero in case that there is only one significant minimum, but if there are many local minima, the distanceFactor should be used to search at several different local minima # childDistribution: string with name of distribution for producing childs: "normal" (Gaussian, with sigma defining range), "uniform" (exactly in range of childs) # distanceFactorGenerations: number of generations (populations) at which the distance factor is active; the distance factor is used to find several local minima; finally, convergence is speed up without the distance factor +# parameterFunctionData: dictionary containing additional data passed to the objectiveFunction inside the parameters with dict key 'functionData'; use this e.g. for passing solver parameters or other settings # randomizerInitialization: initialize randomizer at beginning of optimization in order to get reproducible results, provide any integer in the range between 0 and 2**32 - 1 (default: no initialization) # # debugMode: if True, additional print out is done @@ -536,6 +555,7 @@ def GeneticOptimization(objectiveFunction, parameters, useMultiProcessing=False, showProgress = True, clusterHostNames = [], + parameterFunctionData = {}, **kwargs): def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): @@ -637,9 +657,7 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): pEnd = value[1] value = np.random.uniform(pBegin, pEnd) ind[key] = value - if addComputationIndex: - ind['computationIndex'] = i #unique index for one set of computations - + AddComputationIndexAndFunctionData(ind, i, addComputationIndex, parameterFunctionData) currentGeneration += [ind] #+++++++++++++++++++++++++++++++++++++++++++++++ @@ -673,10 +691,12 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): writeHeader = (popCnt == 0), multiProcessingMode=multiProcessingMode) - #remove computationIndex from new generation + #remove computationIndex and parameterfunctiondata from new generation for item in currentGeneration: if 'computationIndex' in item: del item['computationIndex'] + if 'functionData' in item: + del item['functionData'] #store all values parametersAll += currentGeneration.copy() @@ -753,7 +773,7 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): for k in range(nGen): d = 0 for (key,value) in ind.items(): - if key != 'computationIndex': + if key != 'computationIndex' and key in parameters.keys(): # only manipulate values from given parameters d += (ind[key] - currentGeneration[k][key])**2/(rangesDict[key])**2 d = np.sqrt(d/dim) #number of parameters shall not influence distanceFactor #print("d=",d,":",ind,"-",currentGeneration[k]) @@ -830,7 +850,7 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): currentGeneration += [newGen] #currentGeneration += [indList[pi]] #gives wrong sorting in dict ..., destroys output file order p += 1 - + indList[-1]['functionData'] = parameterFunctionData # add function data cnt += 1 #computation count ... for every parameter variation within one generation # print("pop", popCnt, ": currentGeneration=\n",currentGeneration) else: @@ -848,7 +868,7 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): n = len(parametersAll) if n != 0: for key in parametersAll[0]: - if key != 'computationIndex': + if key != 'computationIndex' and key in parameters.keys(): # do not output function data parameterData = np.zeros(n) #extract parameter list from list of dictionaries: for i in range(n): @@ -862,26 +882,22 @@ def RandomNumber(distribution, rangeBegin, rangeEnd, vMin, vMax): #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ -#**function: Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). +#**function: Compute minimum of given objectiveFunction. This function is based on scipy.optimize.minimize() and it provides the same interface as GeneticOptimization(). Note that in special cases, you should copy this function and adapt to your needs. #**input: # objectiveFunction: function, which takes the form parameterFunction(parameterDict) and which returns a value or list (or numpy array) which reflects the size of the objective to be minimized # parameters: given as a dictionary, consist of name and tuple containing the search range for this parameter (begin, end), e.g. 'mass':(10,50) # storeFunctionValues: if True, objectiveFunction values are computed (additional costs!) and stored in every iteration into valueList # initialGuess: initial guess. Array of real elements of size (n,), where 'n' is the number of independent variables. If not provided by the user, initialGuess is computed from bounds provided in parameterDict. # method: solver that should be used, e.g. 'Nelder-Mead', 'Powell', 'CG' etc. A list of available solvers can be found in the documentation of scipy.optimize.minimize(). -# tol: tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol. For detailed control, use solver-specific options using the 'options' variable. +# tol: tolerance for termination. When tol is specified, the selected minimization algorithm sets some relevant solver-specific tolerance(s) equal to tol (but this is usually not the tolerance for loss or parameters1). For detailed control, use solver-specific options using the 'options' variable. # options: dictionary of solver options. Can be used to set absolute and relative error tolerances. Detailed information can be found in the documentation of scipy.optimize.minimize(). # enforceBounds: if True, ensures that only parameters within the bounds specified in ParameterDict are used for minimization; this may help to avoid, e.g., negative values, but may lead to non-convergence # verbose: prints solver information into console, e.g. number of iterations 'nit', number of funcion evaluations 'nfev', status etc. -# showProgress: if True, shows for every iteration objective function value, number of current iteration, time needed for current iteration, maximum number of iterations until solver option 'maxiter' is reached. +# showProgress: if True, shows for every iteration objective function value, current iteration number, time needed for current iteration, maximum number of iterations and loss (current value of objective function) # addComputationIndex: if True, key 'computationIndex' is added for consistency reasons with GeneticOptimizaiton to every parameterDict in the call to parameterFunction(); however, the value is always 0, because no multi threading is used in Minimize(...) # resultsFile: if provided, the results are stored columnwise into the given file and written after every generation; use resultsMonitor.py to track results in realtime # useScipyBounds: if True, use scipy.optimize.minimize() option 'bounds' to apply bounds on variable specified in ParameterDict. Note, this option is only used by some specific methods of scipy.optimize.minimize()! method='Nelder-Mead' ignores this option for example! if False, option 'enforceBounds' will be set to False! # args: extra arguments passed to the objective function and its derivatives (fun, jac and hess functions). -# jac: method for computing the gradient vector. -# hess: method for computing the Hessian matrix. -# hessp: hessian of objective function times an arbitrary vector p. -# constraints: constraints definition (only for COBYLA, SLSQP and trust-constr). #**author: Stefan Holzinger, Johannes Gerstmayr #**output: returns [optimumParameter, optimumValue, parameterList, valueList], containing the optimum parameter set 'optimumParameter', optimum value 'optimumValue', the whole list of parameters parameterList with according objective values 'valueList' #**notes: This function is still under development and shows an experimental state! There are currently unused arguments of scipy.optimize.minimize(): Detailed information can be found in the documentation of scipy.optimize.minimize(). @@ -889,6 +905,7 @@ def Minimize(objectiveFunction, parameters, initialGuess=[], method='Nelder-Mead enforceBounds=True, debugMode=False, showProgress=True, addComputationIndex=False, storeFunctionValues=True, **kwargs): from scipy import optimize #for minimize + # from functools import partial #add extra args to function # get parameter names parKeyLst = list(parameters.keys()) @@ -924,7 +941,7 @@ def Minimize(objectiveFunction, parameters, initialGuess=[], method='Nelder-Mead # +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ # process initial guess - if initialGuessCopy != []: # initial guess has been provided by the user + if initialGuessCopy == []: # initial guess has been provided by the user initialGuessCopy = [None]*nParameters for i in range(nParameters): initialGuessCopy[i] = np.mean(bounds[i]) @@ -968,10 +985,12 @@ def WriteToFileMinimize(resFileName, parDictInit, pDict, objFunVal, resFileCnt): return resultsFileCntTemp startTime = time.time() #for calculating time to go + timePrintLast = [startTime-10] # +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ # callback: needed to get parameters after each iteration for file writing and post processing - def StoreParameterFunctionValues(parametersAtIteration, *args): + def StoreParameterFunctionValues(parametersAtIteration, convergence=0, lastTime=False): + #global timePrintLast # print(parametersAtIteration2) for i in range(nParameters): parameterValueLst[i].append(parametersAtIteration[i]) @@ -987,24 +1006,25 @@ def StoreParameterFunctionValues(parametersAtIteration, *args): if resultsFile != '': resultsFileCnt[0] = WriteToFileMinimize(resultsFile, parameters, pDict, valuesAtIteration, resultsFileCnt[0]) - # increase iteration counter itCtr[0] += 1 # time needed for iteration iterationsToGo = (maxiter-itCtr[0]) timeToGo = 0 - timeSpent = time.time() - startTime + currentTime = time.time() + timeSpent = currentTime - startTime if itCtr[0] != 0: timeToGo = timeSpent/itCtr[0] * iterationsToGo # print progess to console if showProgress: - print('***** ') - print('iteration ' + str(itCtr[0]) + ' / max. ' + str(iterationsToGo)) - print(' time = ', timeSpent, 's') - print(' time to go (max) = ', timeToGo, 's') - print(' objective function value: ', valuesAtIteration) + if currentTime - timePrintLast[0] > 1 or lastTime: + timePrintLast[0] = currentTime + print('iteration ' + str(itCtr[0]) + ' / ' + str(maxiter), end='') + print(', time = '+str(round(timeSpent,2)), 's / ',end='') + print(str(round(timeToGo,2)) + 's',end='') + print(', loss:', ("{:.0"+str(3)+"g}").format(valuesAtIteration)) @@ -1029,19 +1049,18 @@ def ParameterFunctionMinimize(parametersAtIteration): # +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ # perform optimizaion - optimizeResult = optimize.minimize(ParameterFunctionMinimize, initialGuessCopy, + optimizeResult = optimize.minimize(ParameterFunctionMinimize, + initialGuessCopy, method=method, bounds=scipyMinimizeBounds, + # callback=partial(StoreParameterFunctionValues, convergence=0, callbackArgs=callbackArgs), callback=StoreParameterFunctionValues, tol=tol, options=options, - #jac=jac, - #hess=hess, - #constraints=constraints, ) # if showProgress: # print progress data for final iteration to console - StoreParameterFunctionValues(optimizeResult['x']) + StoreParameterFunctionValues(optimizeResult['x'], lastTime=True) if debugMode: # show solver informations (e.g. number of function evaluations etc.) print('---------------------------------------\n') diff --git a/main/pythonDev/exudyn/robotics/rosInterface.py b/main/pythonDev/exudyn/robotics/rosInterface.py new file mode 100644 index 00000000..69558b54 --- /dev/null +++ b/main/pythonDev/exudyn/robotics/rosInterface.py @@ -0,0 +1,302 @@ +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +# This is an EXUDYN python ROS interface +# +# Details: This interface collects interfaces and functionality for ROS comunication +# This library is under construction (2023-05); +# To make use of this libraries, you need to +# install ROS (ROS1 noetic) including rospy +# Please consider following workflow: +# make sure to have a working ROS1-NOETIC installation, ROS2 is not supported yet +# tested only with ROS1-NOETIC, ubuntu 20.04, and Python 3.8.10 +# you find all ROS1 installation steps on: +# http://wiki.ros.org/noetic/Installation/Ubuntu +# Step 1.4 we recommend to install: (sudo apt install ros-noetic-desktop) +# Check the installation of the turtlesim package (rosrun turtlesim turtlesim_node ) +# if not installed: sudo apt install ros-noetic-turtlesim +# use a catkin workspace and build a ROS1 Package +# Follow instructions on: +# http://wiki.ros.org/ROS/Tutorials (recommend go trough step 1 to 6) +# Minimal example to use: +# create catkin workspace: +# mkdir -p ~/catkin_ws/src +# cd ~/catkin_ws +# catkin_make +# source devel/setup.bash +# build ROS package: +# cd ~/catkin_ws/src +# catkin_create_pkg my_pkg_name rospy roscpp std_msgs geometry_msgs sensor_msgs +# build catkin workspace and sourcing setup file +# cd ~/catkin_ws +# cakin_make +# source ~/catkin_ws/devel/setup.bash +# for more functionality see also: ROSExampleMassPoint.py, ROSExampleBringup.launch, ROSExampleControlVelocity.py +# Author: Martin Sereinig, Peter Manzl +# Date: 2023-05-31 (created) +# +# 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. +# +#+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ + +import numpy as np +import exudyn as exu +from exudyn.utilities import * +import time +import os + +# import needed ROS modules and messages +import rospy +from geometry_msgs.msg import PoseStamped, WrenchStamped, Twist +from std_msgs.msg import Float64MultiArray, Empty, String, Time + +#**class: interface super class to establish a ROS Exudyn interface +# see specific class functions which can be used and extended +# by inheritance with class MyClass(ROSInterface) +#**author: Martin Sereinig, Peter Manzl +#**notes: some inspiration can be taken from +class ROSInterface: + def __init__(self, name = 'ExudynRobotInterface'): + + # check ROS version + self.CheckROSversion() + + # init ros node + rospy.init_node(name, anonymous=True) + + # topics namespace, will be used in all topics + self.topicBase = '/exudyn/' + + # set ROS node start time Time + self.t0 = rospy.get_time() + print('ROS node initialization at time {} done!'.format(self.t0)) + # initialize simulation runtime + self.tsim = self.t0 - rospy.get_time() + + # initialization of some timing variables + self.rosPoseSendInterval = 0.01 #ms + self.rosTwistSendInterval = 0.01 #ms + self.lastPoseSendTime = -self.rosPoseSendInterval + self.lastTwistSendTime = -self.rosTwistSendInterval + self.systemStateUpdateInterval = 0.01 #ms + self.lastSystemStateUpdateTime = -self.systemStateUpdateInterval + self.lastStepTime = 0 # last step time (exudyn time) + + # initialize standard publisher + # publisher for time message + self.exuTimePublisher = self.InitPublisher(pubTopicName='SimiulationTime', + pubType = Time, queueSize = 10) + # publisher for simple string message + self.exuStringPublisher = self.InitPublisher(pubTopicName='SimpleString', + pubType = String, queueSize = 10) + # publisher for velocities (Twist) + self.exuTwistPublisher = self.InitPublisher(pubTopicName='Twist', + pubType = Twist, queueSize = 10) + # publisher for Pose + self.exuPosePublisher = self.InitPublisher(pubTopicName='Pose', + pubType = PoseStamped, queueSize = 10) + # publisher for Wrench + self.exuWrenchPublisher = self.InitPublisher(pubTopicName='Wrensh', + pubType = WrenchStamped, queueSize = 10) + # publisher for system data + self.exuSystemstatePublisher = self.InitPublisher(pubTopicName='Systemstate', + pubType = Float64MultiArray, queueSize = 1) + # add further publisher if needed in inherited class + # initialization of subscriber and needed callback function will be done in inherited class + # self.callbackData = + return + #**classFunction: function to create a publisher + #**input: + # pubTopicName: topic name to publish, actual topic will be /exudyn/pubTopicName + # pubType: data type used in topic + # queSize: length of queue to hold messages, should be as small as sending frequency (= simulation sample time) + #**author: Martin Sereinig + #**notes: find msgs types here + # http://docs.ros.org/en/melodic/api/std_msgs/html/index-msg.html + #**examples: + # publisher for poses, pubType = PoseStamped, + # publisher for system data, pubType = Float64MultiArray, + # publisher for filtered force, pubType = WrenchStamped, + # publisher for velocities, pubType = Twist, + def InitPublisher(self, pubTopicName='', pubType = Empty, queueSize = 10): + exuPublisher = rospy.Publisher(self.topicBase + pubTopicName, + pubType, queue_size=queueSize) + return exuPublisher + + #**classFunction: function to create a generic callback function for a subscriber + #**input: + # topic: topic name generated by init Subscriber + # data: data structure for regarding individual topic + #**author: Peter Manzl + def ExuCallbackGeneric(self,subTopicName, data): + setattr(self, subTopicName, data) + return True + + #**function: function to create a subscriber + #**input: + # subTopicNameSpace: topic namespace: 'exudyn/' + # subTopicName: topic name to subscribe + # subType: data type for topic to subscribe + #**author: Peter Manzl + #**note: callback function will be automatic generated for each subscriber, depending + # on subTopicName. Data will be found under self.subTopicName + def InitSubscriber(self,subTopicNameSpace, subTopicName, subType): + exuSubscriber = rospy.Subscriber(subTopicNameSpace+subTopicName, subType, + lambda data: self.ExuCallbackGeneric(subTopicName, data)) + return exuSubscriber + + #**classFunction: check the current used ROS version + #**author: Martin Sereinig + #**note: just supports ROS1, ROS2 support will be given in future releases + def CheckROSversion(self): + # check and set ROSVersion + #os.system('rosversion -d') + #self.myROSversionString = os.popen('rosversion -d').read() + self.myROSversionEnvInt = int(os.getenv('ROS_VERSION','0')) + self.myROSdistriEnv = os.getenv('ROS_DISTRO','unknown') + rospy.loginfo('-ROS'+str(self.myROSversionEnvInt)+' '+self.myROSdistriEnv+'-') + if self.myROSversionEnvInt != 0: + return True + else: + return False + + #**classFunction: Example method to be called once per frame/control cycle in Exudyn PreStepUserFunction + #**note: reads sensor values, creates message, publish and subscribe to ROS + #**input: + # mbs: mbs (exudyn.exudynCPP.MainSystem), multi-body simulation system from exudyn + # tExu: tExu (float), elapsed time since simulation start + # getData: getData (string), get pose information from 'node' or from 'sensor' + #**author: Martin Sereinig + #**notes: + # reads sensor values, creates message, publish and subscribe to ROS + # publishing each and every step is too much, this would slow down the connection + # thus: publish every few seconds, only + # furthermore, as vrInterface is only updating the graphics with f=60Hz, we don't have to update + # system state every 1ms, so with f=1000Hz. Instead f=60Hz equivalents to update every 1/60=17ms + # timing variable to know when to send new command to robot or when to publish new mbs system state update + def PublishPoseUpdate(self, mbs, tExu, getData = 'node'): + if tExu - self.lastPoseSendTime >= self.rosPoseSendInterval: + self.lastPoseSendTime = tExu + if getData == 'sensor': + # read current kinematic state and orientation from predefined variables send via mbs.variables + posFromExu = mbs.GetSensorValues(mbs.variables['pos']) + oriFromExu = mbs.GetSensorValues(mbs.variables['ori']) + # convert data to numpy arrays + pos = np.array(posFromExu) + rot = np.array(oriFromExu) + rotE = np.roll(RotXYZ2EulerParameters(rot),-1) # use roll to meet ROS eulerparameter convention [x,y,z,w] + + elif getData == 'node': + nodeDic = mbs.GetNode(mbs.variables['nodeNumber']) + if nodeDic['nodeType'] == 'RigidBodyEP': + # get position [x,y,z] and orientation (eulerparameter) [w,x,y,z] from exudyn via node coordinates + # nodeCoordinates = [x,y,z, w,x,y,z] + nodeCoordinates = list(np.array(nodeDic['referenceCoordinates']) + + np.array(mbs.GetNodeOutput(mbs.variables['nodeNumber'],variableType = exu.OutputVariableType.Coordinates))) + # reformulation for ROS + pos = nodeCoordinates[0:3] # pos = [x,y,z] + rotE = np.roll(nodeCoordinates[3:7],-1) # rotE = [x,y,z,w] + + if False: # for debug + print('position: ',nodeCoordinates[0:3]) + print('orientation: ',nodeCoordinates[3:7]) # eulerparameter exu [w,x,y,z] + else: + print('node type not supported') + else: + print('Error! Please choose how to get pose information!') + + + poseExu = np.append(pos,rotE) + # compose message and publish + msgData = PoseStamped() + # postion + msgData.pose.position.x = poseExu[0] + msgData.pose.position.y = poseExu[1] + msgData.pose.position.z = poseExu[2] + # orientation given in unit quarternions + msgData.pose.orientation.x = poseExu[3] + msgData.pose.orientation.y = poseExu[4] + msgData.pose.orientation.z = poseExu[5] + msgData.pose.orientation.w = poseExu[6] + # write current time into message + msgData.header.stamp = rospy.Time.now() + self.exuPosePublisher.publish(msgData) + + + + #**classFunction: Example method to be called once per frame/control cycle in Exudyn PreStepUserFunction + #**note: reads sensor values, creates message, publish and subscribe to ROS + #**input: + # mbs: mbs (exudyn.exudynCPP.MainSystem), multi-body simulation system from exudyn + # tExu: tExu (float), elapsed time since simulation start + # getData: getData (string), get pose information from 'node' or from 'sensor' + #**author: Martin Sereinig + #**notes: + # reads sensor values, creates message, publish and subscribe to ROS + def PublishTwistUpdate(self, mbs, tExu, getData='node'): + if tExu - self.lastTwistSendTime >= self.rosTwistSendInterval: + self.lastTwistSendTime = tExu + + if getData == 'sensor': + # read current kinematic state and orientation from predefined variables + velocityLinearFromExu = mbs.GetSensorValues(mbs.variables['velt']) + velocityAngularFromExu = mbs.GetSensorValues(mbs.variables['velr']) + # convert data to numpy arrays + velLin = np.array(velocityLinearFromExu) + velAng = np.array(velocityAngularFromExu) + + elif getData == 'node': + nodeDic = mbs.GetNode(mbs.variables['nodeNumber']) + if nodeDic['nodeType'] == 'RigidBodyEP': + # get linear and angular velocity form exudyn via node + velLin= mbs.GetNodeOutput(mbs.variables['nodeNumber'],variableType = exu.OutputVariableType.Velocity) + velAng = mbs.GetNodeOutput(mbs.variables['nodeNumber'],variableType = exu.OutputVariableType.AngularVelocity) + # same could be done to get acceleration from exudyn node + # nUIPLinearAcc= mbs.GetNodeOutput(nUIP,variableType = exu.OutputVariableType.Acceleration) + # nUIPAngularAcc= mbs.GetNodeOutput(nUIP,variableType = exu.OutputVariableType.AngularAcceleration) + + twistExu = np.append(velLin,velAng) + # compose message and publish + msgData = Twist() + # linear velocities + msgData.linear.x = twistExu[0] + msgData.linear.y = twistExu[1] + msgData.linear.z = twistExu[2] + # angular velocities + msgData.angular.x = twistExu[3] + msgData.angular.y = twistExu[4] + msgData.angular.z = twistExu[5] + # write current time into message + self.exuTwistPublisher.publish(msgData) + + #**classFunction: method to be send system state data once per frame/control cycle in Exudyn PreStepUserFunction + #**input: + # mbs: mbs (exudyn.exudynCPP.MainSystem), multi-body simulation system from exudyn + # tExu: tExu (float), simulation time + # systemStateData: systemStateData (list), full Exudyn SystemState + #**author: Martin Sereinig + #**note: collects important exudyn system data and send it to ros-topic + def PublishSystemStateUpdate(self, mbs, tExu): + if tExu - self.lastSystemStateUpdateTime >= self.systemStateUpdateInterval: + self.lastSystemStateUpdateTime = tExu + + systemStateList1d = [] + # publish system state to ros-topic + systemStateData = mbs.systemData.GetSystemState() + + # first entry is current time + systemStateList1d.append(tExu) + + # then systemData itself follows + for array in systemStateData: + # add length of next array + systemStateList1d.append(float(len(array))) + # add array itself + for i in range(len(array)): + systemStateList1d.append(array[i]) + + msg = Float64MultiArray() + msg.data = systemStateList1d # dataList + self.exuSystemstatePublisher.publish(msg) + + diff --git a/main/pythonDev/exudyn/signalProcessing.py b/main/pythonDev/exudyn/signalProcessing.py index 21571ff0..81016ac1 100644 --- a/main/pythonDev/exudyn/signalProcessing.py +++ b/main/pythonDev/exudyn/signalProcessing.py @@ -217,11 +217,11 @@ def GetInterpolatedSignalValue(time, dataArray, timeArray=[], dataArrayIndex = - tB = tA+dt #check if time index is correct: if timeArrayIndex == -1: #1D array - if abs(tA-timeArray[index]) > tolerance or abs(tB-timeArray[index+1]) > tolerance : + if abs(tA-timeArrayNew[index]) > tolerance or abs(tB-timeArrayNew[index+1]) > tolerance : print('Warning: GetInterpolatedSignalValue: timeArray does not seem to have constant sampling rate; use larger tolerance or numpy.interp(...) instead') else: #2D array - if (abs(tA-timeArray[index,timeArrayIndex]) > tolerance or - abs(tB-timeArray[index+1,timeArrayIndex]) > tolerance): + if (abs(tA-timeArrayNew[index,timeArrayIndex]) > tolerance or + abs(tB-timeArrayNew[index+1,timeArrayIndex]) > tolerance): print('Warning: GetInterpolatedSignalValue: timeArray does not seem to have constant sampling rate; use larger tolerance or numpy.interp(...) instead') diff --git a/main/pythonDev/exudyn/solver.py b/main/pythonDev/exudyn/solver.py index b9e6bfb8..5db946bc 100644 --- a/main/pythonDev/exudyn/solver.py +++ b/main/pythonDev/exudyn/solver.py @@ -346,8 +346,8 @@ def RestoreSimulationSettings(simulationSettings, store): # SC = exu.SystemContainer() # mbs = SC.AddSystem() # # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], -# initialVelocities = [2*0,5,0], +# b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], +# initialVelocity = [2*0,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # # @@ -421,8 +421,8 @@ def ComputeLinearizedSystem(mbs, # SC = exu.SystemContainer() # mbs = SC.AddSystem() # # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], -# initialVelocities = [2*0,5,0], +# b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], +# initialVelocity = [2*0,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # # diff --git a/main/setup.py b/main/setup.py index 1e3e82d6..3cd0a6ad 100644 --- a/main/setup.py +++ b/main/setup.py @@ -15,8 +15,8 @@ try: #create single __init__.pyi file from subfiles - oldDir = os.getcwd() - os.chdir(oldDir+'\src\pythonGenerator') + oldDir = os.getcwd().replace('\\','/') + os.chdir(oldDir+'/src/pythonGenerator') fileCS='createStubFiles.py' exec(open(fileCS).read(), globals()) #must be executed in pythonGenerator dir os.chdir(oldDir) @@ -24,8 +24,8 @@ print('WARNING: stub files could not be merged!') #raise ValueError('') -#os.environ["CC"] = "gcc-8" #use gcc-8.4 on linux; does not work on windows -#os.environ["CXX"] = "gcc-8" +#os.environ["CC"] = "gcc-9" #for linux to choose compiler +#os.environ["CXX"] = "gcc-9" startTime = time.time() #print('setup.py: START time:', startTime) @@ -550,7 +550,7 @@ class BuildExt(build_ext): l_opts['unix'] += darwin_opts else: l_opts['unix'] += [ - '-lgomp', #for openmp ==> needed for omp_get_num_threads() + #'-lgomp', #for openmp; not needed any more, as omp_get_num_threads() has been replaced '-lstdc++fs', #for autocreate directories, using std::filesystem from c++17 std ] #warnings not available in clang: @@ -795,6 +795,7 @@ def _single_compile(obj): "Programming Language :: Python :: 3.8", "Programming Language :: Python :: 3.9", "Programming Language :: Python :: 3.10", + "Programming Language :: Python :: 3.11", "Intended Audience :: Science/Research", "License :: OSI Approved :: BSD License", #"Operating System :: Microsoft :: Windows :: Windows 10", diff --git a/main/src/Autogenerated/BeamSectionGeometry.h b/main/src/Autogenerated/BeamSectionGeometry.h index 23a74f97..f6e9b27c 100644 --- a/main/src/Autogenerated/BeamSectionGeometry.h +++ b/main/src/Autogenerated/BeamSectionGeometry.h @@ -4,7 +4,7 @@ * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/CObjectConnectorReevingSystemSprings.h b/main/src/Autogenerated/CObjectConnectorReevingSystemSprings.h index ec79a836..d6fc6f9b 100644 --- a/main/src/Autogenerated/CObjectConnectorReevingSystemSprings.h +++ b/main/src/Autogenerated/CObjectConnectorReevingSystemSprings.h @@ -4,7 +4,7 @@ * * @author Gerstmayr Johannes * @date 2019-07-01 (generated) -* @date 2022-12-01 20:24:37 (last modified) +* @date 2023-07-12 16:03:38 (last modified) * * @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. * @note Bug reports, support and further information: @@ -35,6 +35,7 @@ class CObjectConnectorReevingSystemSpringsParameters // AUTO: Real dampingPerLength; //!< AUTO: axial damping per length [SI:N/(m/s)/m] of rope; the effective damping coefficient of the reeving system is computed as \f$DA/L\f$ in which \f$L\f$ is the current length of the rope Real dampingTorsional; //!< AUTO: torsional damping [SI:Nms] between sheaves; this effect can damp rotations around the rope axis, pairwise between sheaves; this parameter is experimental Real dampingShear; //!< AUTO: damping of shear motion [SI:Ns] between sheaves; this effect can damp motion perpendicular to the rope between each pair of sheaves; this parameter is experimental + Real regularizationForce; //!< AUTO: small regularization force [SI:N] in order to avoid large compressive forces; this regularization force can either be \f$<0\f$ (using a linear tension/compression spring model) or \f$>0\f$, which restricts forces in the rope to be always \f$\ge -F_{reg}\f$. Note that smaller forces lead to problems in implicit integrators and smaller time steps. For explicit integrators, this force can be chosen close to zero. Real referenceLength; //!< AUTO: reference length for computation of roped force Vector3DList sheavesAxes; //!< AUTO: list of local vectors axes of sheaves; vectors refer to rigid body markers given in list of markerNumbers; first and last axes are ignored, as they represent the attachment of the rope ends Vector sheavesRadii; //!< AUTO: radius for each sheave, related to list of markerNumbers and list of sheaveAxes; first and last radii must always be zero. @@ -49,6 +50,7 @@ class CObjectConnectorReevingSystemSpringsParameters // AUTO: dampingPerLength = 0.; dampingTorsional = 0.; dampingShear = 0.; + regularizationForce = 0.1; referenceLength = 0.; sheavesAxes = Vector3DList(); sheavesRadii = Vector(); @@ -59,7 +61,7 @@ class CObjectConnectorReevingSystemSpringsParameters // AUTO: /** *********************************************************************************************** * @class CObjectConnectorReevingSystemSprings -* @brief A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \f$nr\f$ rigid body markers \f$[m_0, \, m_1, \, \ldots, \, m_{nr-1}]\f$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \f$m_{c0}\f$ and \f$m_{c1}\f$ . +* @brief A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). NOTE that the spring can undergo tension AND compression (in order to avoid compression, use a PreStepUserFunction to turn off stiffness and damping in this case!). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \f$nr\f$ rigid body markers \f$[m_0, \, m_1, \, \ldots, \, m_{nr-1}]\f$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \f$m_{c0}\f$ and \f$m_{c1}\f$ . * * @author Gerstmayr Johannes * @date 2019-07-01 (generated) diff --git a/main/src/Autogenerated/CSolverStructures.h b/main/src/Autogenerated/CSolverStructures.h index eefbda65..71ef3213 100644 --- a/main/src/Autogenerated/CSolverStructures.h +++ b/main/src/Autogenerated/CSolverStructures.h @@ -4,7 +4,7 @@ * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -139,7 +139,7 @@ class CSolverTimer // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -263,7 +263,7 @@ class SolverLocalData // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -377,7 +377,7 @@ class SolverIterationData // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -473,7 +473,7 @@ class SolverConvergenceData // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -585,7 +585,7 @@ class SolverOutputData // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/DictionariesGetSet.h b/main/src/Autogenerated/DictionariesGetSet.h index ee699257..529d4c04 100644 --- a/main/src/Autogenerated/DictionariesGetSet.h +++ b/main/src/Autogenerated/DictionariesGetSet.h @@ -2,7 +2,7 @@ // AUTO: Helper file for dictionaries get/set for system structures; generated by Johannes Gerstmayr // AUTO: Generated by Johannes Gerstmayr // AUTO: Used for SimulationSettings and VisualizationSettings -// AUTO: last modified = 2023-06-12 +// AUTO: last modified = 2023-07-17 // AUTO: ++++++++++++++++++++++ #ifndef DICTIONARIESGETSET__H @@ -1074,7 +1074,7 @@ d = py::dict(); //reset local dict d["itemIdentifier"] = std::string(""); //identifier for item d["value"] = data.PyGetPivotThreshold(); - d["type"] = "PReal"; + d["type"] = "UReal"; d["size"] = std::vector{1}; d["description"] = "[ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity"; structureDict["pivotThreshold"] = d; @@ -2190,9 +2190,172 @@ data.showNumbers = py::cast(d["showNumbers"]); } //! AUTO: read access to structure; converting into dictionary + py::dict GetDictionaryWithTypeInfo(const VSettingsSensorTraces& data) { + auto structureDict = py::dict(); + auto d = py::dict(); //local dict + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetLineWidth(); + d["type"] = "UFloat"; + d["size"] = std::vector{1}; + d["description"] = "line width for traces"; + structureDict["lineWidth"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetListOfPositionSensors(); + d["type"] = "IndexArray"; + d["size"] = std::vector{-1}; + d["description"] = "list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown"; + structureDict["listOfPositionSensors"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetListOfTriadSensors(); + d["type"] = "IndexArray"; + d["size"] = std::vector{-1}; + d["description"] = "list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position"; + structureDict["listOfTriadSensors"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetListOfVectorSensors(); + d["type"] = "IndexArray"; + d["size"] = std::vector{-1}; + d["description"] = "list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position"; + structureDict["listOfVectorSensors"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetPositionsShowEvery(); + d["type"] = "PInt"; + d["size"] = std::vector{1}; + d["description"] = "integer value i; out of available sensor data, show every i-th position"; + structureDict["positionsShowEvery"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.sensorsMbsNumber; + d["type"] = "Index"; + d["size"] = std::vector{1}; + d["description"] = "number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number"; + structureDict["sensorsMbsNumber"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showCurrent; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable"; + structureDict["showCurrent"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showFuture; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "show trace future to current visualization state if already computed (e.g. in SolutionViewer)"; + structureDict["showFuture"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showPast; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "show trace previous to current visualization state"; + structureDict["showPast"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showPositionTrace; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True"; + structureDict["showPositionTrace"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showTriads; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "if True, show basis vectors from rotation matrices provided by sensors"; + structureDict["showTriads"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.showVectors; + d["type"] = "bool"; + d["size"] = std::vector{1}; + d["description"] = "if True, show vector quantities according to description in showPositionTrace"; + structureDict["showVectors"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetTraceColors(); + d["type"] = "VectorFloat"; + d["size"] = std::vector{-1}; + d["description"] = "RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue"; + structureDict["traceColors"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.triadSize; + d["type"] = "float"; + d["size"] = std::vector{1}; + d["description"] = "length of triad axes if shown"; + structureDict["triadSize"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetTriadsShowEvery(); + d["type"] = "PInt"; + d["size"] = std::vector{1}; + d["description"] = "integer value i; out of available sensor data, show every i-th triad"; + structureDict["triadsShowEvery"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.vectorScaling; + d["type"] = "float"; + d["size"] = std::vector{1}; + d["description"] = "scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly"; + structureDict["vectorScaling"] = d; + + d = py::dict(); //reset local dict + d["itemIdentifier"] = std::string(""); //identifier for item + d["value"] = data.PyGetVectorsShowEvery(); + d["type"] = "PInt"; + d["size"] = std::vector{1}; + d["description"] = "integer value i; out of available sensor data, show every i-th vector"; + structureDict["vectorsShowEvery"] = d; + + return structureDict; + } + //! AUTO: write access to data structure; converting dictionary d into structure + void SetDictionary(VSettingsSensorTraces& data, const py::dict& d) { + data.lineWidth = py::cast(d["lineWidth"]); + data.listOfPositionSensors = py::cast>(d["listOfPositionSensors"]); + data.listOfTriadSensors = py::cast>(d["listOfTriadSensors"]); + data.listOfVectorSensors = py::cast>(d["listOfVectorSensors"]); + data.positionsShowEvery = py::cast(d["positionsShowEvery"]); + data.sensorsMbsNumber = py::cast(d["sensorsMbsNumber"]); + data.showCurrent = py::cast(d["showCurrent"]); + data.showFuture = py::cast(d["showFuture"]); + data.showPast = py::cast(d["showPast"]); + data.showPositionTrace = py::cast(d["showPositionTrace"]); + data.showTriads = py::cast(d["showTriads"]); + data.showVectors = py::cast(d["showVectors"]); + data.traceColors = py::cast>(d["traceColors"]); + data.triadSize = py::cast(d["triadSize"]); + data.triadsShowEvery = py::cast(d["triadsShowEvery"]); + data.vectorScaling = py::cast(d["vectorScaling"]); + data.vectorsShowEvery = py::cast(d["vectorsShowEvery"]); + } + //! AUTO: read access to structure; converting into dictionary py::dict GetDictionaryWithTypeInfo(const VSettingsSensors& data) { auto structureDict = py::dict(); auto d = py::dict(); //local dict + structureDict["traces"] = GetDictionaryWithTypeInfo(data.traces); d = py::dict(); //reset local dict d["itemIdentifier"] = std::string(""); //identifier for item d["value"] = data.PyGetDefaultColor(); @@ -2237,6 +2400,7 @@ } //! AUTO: write access to data structure; converting dictionary d into structure void SetDictionary(VSettingsSensors& data, const py::dict& d) { + SetDictionary(data.traces, py::cast(d["traces"])); data.defaultColor = py::cast>(d["defaultColor"]); data.defaultSize = py::cast(d["defaultSize"]); data.drawSimplified = py::cast(d["drawSimplified"]); diff --git a/main/src/Autogenerated/MainObjectConnectorReevingSystemSprings.h b/main/src/Autogenerated/MainObjectConnectorReevingSystemSprings.h index c4a2e9cd..dd68ca2d 100644 --- a/main/src/Autogenerated/MainObjectConnectorReevingSystemSprings.h +++ b/main/src/Autogenerated/MainObjectConnectorReevingSystemSprings.h @@ -4,7 +4,7 @@ * * @author Gerstmayr Johannes * @date 2019-07-01 (generated) -* @date 2022-12-01 20:06:47 (last modified) +* @date 2023-07-12 16:00:01 (last modified) * * @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. * @note Bug reports, support and further information: @@ -38,7 +38,7 @@ class MainObjectConnectorReevingSystemSpringsParameters // AUTO: /** *********************************************************************************************** * @class MainObjectConnectorReevingSystemSprings -* @brief A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \f$nr\f$ rigid body markers \f$[m_0, \, m_1, \, \ldots, \, m_{nr-1}]\f$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \f$m_{c0}\f$ and \f$m_{c1}\f$ . +* @brief A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). NOTE that the spring can undergo tension AND compression (in order to avoid compression, use a PreStepUserFunction to turn off stiffness and damping in this case!). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by \f$nr\f$ rigid body markers \f$[m_0, \, m_1, \, \ldots, \, m_{nr-1}]\f$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by \f$m_{c0}\f$ and \f$m_{c1}\f$ . * * @author Gerstmayr Johannes * @date 2019-07-01 (generated) @@ -115,6 +115,7 @@ class MainObjectConnectorReevingSystemSprings: public MainObjectConnector // AUT if (EPyUtils::DictItemExists(d, "dampingPerLength")) { cObjectConnectorReevingSystemSprings->GetParameters().dampingPerLength = py::cast(d["dampingPerLength"]); /* AUTO: read out dictionary and cast to C++ type*/} if (EPyUtils::DictItemExists(d, "dampingTorsional")) { cObjectConnectorReevingSystemSprings->GetParameters().dampingTorsional = py::cast(d["dampingTorsional"]); /* AUTO: read out dictionary and cast to C++ type*/} if (EPyUtils::DictItemExists(d, "dampingShear")) { cObjectConnectorReevingSystemSprings->GetParameters().dampingShear = py::cast(d["dampingShear"]); /* AUTO: read out dictionary and cast to C++ type*/} + if (EPyUtils::DictItemExists(d, "regularizationForce")) { cObjectConnectorReevingSystemSprings->GetParameters().regularizationForce = py::cast(d["regularizationForce"]); /* AUTO: read out dictionary and cast to C++ type*/} if (EPyUtils::DictItemExists(d, "referenceLength")) { cObjectConnectorReevingSystemSprings->GetParameters().referenceLength = py::cast(d["referenceLength"]); /* AUTO: read out dictionary and cast to C++ type*/} EPyUtils::SetVector3DListSafely(d, "sheavesAxes", cObjectConnectorReevingSystemSprings->GetParameters().sheavesAxes); /*! AUTO: safely cast to C++ type*/ cObjectConnectorReevingSystemSprings->GetParameters().sheavesRadii = py::cast>(d["sheavesRadii"]); /* AUTO: read out dictionary and cast to C++ type*/ @@ -138,6 +139,7 @@ class MainObjectConnectorReevingSystemSprings: public MainObjectConnector // AUT d["dampingPerLength"] = (Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingPerLength; //! AUTO: cast variables into python (not needed for standard types) d["dampingTorsional"] = (Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingTorsional; //! AUTO: cast variables into python (not needed for standard types) d["dampingShear"] = (Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingShear; //! AUTO: cast variables into python (not needed for standard types) + d["regularizationForce"] = (Real)cObjectConnectorReevingSystemSprings->GetParameters().regularizationForce; //! AUTO: cast variables into python (not needed for standard types) d["referenceLength"] = (Real)cObjectConnectorReevingSystemSprings->GetParameters().referenceLength; //! AUTO: cast variables into python (not needed for standard types) d["sheavesAxes"] = (PyVector3DList)cObjectConnectorReevingSystemSprings->GetParameters().sheavesAxes; //! AUTO: cast variables into python (not needed for standard types) d["sheavesRadii"] = EPyUtils::Vector2NumPy(cObjectConnectorReevingSystemSprings->GetParameters().sheavesRadii); //! AUTO: cast variables into python (not needed for standard types) @@ -160,6 +162,7 @@ class MainObjectConnectorReevingSystemSprings: public MainObjectConnector // AUT else if (parameterName.compare("dampingPerLength") == 0) { return py::cast((Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingPerLength);} //! AUTO: get parameter else if (parameterName.compare("dampingTorsional") == 0) { return py::cast((Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingTorsional);} //! AUTO: get parameter else if (parameterName.compare("dampingShear") == 0) { return py::cast((Real)cObjectConnectorReevingSystemSprings->GetParameters().dampingShear);} //! AUTO: get parameter + else if (parameterName.compare("regularizationForce") == 0) { return py::cast((Real)cObjectConnectorReevingSystemSprings->GetParameters().regularizationForce);} //! AUTO: get parameter else if (parameterName.compare("referenceLength") == 0) { return py::cast((Real)cObjectConnectorReevingSystemSprings->GetParameters().referenceLength);} //! AUTO: get parameter else if (parameterName.compare("sheavesAxes") == 0) { return py::cast((PyVector3DList)cObjectConnectorReevingSystemSprings->GetParameters().sheavesAxes);} //! AUTO: get parameter else if (parameterName.compare("sheavesRadii") == 0) { return EPyUtils::Vector2NumPy(cObjectConnectorReevingSystemSprings->GetParameters().sheavesRadii);} //! AUTO: get parameter @@ -183,6 +186,7 @@ class MainObjectConnectorReevingSystemSprings: public MainObjectConnector // AUT else if (parameterName.compare("dampingPerLength") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().dampingPerLength = py::cast(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter else if (parameterName.compare("dampingTorsional") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().dampingTorsional = py::cast(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter else if (parameterName.compare("dampingShear") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().dampingShear = py::cast(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter + else if (parameterName.compare("regularizationForce") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().regularizationForce = py::cast(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter else if (parameterName.compare("referenceLength") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().referenceLength = py::cast(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter else if (parameterName.compare("sheavesAxes") == 0) { EPyUtils::SetVector3DListSafely(value, cObjectConnectorReevingSystemSprings->GetParameters().sheavesAxes); /*! AUTO: safely cast to C++ type*/; } //! AUTO: get parameter else if (parameterName.compare("sheavesRadii") == 0) { cObjectConnectorReevingSystemSprings->GetParameters().sheavesRadii = py::cast>(value); /* AUTO: read out dictionary and cast to C++ type*/; } //! AUTO: get parameter diff --git a/main/src/Autogenerated/MainSolver.h b/main/src/Autogenerated/MainSolver.h index 8a982dc0..ea13d64e 100644 --- a/main/src/Autogenerated/MainSolver.h +++ b/main/src/Autogenerated/MainSolver.h @@ -6,7 +6,7 @@ and hereafter you can access all data and functions via 'solver'. * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -91,7 +91,7 @@ and hereafter you can access all data and functions via 'solver'. * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -260,7 +260,7 @@ and hereafter you can access all data and functions via 'solver'. * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/PyStructuralElementsDataStructures.h b/main/src/Autogenerated/PyStructuralElementsDataStructures.h index 96d69d0b..3b9774ed 100644 --- a/main/src/Autogenerated/PyStructuralElementsDataStructures.h +++ b/main/src/Autogenerated/PyStructuralElementsDataStructures.h @@ -4,7 +4,7 @@ * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/Pybind_modules.h b/main/src/Autogenerated/Pybind_modules.h index d264327d..5673fe1e 100644 --- a/main/src/Autogenerated/Pybind_modules.h +++ b/main/src/Autogenerated/Pybind_modules.h @@ -1,6 +1,6 @@ // AUTO: ++++++++++++++++++++++ // AUTO: pybind11 module includes; generated by Johannes Gerstmayr -// AUTO: last modified = 2023-06-12 +// AUTO: last modified = 2023-07-17 // AUTO: ++++++++++++++++++++++ //++++++++++++++++++++++++++++++++ @@ -418,10 +418,36 @@ .def("__repr__", [](const VSettingsLoads &item) { return ""; } ) //!< AUTO: add representation for object based on ostream operator ; // AUTO: end of class definition!!! + //++++++++++++++++++++++++++++++++ + //++++++++++++++++++++++++++++++++ + py::class_(m, "VSettingsSensorTraces", "VSettingsSensorTraces class") // AUTO: + .def(py::init<>()) + .def_property("lineWidth", &VSettingsSensorTraces::PyGetLineWidth, &VSettingsSensorTraces::PySetLineWidth) + .def_property("listOfPositionSensors", &VSettingsSensorTraces::PyGetListOfPositionSensors, &VSettingsSensorTraces::PySetListOfPositionSensors) + .def_property("listOfTriadSensors", &VSettingsSensorTraces::PyGetListOfTriadSensors, &VSettingsSensorTraces::PySetListOfTriadSensors) + .def_property("listOfVectorSensors", &VSettingsSensorTraces::PyGetListOfVectorSensors, &VSettingsSensorTraces::PySetListOfVectorSensors) + .def_property("positionsShowEvery", &VSettingsSensorTraces::PyGetPositionsShowEvery, &VSettingsSensorTraces::PySetPositionsShowEvery) + .def_readwrite("sensorsMbsNumber", &VSettingsSensorTraces::sensorsMbsNumber, "number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number") + .def_readwrite("showCurrent", &VSettingsSensorTraces::showCurrent, "show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable") + .def_readwrite("showFuture", &VSettingsSensorTraces::showFuture, "show trace future to current visualization state if already computed (e.g. in SolutionViewer)") + .def_readwrite("showPast", &VSettingsSensorTraces::showPast, "show trace previous to current visualization state") + .def_readwrite("showPositionTrace", &VSettingsSensorTraces::showPositionTrace, "show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True") + .def_readwrite("showTriads", &VSettingsSensorTraces::showTriads, "if True, show basis vectors from rotation matrices provided by sensors") + .def_readwrite("showVectors", &VSettingsSensorTraces::showVectors, "if True, show vector quantities according to description in showPositionTrace") + .def_property("traceColors", &VSettingsSensorTraces::PyGetTraceColors, &VSettingsSensorTraces::PySetTraceColors) + .def_readwrite("triadSize", &VSettingsSensorTraces::triadSize, "length of triad axes if shown") + .def_property("triadsShowEvery", &VSettingsSensorTraces::PyGetTriadsShowEvery, &VSettingsSensorTraces::PySetTriadsShowEvery) + .def_readwrite("vectorScaling", &VSettingsSensorTraces::vectorScaling, "scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly") + .def_property("vectorsShowEvery", &VSettingsSensorTraces::PyGetVectorsShowEvery, &VSettingsSensorTraces::PySetVectorsShowEvery) + // AUTO: access functions for VSettingsSensorTraces + .def("__repr__", [](const VSettingsSensorTraces &item) { return ""; } ) //!< AUTO: add representation for object based on ostream operator + ; // AUTO: end of class definition!!! + //++++++++++++++++++++++++++++++++ //++++++++++++++++++++++++++++++++ py::class_(m, "VSettingsSensors", "VSettingsSensors class") // AUTO: .def(py::init<>()) + .def_readwrite("traces", &VSettingsSensors::traces, "settings for showing (position) sensor traces and vector plots in the render window") .def_property("defaultColor", &VSettingsSensors::PyGetDefaultColor, &VSettingsSensors::PySetDefaultColor) .def_readwrite("defaultSize", &VSettingsSensors::defaultSize, "global sensor size; if -1.f, sensor size is relative to maxSceneSize") .def_readwrite("drawSimplified", &VSettingsSensors::drawSimplified, "draw sensors with simplified symbols") diff --git a/main/src/Autogenerated/SimulationSettings.h b/main/src/Autogenerated/SimulationSettings.h index 1f7658b3..429f225c 100644 --- a/main/src/Autogenerated/SimulationSettings.h +++ b/main/src/Autogenerated/SimulationSettings.h @@ -4,7 +4,7 @@ * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -162,7 +162,7 @@ class SolutionSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -245,7 +245,7 @@ class NumericalDifferentiationSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -313,7 +313,7 @@ class DiscontinuousSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -443,7 +443,7 @@ class NewtonSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -531,7 +531,7 @@ class GeneralizedAlphaSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -595,7 +595,7 @@ class ExplicitIntegrationSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -816,7 +816,7 @@ class TimeIntegrationSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -985,7 +985,7 @@ class StaticSolverSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1021,7 +1021,7 @@ class LinearSolverSettings // AUTO: // AUTO: access functions //! AUTO: Set function (needed in pybind) for: [ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity - void PySetPivotThreshold(const Real& pivotThresholdInit) { pivotThreshold = EXUstd::GetSafelyPReal(pivotThresholdInit,"pivotThreshold"); } + void PySetPivotThreshold(const Real& pivotThresholdInit) { pivotThreshold = EXUstd::GetSafelyUReal(pivotThresholdInit,"pivotThreshold"); } //! AUTO: Read (Copy) access to: [ONLY available for EXUdense and EigenDense (FullPivot) solver] threshold for dense linear solver, can be used to detect close to singular solutions, setting this to, e.g., 1e-12; solver then reports on equations that are causing close to singularity Real PyGetPivotThreshold() const { return Real(pivotThreshold); } @@ -1051,7 +1051,7 @@ class LinearSolverSettings // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1156,7 +1156,7 @@ class Parallel // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/VisualizationSettings.h b/main/src/Autogenerated/VisualizationSettings.h index 6b7b1c02..0fef0acf 100644 --- a/main/src/Autogenerated/VisualizationSettings.h +++ b/main/src/Autogenerated/VisualizationSettings.h @@ -4,7 +4,7 @@ * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -207,7 +207,7 @@ class VSettingsGeneral // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -299,7 +299,7 @@ class VSettingsContour // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -390,7 +390,7 @@ class VSettingsNodes // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -484,7 +484,7 @@ class VSettingsBeams // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -545,7 +545,7 @@ class VSettingsKinematicTree // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -623,7 +623,7 @@ class VSettingsBodies // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -712,7 +712,7 @@ class VSettingsConnectors // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -781,7 +781,7 @@ class VSettingsMarkers // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -853,13 +853,153 @@ class VSettingsLoads // AUTO: }; +/** *********************************************************************************************** +* @class VSettingsSensorTraces +* @brief Visualization settings for traces of sensors. Note that a large number of time points (influenced by simulationSettings.solutionSettings.sensorsWritePeriod) may lead to slow graphics. +* +* @author AUTO: Gerstmayr Johannes +* @date AUTO: 2019-07-01 (generated) +* @date AUTO: 2023-07-17 (last modfied) +* +* @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. +* @note Bug reports, support and further information: + - email: johannes.gerstmayr@uibk.ac.at + - weblink: missing + +************************************************************************************************ **/ +#include + +#include "Utilities/ReleaseAssert.h" +#include "Utilities/BasicDefinitions.h" +#include "Main/OutputVariable.h" +#include "Linalg/BasicLinalg.h" + +class VSettingsSensorTraces // AUTO: +{ +public: // AUTO: + float lineWidth; //!< AUTO: line width for traces + ArrayIndex listOfPositionSensors; //!< AUTO: list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown + ArrayIndex listOfTriadSensors; //!< AUTO: list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position + ArrayIndex listOfVectorSensors; //!< AUTO: list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position + Index positionsShowEvery; //!< AUTO: integer value i; out of available sensor data, show every i-th position + Index sensorsMbsNumber; //!< AUTO: number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number + bool showCurrent; //!< AUTO: show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable + bool showFuture; //!< AUTO: show trace future to current visualization state if already computed (e.g. in SolutionViewer) + bool showPast; //!< AUTO: show trace previous to current visualization state + bool showPositionTrace; //!< AUTO: show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True + bool showTriads; //!< AUTO: if True, show basis vectors from rotation matrices provided by sensors + bool showVectors; //!< AUTO: if True, show vector quantities according to description in showPositionTrace + ArrayFloat traceColors; //!< AUTO: RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue + float triadSize; //!< AUTO: length of triad axes if shown + Index triadsShowEvery; //!< AUTO: integer value i; out of available sensor data, show every i-th triad + float vectorScaling; //!< AUTO: scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly + Index vectorsShowEvery; //!< AUTO: integer value i; out of available sensor data, show every i-th vector + + +public: // AUTO: + //! AUTO: default constructor with parameter initialization + VSettingsSensorTraces() + { + lineWidth = 2.f; + listOfPositionSensors = ArrayIndex(); + listOfTriadSensors = ArrayIndex(); + listOfVectorSensors = ArrayIndex(); + positionsShowEvery = 1; + sensorsMbsNumber = 0; + showCurrent = true; + showFuture = false; + showPast = true; + showPositionTrace = false; + showTriads = false; + showVectors = false; + traceColors = ArrayFloat({0.2f,0.2f,0.2f,1.f, 0.8f,0.2f,0.2f,1.f, 0.2f,0.8f,0.2f,1.f, 0.2f,0.2f,0.8f,1.f, 0.2f,0.8f,0.8f,1.f, 0.8f,0.2f,0.8f,1.f, 0.8f,0.4f,0.1f,1.f}); + triadSize = 0.1f ; + triadsShowEvery = 1; + vectorScaling = 0.01f; + vectorsShowEvery = 1; + }; + + // AUTO: access functions + //! AUTO: Set function (needed in pybind) for: line width for traces + void PySetLineWidth(const float& lineWidthInit) { lineWidth = EXUstd::GetSafelyUFloat(lineWidthInit,"lineWidth"); } + //! AUTO: Read (Copy) access to: line width for traces + float PyGetLineWidth() const { return float(lineWidth); } + + //! AUTO: Set function (needed in pybind) for: list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown + void PySetListOfPositionSensors(const std::vector& listOfPositionSensorsInit) { listOfPositionSensors = listOfPositionSensorsInit; } + //! AUTO: Read (Copy) access to: list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown + std::vector PyGetListOfPositionSensors() const { return std::vector(listOfPositionSensors); } + + //! AUTO: Set function (needed in pybind) for: list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position + void PySetListOfTriadSensors(const std::vector& listOfTriadSensorsInit) { listOfTriadSensors = listOfTriadSensorsInit; } + //! AUTO: Read (Copy) access to: list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position + std::vector PyGetListOfTriadSensors() const { return std::vector(listOfTriadSensors); } + + //! AUTO: Set function (needed in pybind) for: list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position + void PySetListOfVectorSensors(const std::vector& listOfVectorSensorsInit) { listOfVectorSensors = listOfVectorSensorsInit; } + //! AUTO: Read (Copy) access to: list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position + std::vector PyGetListOfVectorSensors() const { return std::vector(listOfVectorSensors); } + + //! AUTO: Set function (needed in pybind) for: integer value i; out of available sensor data, show every i-th position + void PySetPositionsShowEvery(const Index& positionsShowEveryInit) { positionsShowEvery = EXUstd::GetSafelyPInt(positionsShowEveryInit,"positionsShowEvery"); } + //! AUTO: Read (Copy) access to: integer value i; out of available sensor data, show every i-th position + Index PyGetPositionsShowEvery() const { return Index(positionsShowEvery); } + + //! AUTO: Set function (needed in pybind) for: RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue + void PySetTraceColors(const std::vector& traceColorsInit) { traceColors = traceColorsInit; } + //! AUTO: Read (Copy) access to: RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue + std::vector PyGetTraceColors() const { return std::vector(traceColors); } + + //! AUTO: Set function (needed in pybind) for: integer value i; out of available sensor data, show every i-th triad + void PySetTriadsShowEvery(const Index& triadsShowEveryInit) { triadsShowEvery = EXUstd::GetSafelyPInt(triadsShowEveryInit,"triadsShowEvery"); } + //! AUTO: Read (Copy) access to: integer value i; out of available sensor data, show every i-th triad + Index PyGetTriadsShowEvery() const { return Index(triadsShowEvery); } + + //! AUTO: Set function (needed in pybind) for: integer value i; out of available sensor data, show every i-th vector + void PySetVectorsShowEvery(const Index& vectorsShowEveryInit) { vectorsShowEvery = EXUstd::GetSafelyPInt(vectorsShowEveryInit,"vectorsShowEvery"); } + //! AUTO: Read (Copy) access to: integer value i; out of available sensor data, show every i-th vector + Index PyGetVectorsShowEvery() const { return Index(vectorsShowEvery); } + + //! AUTO: print function used in ostream operator (print is virtual and can thus be overloaded) + virtual void Print(std::ostream& os) const + { + os << "VSettingsSensorTraces" << ":\n"; + os << " lineWidth = " << lineWidth << "\n"; + os << " listOfPositionSensors = " << listOfPositionSensors << "\n"; + os << " listOfTriadSensors = " << listOfTriadSensors << "\n"; + os << " listOfVectorSensors = " << listOfVectorSensors << "\n"; + os << " positionsShowEvery = " << positionsShowEvery << "\n"; + os << " sensorsMbsNumber = " << sensorsMbsNumber << "\n"; + os << " showCurrent = " << showCurrent << "\n"; + os << " showFuture = " << showFuture << "\n"; + os << " showPast = " << showPast << "\n"; + os << " showPositionTrace = " << showPositionTrace << "\n"; + os << " showTriads = " << showTriads << "\n"; + os << " showVectors = " << showVectors << "\n"; + os << " traceColors = " << traceColors << "\n"; + os << " triadSize = " << triadSize << "\n"; + os << " triadsShowEvery = " << triadsShowEvery << "\n"; + os << " vectorScaling = " << vectorScaling << "\n"; + os << " vectorsShowEvery = " << vectorsShowEvery << "\n"; + os << "\n"; + } + + friend std::ostream& operator<<(std::ostream& os, const VSettingsSensorTraces& object) + { + object.Print(os); + return os; + } + +}; + + /** *********************************************************************************************** * @class VSettingsSensors * @brief Visualization settings for sensors. * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -877,6 +1017,7 @@ class VSettingsLoads // AUTO: class VSettingsSensors // AUTO: { public: // AUTO: + VSettingsSensorTraces traces; //!< AUTO: settings for showing (position) sensor traces and vector plots in the render window Float4 defaultColor; //!< AUTO: default cRGB color for sensors; 4th value is alpha-transparency float defaultSize; //!< AUTO: global sensor size; if -1.f, sensor size is relative to maxSceneSize bool drawSimplified; //!< AUTO: draw sensors with simplified symbols @@ -905,6 +1046,7 @@ class VSettingsSensors // AUTO: virtual void Print(std::ostream& os) const { os << "VSettingsSensors" << ":\n"; + os << " traces = " << traces << "\n"; os << " defaultColor = " << defaultColor << "\n"; os << " defaultSize = " << defaultSize << "\n"; os << " drawSimplified = " << drawSimplified << "\n"; @@ -928,7 +1070,7 @@ class VSettingsSensors // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1014,7 +1156,7 @@ class VSettingsContact // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1112,7 +1254,7 @@ class VSettingsWindow // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1186,7 +1328,7 @@ class VSettingsDialogs // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1458,7 +1600,7 @@ class VSettingsOpenGL // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1560,7 +1702,7 @@ class VSettingsExportImages // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1621,7 +1763,7 @@ class VSettingsOpenVR // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: @@ -1763,7 +1905,7 @@ class VSettingsInteractive // AUTO: * * @author AUTO: Gerstmayr Johannes * @date AUTO: 2019-07-01 (generated) -* @date AUTO: 2023-06-12 (last modfied) +* @date AUTO: 2023-07-17 (last modfied) * * @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. * @note Bug reports, support and further information: diff --git a/main/src/Autogenerated/pybind_manual_classes.h b/main/src/Autogenerated/pybind_manual_classes.h index e34ff384..3a4df5b4 100644 --- a/main/src/Autogenerated/pybind_manual_classes.h +++ b/main/src/Autogenerated/pybind_manual_classes.h @@ -1,6 +1,6 @@ // AUTO: ++++++++++++++++++++++ // AUTO: pybind11 manual module includes; generated by Johannes Gerstmayr -// AUTO: last modified = 2023-06-12 +// AUTO: last modified = 2023-07-19 // AUTO: ++++++++++++++++++++++ // pybinding to enum classes: @@ -363,6 +363,10 @@ item.PySetItem(index, vector); }, "set list item 'index' with data, write: data[index] = ...") .def("__getitem__", [](const PyVector3DList &item, Index index) { return py::array_t(item[index].NumberOfItems(), item[index].GetDataPointer()); }, "get copy of list item with 'index' as vector") + .def("__copy__", [](const PyVector3DList &item) { + return PyVector3DList(item); }, "copy method to be used for copy.copy(...); in fact does already deep copy") + .def("__deepcopy__", [](const PyVector3DList &item, py::dict) { + return PyVector3DList(item); }, "memo"_a, "deepcopy method to be used for copy.copy(...)") .def("__repr__", [](const PyVector3DList &item) { return EXUstd::ToString(item.GetPythonObject()); }, "return the string representation of the Vector3DList data, e.g.: print(data)") ; // end of PyVector3DList pybind definitions @@ -379,6 +383,10 @@ item.PySetItem(index, vector); }, "set list item 'index' with data, write: data[index] = ...") .def("__getitem__", [](const PyVector2DList &item, Index index) { return py::array_t(item[index].NumberOfItems(), item[index].GetDataPointer()); }, "get copy of list item with 'index' as vector") + .def("__copy__", [](const PyVector2DList &item) { + return PyVector2DList(item); }, "copy method to be used for copy.copy(...); in fact does already deep copy") + .def("__deepcopy__", [](const PyVector2DList &item, py::dict) { + return PyVector2DList(item); }, "memo"_a, "deepcopy method to be used for copy.copy(...)") .def("__repr__", [](const PyVector2DList &item) { return EXUstd::ToString(item.GetPythonObject()); }, "return the string representation of the Vector2DList data, e.g.: print(data)") ; // end of PyVector2DList pybind definitions @@ -395,6 +403,10 @@ item.PySetItem(index, vector); }, "set list item 'index' with data, write: data[index] = ...") .def("__getitem__", [](const PyVector6DList &item, Index index) { return py::array_t(item[index].NumberOfItems(), item[index].GetDataPointer()); }, "get copy of list item with 'index' as vector") + .def("__copy__", [](const PyVector6DList &item) { + return PyVector6DList(item); }, "copy method to be used for copy.copy(...); in fact does already deep copy") + .def("__deepcopy__", [](const PyVector6DList &item, py::dict) { + return PyVector6DList(item); }, "memo"_a, "deepcopy method to be used for copy.copy(...)") .def("__repr__", [](const PyVector6DList &item) { return EXUstd::ToString(item.GetPythonObject()); }, "return the string representation of the Vector6DList data, e.g.: print(data)") ; // end of PyVector6DList pybind definitions diff --git a/main/src/Autogenerated/versionCpp.cpp b/main/src/Autogenerated/versionCpp.cpp index bc089c7c..21ca4671 100644 --- a/main/src/Autogenerated/versionCpp.cpp +++ b/main/src/Autogenerated/versionCpp.cpp @@ -1,7 +1,7 @@ // AUTO: ++++++++++++++++++++++ // AUTO: version info automatically generated by tracker; generated by Johannes Gerstmayr -// AUTO: last modified = 2023-06-12 +// AUTO: last modified = 2023-07-19 // AUTO: ++++++++++++++++++++++ namespace EXUstd { - const char* exudynVersion = "1.6.164.dev1"; + const char* exudynVersion = "1.7.0"; } diff --git a/main/src/Graphics/GlfwClient.cpp b/main/src/Graphics/GlfwClient.cpp index f323c822..30d9d287 100644 --- a/main/src/Graphics/GlfwClient.cpp +++ b/main/src/Graphics/GlfwClient.cpp @@ -133,6 +133,11 @@ ResizableArray* GlfwRenderer::graphicsDataList = nullptr; VisualizationSettings* GlfwRenderer::visSettings = nullptr; VisualizationSystemContainerBase* GlfwRenderer::basicVisualizationSystemContainer = nullptr; //++++++++++++++++++++++++++++++++++++++++++ +Vector3DList GlfwRenderer::sensorTracePositions; +Vector3DList GlfwRenderer::sensorTraceVectors; //synchronized with triads +Matrix3DList GlfwRenderer::sensorTraceTriads; //synchronized with vectors +Vector GlfwRenderer::sensorTraceValues; //temporary storage for current sensor data +//++++++++++++++++++++++++++++++++++++++++++ GlfwRenderer::GlfwRenderer() @@ -1209,6 +1214,8 @@ void GlfwRenderer::SetViewOnMouseCursor(GLdouble x, GLdouble y, GLdouble delX, G //! function to evaluate selection of items, show message, return dictionary string bool GlfwRenderer::MouseSelect(GLFWwindow* window, Index mouseX, Index mouseY, Index& itemID) { + //if (verboseRenderer) { std::cout << "Mouse select" << std::flush; } + MouseSelectOpenGL(window, (Index)stateMachine.selectionMouseCoordinates[0], (Index)stateMachine.selectionMouseCoordinates[1], @@ -1217,6 +1224,8 @@ bool GlfwRenderer::MouseSelect(GLFWwindow* window, Index mouseX, Index mouseY, I const Real timeOutHighlightItem = 0.5; //just short to exactly see object ItemID2IndexType(itemID, stateMachine.highlightIndex, stateMachine.highlightType, stateMachine.highlightMbsNumber); + //if (verboseRenderer) { std::cout << " select=" << EXUstd::ToString(itemID) << std::flush; } + //PrintDelayed("itemID=" + EXUstd::ToString(itemID)); if (stateMachine.highlightType != ItemType::_None && stateMachine.highlightIndex != invalidIndex) @@ -1250,6 +1259,7 @@ void GlfwRenderer::MouseSelectOpenGL(GLFWwindow* window, Index mouseX, Index mou //put into separate function, for Render(...) int width, height; + //if (verboseRenderer) { std::cout << " MouseSelectOpenGL" << std::flush; } glfwGetFramebufferSize(window, &width, &height); //rendererOut << "current window: width=" << width << ", height=" << height << "\n"; @@ -1261,9 +1271,12 @@ void GlfwRenderer::MouseSelectOpenGL(GLFWwindow* window, Index mouseX, Index mou //++++++++++++++++++++++++++++++++++++++++ + //if (verboseRenderer) { std::cout << " glSelectBuffer" << std::flush; } const Index selectBufferSize = 10000; //size for number of objects picked at same time GLuint selectBuffer[selectBufferSize]; glSelectBuffer(selectBufferSize, selectBuffer); + + //if (verboseRenderer) { std::cout << " glRenderMode" << std::flush; } glRenderMode(GL_SELECT); GLint viewport[4]; @@ -1278,6 +1291,7 @@ void GlfwRenderer::MouseSelectOpenGL(GLFWwindow* window, Index mouseX, Index mou glClearStencil(0); glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT | GL_STENCIL_BUFFER_BIT); + //if (verboseRenderer) { std::cout << " glMatrixMode" << std::flush; } //++++++++++++++++++++++++++++++++++++++++ //from Render(...) glMatrixMode(GL_PROJECTION); @@ -1302,26 +1316,32 @@ void GlfwRenderer::MouseSelectOpenGL(GLFWwindow* window, Index mouseX, Index mou //++++++++++++++++++++++++++++++++++++++++ //add one name in hierarchie and then draw scene with names + //if (verboseRenderer) { std::cout << " glInitNames" << std::flush; } glInitNames(); + //if (verboseRenderer) { std::cout << " glPushName" << std::flush; } glPushName(1); const bool selectionMode = true; + //if (verboseRenderer) { std::cout << " RenderGraphicsData" << std::flush; } RenderGraphicsData(selectionMode); //render scene with names //glCallList (filledlist); glPopName(); //++++++++++++++++++++++++++++++++++++++++ + //if (verboseRenderer) { std::cout << " glPopMatrix" << std::flush; } glMatrixMode(GL_PROJECTION); glPopMatrix(); glMatrixMode(GL_MODELVIEW); glPopMatrix(); + //if (verboseRenderer) { std::cout << " glRenderMode" << std::flush; } Index numberOfItemsFound = glRenderMode(GL_RENDER); //++++++++++++++++++++++++++++++++++++++++ //evaluate items: //rendererOut << "number of found items = " << numberOfItemsFound << "\n"; + //if (verboseRenderer) { std::cout << " evaluate" << std::flush; } Index itemIDnearest = 0; GLuint minimalDepth = 0; //clip other items that are closer @@ -1762,7 +1782,7 @@ void GlfwRenderer::RunLoop() FinishRunLoop(); } -void GlfwRenderer::DoRendererTasks() +void GlfwRenderer::DoRendererTasks(bool graphicsUpdateAndRender) { Real updateInterval = (Real)(visSettings->general.graphicsUpdateInterval); Real time = EXUstd::GetTimeInSeconds(); @@ -1779,7 +1799,10 @@ void GlfwRenderer::DoRendererTasks() } - if (useMultiThreadedRendering || (time >= lastGraphicsUpdate + updateInterval) || GetCallBackSignal()) + if (useMultiThreadedRendering || + (time >= lastGraphicsUpdate + updateInterval) || + GetCallBackSignal() || + graphicsUpdateAndRender) { basicVisualizationSystemContainer->UpdateGraphicsData(); bool maxSceneComputed = false; @@ -1852,7 +1875,7 @@ void GlfwRenderer::FinishRunLoop() } //! run renderer idle for certain amount of time; use this for single-threaded, interactive animations; waitSeconds==-1 waits forever -void GlfwRenderer::DoRendererIdleTasks(Real waitSeconds) +void GlfwRenderer::DoRendererIdleTasks(Real waitSeconds, bool graphicsUpdateAndRender) { Real time = EXUstd::GetTimeInSeconds(); bool continueTask = true; @@ -1866,7 +1889,7 @@ void GlfwRenderer::DoRendererIdleTasks(Real waitSeconds) { if (!useMultiThreadedRendering) { - DoRendererTasks(); + DoRendererTasks(graphicsUpdateAndRender); } else { @@ -2378,7 +2401,8 @@ void GlfwRenderer::Render3Dobjects(int screenWidth, int screenHeight, float& scr SetModelRotationTranslation(); - RenderGraphicsData(); + RenderSensorTraces(); + RenderGraphicsData(); @@ -2735,6 +2759,148 @@ void GlfwRenderer::RenderGraphicsDataText(GraphicsData* data, Index lastItemID, } +//Index cnt0 = 0; + +//draw sensor traces +//NOTE: this function could be moved to VisualizationSystem to create this data only once (but what happens for animations?)? +void GlfwRenderer::RenderSensorTraces() +{ + if (visSettings->sensors.traces.showPositionTrace || + visSettings->sensors.traces.showVectors || + visSettings->sensors.traces.showTriads) + { + float factOffset = 1.f*state->maxSceneSize; + if (state->zoom != 0.f) { factOffset *= 1.f / state->zoom; } + + glPolygonMode(GL_FRONT_AND_BACK, GL_FILL); + glPolygonOffset(visSettings->openGL.polygonOffset*factOffset, visSettings->openGL.polygonOffset*factOffset); // + glEnable(GL_POLYGON_OFFSET_FILL); + glDisable(GL_POLYGON_OFFSET_LINE); + + glPolygonMode(GL_FRONT_AND_BACK, GL_LINE); + if (visSettings->openGL.lineSmooth) { glEnable(GL_LINE_SMOOTH); } + + const ArrayIndex& positionSensors = visSettings->sensors.traces.listOfPositionSensors; + const ArrayIndex& vectorSensors = visSettings->sensors.traces.listOfVectorSensors; + const ArrayIndex& triadSensors = visSettings->sensors.traces.listOfTriadSensors; + + glLineWidth(visSettings->sensors.traces.lineWidth); + + Index positionsShowEvery = EXUstd::Maximum(1,visSettings->sensors.traces.positionsShowEvery); //max in order to avoid crash in case of 0 or negative numbers + Index vectorsShowEvery = EXUstd::Maximum(1, visSettings->sensors.traces.vectorsShowEvery); + Index triadsShowEvery = EXUstd::Maximum(1, visSettings->sensors.traces.triadsShowEvery); + + const ArrayFloat& edgeColors = visSettings->sensors.traces.traceColors; + + bool showVectors = visSettings->sensors.traces.showVectors && (positionSensors.NumberOfItems() == vectorSensors.NumberOfItems()); + bool showTriads = visSettings->sensors.traces.showTriads && (positionSensors.NumberOfItems() == triadSensors.NumberOfItems()); + + Real vectorScaling = (Real)visSettings->sensors.traces.vectorScaling; + float triadSize = visSettings->sensors.traces.triadSize; + // if no sensors, do other approach: + //while list with stop criteria + //GetSensorsPositionsVectorsLists returns true if further sensors available + //std::cout << "ST" << showTriads << ", PL" << positionSensors.NumberOfItems() + // << ", TL" << triadSensors.NumberOfItems() << "\n"; + + + Index i = 0; + bool returnValue = true; + while ((positionSensors.NumberOfItems() > 0 && i < positionSensors.NumberOfItems()) || (positionSensors.NumberOfItems() == 0 && returnValue) ) + { + Float4 edgeColor({ 0.,0.,0.,1. }); //Default + if (edgeColors.NumberOfItems() >= (i + 1) * 4) + { + for (Index j = 0; j < 4; j++) + { + edgeColor[j] = edgeColors[i * 4 + j]; + } + } + + Index positionSensorIndex = i; + Index vectorSensorIndex = -1; + Index triadSensorIndex = -1; + if (i < positionSensors.NumberOfItems()) { positionSensorIndex = positionSensors[i]; } + if (i < vectorSensors.NumberOfItems() && showVectors) { vectorSensorIndex = vectorSensors[i]; } + if (i < triadSensors.NumberOfItems() && showTriads) { triadSensorIndex = triadSensors[i]; } + + //get sensor data + returnValue = basicVisualizationSystemContainer->GetSensorsPositionsVectorsLists(visSettings->sensors.traces.sensorsMbsNumber, positionSensorIndex, + vectorSensorIndex, triadSensorIndex, sensorTracePositions, sensorTraceVectors, sensorTraceTriads, sensorTraceValues, + visSettings->sensors.traces); + + if (visSettings->sensors.traces.showPositionTrace)// && sensorTracePositions.NumberOfItems() > 1) + { + glBegin(GL_LINE_STRIP); //list of single points to define lines + glColor4f(edgeColor[0], edgeColor[1], edgeColor[2], edgeColor[3]); + + for (Index j = 0; j < sensorTracePositions.NumberOfItems(); j++) + { + if (j % positionsShowEvery == 0 || j == sensorTracePositions.NumberOfItems() - 1) + { + const Vector3D& p = sensorTracePositions[j]; + glVertex3f((float)p[0], (float)p[1], (float)p[2]); + } + } + glEnd(); //GL_LINE_STRIP + } + + if ((visSettings->sensors.traces.showVectors && sensorTraceVectors.NumberOfItems() != 0) || + (visSettings->sensors.traces.showTriads && sensorTraceTriads.NumberOfItems() != 0) ) + { + glBegin(GL_LINES); + //if (visSettings->openGL.enableLighting) { glEnable(GL_LIGHTING); } //only enabled when drawing triangle faces + //glColorMaterial(GL_FRONT_AND_BACK, GL_AMBIENT_AND_DIFFUSE); + for (Index j = 0; j < sensorTracePositions.NumberOfItems(); j++) + { + if (j < sensorTraceVectors.NumberOfItems()) + { + if (j % vectorsShowEvery == 0 || j == sensorTraceVectors.NumberOfItems() - 1) + { + const Vector3D& p = sensorTracePositions[j]; + const Vector3D& v = sensorTraceVectors[j]; + glColor4f(edgeColor[0], edgeColor[1], edgeColor[2], edgeColor[3]); + glVertex3f((float)p[0], (float)p[1], (float)p[2]); + glVertex3f((float)(p[0] + vectorScaling * v[0]), + (float)(p[1] + vectorScaling * v[1]), + (float)(p[2] + vectorScaling * v[2])); + } + } + if (j < sensorTraceTriads.NumberOfItems()) + { + if (j % triadsShowEvery == 0 || j == sensorTraceTriads.NumberOfItems() - 1) + { + float f = triadSize; + Float3 p({ (float)sensorTracePositions[j][0], + (float)sensorTracePositions[j][1], + (float)sensorTracePositions[j][2] }); + const Matrix3D& m = sensorTraceTriads[j]; + //glColor4f(edgeColor[0], edgeColor[1], edgeColor[2], edgeColor[3]); //set back to trace color! + glColor4f(1.f, 0, 0, edgeColor[3]); + glVertex3f(p[0], p[1], p[2]); + glVertex3f(p[0] + f * (float)m(0, 0), p[1] + f * (float)m(1, 0), p[2] + f * (float)m(2, 0)); + + glColor4f(0, 1.f, 0, edgeColor[3]); + glVertex3f(p[0], p[1], p[2]); + glVertex3f(p[0] + f * (float)m(0, 1), p[1] + f * (float)m(1, 1), p[2] + f * (float)m(2, 1)); + + glColor4f(0, 0, 1.f, edgeColor[3]); + glVertex3f(p[0], p[1], p[2]); + glVertex3f(p[0] + f * (float)m(0, 2), p[1] + f * (float)m(1, 2), p[2] + f * (float)m(2, 2)); + } + } + } + glEnd(); //GL_LINES + + //if (visSettings->openGL.enableLighting) { glDisable(GL_LIGHTING); } //only enabled when drawing triangle faces + } + + i++; + } + if (visSettings->openGL.lineSmooth) { glDisable(GL_LINE_SMOOTH); } + + } +} void GlfwRenderer::RenderGraphicsData(bool selectionMode) { diff --git a/main/src/Graphics/GlfwClient.h b/main/src/Graphics/GlfwClient.h index d714bc41..664a4ddd 100644 --- a/main/src/Graphics/GlfwClient.h +++ b/main/src/Graphics/GlfwClient.h @@ -121,6 +121,7 @@ class GlfwRenderer static std::atomic_flag renderFunctionRunning; //!< semaphore to check if Render(...) function is currently running (prevent from calling twice) static std::atomic_flag showMessageSemaphore; //!< semaphore to prevent calling ShowMessage twice + //+++++++++++++++++++++++++++++++++++++++++ static BitmapFont bitmapFont; //!< bitmap font for regular texts and for textured fonts, initialized upon start of renderer static float fontScale; //!< monitor scaling factor from windows, to scale fonts @@ -151,7 +152,13 @@ class GlfwRenderer static ResizableArray* graphicsDataList; //!< link to graphics data; only works for one MainSystem, but could also be realized for several systems static VisualizationSettings* visSettings; //!< link to visualization settings static VisualizationSystemContainerBase* basicVisualizationSystemContainer; - //+++++++++++++++++++++++++++++++++++++++++ + //+++++++++++++++++++++++++++++++++++++++++ + //for sensor traces: + static Vector3DList sensorTracePositions; + static Vector3DList sensorTraceVectors; //synchronized with triads + static Matrix3DList sensorTraceTriads; //synchronized with vectors + static Vector sensorTraceValues; //temporary storage for current sensor data + //+++++++++++++++++++++++++++++++++++++++++ public: GlfwRenderer(); @@ -291,7 +298,7 @@ class GlfwRenderer static void ShowMessage(const STDstring& str, Real timeout = 0); //! run renderer idle for certain amount of time; use this for single-threaded, interactive animations; waitSeconds==-1 waits forever - static void DoRendererIdleTasks(Real waitSeconds); + static void DoRendererIdleTasks(Real waitSeconds, bool graphicsUpdateAndRender=false); //! check if separate thread used: static bool UseMultiThreadedRendering() { return useMultiThreadedRendering; } @@ -372,7 +379,8 @@ class GlfwRenderer static void RunLoop(); //! tasks which are regularly called by RunLoop(), used if no separate thread used in GLFW; use wait in seconds to do this - static void DoRendererTasks(); + //! for single-threaded renderer, an immediate rendering can be requested + static void DoRendererTasks(bool graphicsUpdateAndRender = false); //! tasks which are done if renderer is shut down static void FinishRunLoop(); @@ -398,6 +406,9 @@ class GlfwRenderer //! Render particulary the graphics data of multibody system; selectionMode==true adds names static void RenderGraphicsData(bool selectionMode = false); + //! render sensor traces if activated and available + static void RenderSensorTraces(); + //! Render particulary the text of multibody system; selectionMode==true adds names static void RenderGraphicsDataText(GraphicsData* data, Index lastItemID, bool highlight, Index highlightID, Float4 highlightColor2, Float4 otherColor2, bool selectionMode=false); diff --git a/main/src/Graphics/VisualizationSystemContainer.cpp b/main/src/Graphics/VisualizationSystemContainer.cpp index 2287c092..fe15fa94 100644 --- a/main/src/Graphics/VisualizationSystemContainer.cpp +++ b/main/src/Graphics/VisualizationSystemContainer.cpp @@ -107,11 +107,32 @@ void VisualizationSystemContainer::RedrawAndSaveImage() Index timerMilliseconds = settings.exportImages.saveImageTimeOut / timeOut; if (timerMilliseconds == 0) { timerMilliseconds = 1; } //min wait time per iteration +#ifdef USE_GLFW_GRAPHICS + if (!glfwRenderer.UseMultiThreadedRendering()) //otherwise, user functions are anyway processed + { + //in this case, we need to update graphics, otherwise it is not saved + + glfwRenderer.DoRendererIdleTasks(0., true); //request immediate redraw + //now image should be saved ... + } +#endif + //now wait until the saveImage flag has been deleted by the current redraw operation Index i = 0; while (i++ < timeOut && (saveImageOpenGL || saveImage)) //wait timeOut*timerMilliseconds seconds for last operation to finish { std::this_thread::sleep_for(std::chrono::milliseconds(timerMilliseconds)); +#ifdef USE_GLFW_GRAPHICS + if (glfwRenderer.UseMultiThreadedRendering()) //otherwise, user functions are anyway processed + { + //Needed ?: PyProcessExecuteQueue(); //use time to execute incoming python tasks + //process user functions + for (auto item : visualizationSystems) + { + item->postProcessData->ProcessUserFunctionDrawing(); //check if user functions to be drawn and do user function evaluations + } + } +#endif } if (saveImageOpenGL || saveImage) { @@ -285,6 +306,7 @@ std::string VisualizationSystemContainer::GetComputationMessage(bool solverInfor return std::string(); } +//get marker position and orientation void VisualizationSystemContainer::GetMarkerPositionOrientation(Index markerNumber, Index mbsNumber, Vector3D& position, Matrix3D& orientation, bool& hasPosition, bool& hasOrientation) { position = Vector3D(0); @@ -313,6 +335,115 @@ void VisualizationSystemContainer::GetMarkerPositionOrientation(Index markerNumb } +//get sensor data list (if available) +bool VisualizationSystemContainer::GetSensorsPositionsVectorsLists(Index mbsNumber, Index positionSensorIndex, Index vectorSensorIndex, Index triadSensorIndex, + Vector3DList& sensorTracePositions, Vector3DList& sensorTraceVectors, Matrix3DList& sensorTraceTriads, Vector sensorTraceValues, + const VSettingsSensorTraces& traces) +{ + sensorTracePositions.SetNumberOfItems(0); + sensorTraceVectors.SetNumberOfItems(0); + sensorTraceTriads.SetNumberOfItems(0); + + //bool showVectors, bool showTriads, bool showPast, bool showFuture, bool showCurrent + + if (mbsNumber >= 0 && mbsNumber < NumberOFMainSystemsBacklink()) + { + CSystem* cSystem = GetMainSystemBacklink(mbsNumber)->GetCSystem(); + Real time = cSystem->GetSystemData().GetCData().GetVisualization().GetTime(); + if (positionSensorIndex >= 0 && positionSensorIndex < cSystem->GetSystemData().GetCSensors().NumberOfItems()) + { + const CSensor& sensor = *cSystem->GetSystemData().GetCSensors()[positionSensorIndex]; + if (EXUstd::IsOfType(sensor.GetOutputVariableType(), OutputVariableType::Position)) + { + const ResizableMatrix& data = sensor.GetInternalStorage(); + if (data.NumberOfRows() > 0 and data.NumberOfColumns() == 4) //must be position compatible data + { + for (Index i = 0; i < data.NumberOfRows(); i++) + { + if ((traces.showPast && data(i, 0) <= time) || + (traces.showFuture && data(i, 0) > time) || + (traces.showCurrent && fabs(data(i, 0) - time) < 1e-10)) //needed for current vectors + { + Vector3D v({ data(i,1), data(i,2), data(i,3) }); //time not used + sensorTracePositions.Append(v); + } + } + } + + if (traces.showVectors && vectorSensorIndex >= 0 && vectorSensorIndex < cSystem->GetSystemData().GetCSensors().NumberOfItems()) + { + const CSensor& vectorSensor = *cSystem->GetSystemData().GetCSensors()[vectorSensorIndex]; + const ResizableMatrix& data = vectorSensor.GetInternalStorage(); + if (data.NumberOfRows() > 0 && data.NumberOfColumns() == 4) //must be Vector3D data + { + for (Index i = 0; i < data.NumberOfRows(); i++) + { + if ((traces.showPast && data(i, 0) <= time) || + (traces.showFuture && data(i, 0) > time) || + (traces.showCurrent && fabs(data(i, 0) - time) < 1e-10) ) + { + Vector3D v({ data(i,1), data(i,2), data(i,3) }); //time not used + sensorTraceVectors.Append(v); + } + } + //this won't work, as in solution viewer current values are not "current"! + //if (showCurrent) + //{ + // vectorSensor.GetSensorValues(cSystem->GetSystemData(), sensorTraceValues, ConfigurationType::Visualization); + // if (sensorTraceValues.NumberOfItems() == 3) + // { + // Vector3D v({ sensorTraceValues[0], + // sensorTraceValues[1], + // sensorTraceValues[2] }); //time not used + // sensorTraceVectors.Append(v); + // } + //} + } + } + if (traces.showTriads && triadSensorIndex >= 0 && triadSensorIndex < cSystem->GetSystemData().GetCSensors().NumberOfItems()) + { + //std::cout << "A," << GetOutputVariableTypeString(triadSensor.GetOutputVariableType()) << ";\n"; + const CSensor& triadSensor = *cSystem->GetSystemData().GetCSensors()[triadSensorIndex]; + const ResizableMatrix& data = triadSensor.GetInternalStorage(); + if (data.NumberOfRows() > 0 && data.NumberOfColumns() == 10 && + EXUstd::IsOfType(triadSensor.GetOutputVariableType(), OutputVariableType::RotationMatrix)) //must be Matrix3D data + { + for (Index i = 0; i < data.NumberOfRows(); i++) + { + if ((traces.showPast && data(i, 0) <= time) || + (traces.showFuture && data(i, 0) > time) || + (traces.showCurrent && fabs(data(i, 0) - time) < 1e-10) ) + { + Matrix3D m(3, 3, { data(i,1), data(i,2), data(i,3), + data(i,4), data(i,5), data(i,6), + data(i,7), data(i,8), data(i,9) }); //time not used + sensorTraceTriads.Append(m); + //std::cout << "out"; + } + } + //if (showCurrent) + //{ + // triadSensor.GetSensorValues(cSystem->GetSystemData(), sensorTraceValues, ConfigurationType::Visualization); + // if (sensorTraceValues.NumberOfItems() == 10) + // { + // Matrix3D m(3, 3, { sensorTraceValues[1], sensorTraceValues[2], sensorTraceValues[3], + // sensorTraceValues[4], sensorTraceValues[5], sensorTraceValues[6], + // sensorTraceValues[7], sensorTraceValues[8], sensorTraceValues[9] }); //time not used + // sensorTraceTriads.Append(m); + // } + //} + } + } + } + } + if (positionSensorIndex < cSystem->GetSystemData().GetCSensors().NumberOfItems()-1) + { + return true; + } + } + return false; +} + //! REMOVE: get backlink of ith main system (0 if not existing), temporary for selection MainSystem* VisualizationSystemContainer::GetMainSystemBacklink(Index iSystem) { diff --git a/main/src/Graphics/VisualizationSystemContainer.h b/main/src/Graphics/VisualizationSystemContainer.h index 4328c1be..3a243902 100644 --- a/main/src/Graphics/VisualizationSystemContainer.h +++ b/main/src/Graphics/VisualizationSystemContainer.h @@ -240,6 +240,9 @@ class VisualizationSystemContainer: public VisualizationSystemContainerBase virtual bool GetComputeMaxSceneRequest() override { return computeMaxSceneRequest; } virtual void GetMarkerPositionOrientation(Index markerNumber, Index mbsNumber, Vector3D& position, Matrix3D& orientation, bool& hasPosition, bool& hasOrientation) override; + virtual bool GetSensorsPositionsVectorsLists(Index mbsNumber, Index positionSensorIndex, Index vectorSensorIndex, Index triadSensorIndex, + Vector3DList& sensorTracePositions, Vector3DList& sensorTraceVectors, Matrix3DList& sensorTraceTriads, Vector sensorTraceValues, + const VSettingsSensorTraces& traces) override; //! any multi-line text message from computation to be shown in renderer (e.g. time, solver, ...) virtual std::string GetComputationMessage(bool solverInformation = true, diff --git a/main/src/Graphics/VisualizationSystemContainerBase.h b/main/src/Graphics/VisualizationSystemContainerBase.h index c520ffa9..4f6fb0ee 100644 --- a/main/src/Graphics/VisualizationSystemContainerBase.h +++ b/main/src/Graphics/VisualizationSystemContainerBase.h @@ -41,7 +41,12 @@ class VisualizationSystemContainerBase virtual void SetComputeMaxSceneRequest(bool flag) = 0; virtual bool GetComputeMaxSceneRequest() = 0; + //get marker position and orientation virtual void GetMarkerPositionOrientation(Index markerNumber, Index mbsNumber, Vector3D& position, Matrix3D& orientation, bool& hasPosition, bool& hasOrientation) = 0; + //get sensor data list (if available); return true if further sensors available + virtual bool GetSensorsPositionsVectorsLists(Index mbsNumber, Index positionSensorIndex, Index vectorSensorIndex, Index triadSensorIndex, + Vector3DList& sensorTracePositions, Vector3DList& sensorTraceVectors, Matrix3DList& sensorTraceTriads, Vector sensorTraceValues, + const VSettingsSensorTraces& traces) = 0; virtual std::string GetComputationMessage(bool solverInformation = true, bool solutionInformation = true, bool solverTime = true) = 0; //! any multi-line text message from computation to be shown in renderer (e.g. time, solver, ...) diff --git a/main/src/Main/CSystem.cpp b/main/src/Main/CSystem.cpp index 052461fb..1a534b3b 100644 --- a/main/src/Main/CSystem.cpp +++ b/main/src/Main/CSystem.cpp @@ -1701,19 +1701,25 @@ void CSystem::ComputeODE2SingleLoad(Index loadIndex, TemporaryComputationData& t { Vector3D loadVector3D(0); //initialization in order to avoid gcc warnings Vector1D loadVector1D(0); //scalar loads...//initialization in order to avoid gcc warnings +#ifndef __FAST_EXUDYN_LINALG bool loadVector1Ddefined = false; //add checks such that wrong formats would fail bool loadVector3Ddefined = false; //add checks such that wrong formats would fail +#endif CLoad* cLoad = cSystemData.GetCLoads()[(Index)loadIndex]; if (cLoad->IsVector()) { loadVector3D = cLoad->GetLoadVector(cSystemData.GetMainSystemBacklink(), currentTime); +#ifndef __FAST_EXUDYN_LINALG loadVector3Ddefined = true; +#endif } else { loadVector1D = Vector1D(cLoad->GetLoadValue(cSystemData.GetMainSystemBacklink(), currentTime)); +#ifndef __FAST_EXUDYN_LINALG loadVector1Ddefined = true; +#endif } Index markerNumber = cLoad->GetMarkerNumber(); @@ -1887,7 +1893,7 @@ void CSystem::ComputeODE2SingleLoadLTG(Index loadIndex, ArrayIndex& ltgODE2equat CLoad* cLoad = cSystemData.GetCLoads()[(Index)loadIndex]; Index markerNumber = cLoad->GetMarkerNumber(); CMarker* marker = cSystemData.GetCMarkers()[markerNumber]; - LoadType loadType = cLoad->GetType(); + //LoadType loadType = cLoad->GetType(); //loads only applied to Marker::Body or Marker::Node if (marker->GetType() & Marker::Body) //code for body markers @@ -1985,9 +1991,9 @@ void CSystem::JacobianODE2Loads(TemporaryComputationDataArray& tempArray, const //Index nODE2 = cSystemData.GetNumberOfCoordinatesODE2(); //Index nODE1 = cSystemData.GetNumberOfCoordinatesODE1(); - Vector& xODE1 = cSystemData.GetCData().currentState.ODE1Coords; //current coordinates ==> this is what is differentiated for + //Vector& xODE1 = cSystemData.GetCData().currentState.ODE1Coords; //current coordinates ==> this is what is differentiated for Vector& xODE2 = cSystemData.GetCData().currentState.ODE2Coords; //current coordinates ==> this is what is differentiated for - Vector& xRefODE1 = cSystemData.GetCData().referenceState.ODE1Coords; //reference coordinates; might be important for numerical differentiation + //Vector& xRefODE1 = cSystemData.GetCData().referenceState.ODE1Coords; //reference coordinates; might be important for numerical differentiation Vector& xRefODE2 = cSystemData.GetCData().referenceState.ODE2Coords; //reference coordinates; might be important for numerical differentiation Vector& xODE2_t = cSystemData.GetCData().currentState.ODE2Coords_t; //for diff w.r.t. velocities @@ -2001,7 +2007,7 @@ void CSystem::JacobianODE2Loads(TemporaryComputationDataArray& tempArray, const ComputeODE2SingleLoadLTG(j, ltgODE2eq, ltgODE2coords, ltgODE1coords); Index nLocalODE2eq = ltgODE2eq.NumberOfItems(); Index nLocalODE2coords = ltgODE2coords.NumberOfItems(); - Index nLocalODE1coords = ltgODE1coords.NumberOfItems(); + //Index nLocalODE1coords = ltgODE1coords.NumberOfItems(); if (nLocalODE2eq != 0) { @@ -2055,6 +2061,7 @@ void CSystem::ComputeODE1Loads(TemporaryComputationData& temp, Vector& systemODE Vector1D loadVector1D(0); //scalar loads...//initialization in order to avoid gcc warnings bool loadVector1Ddefined = false; //add checks such that wrong formats would fail //bool loadVector3Ddefined = false; //add checks such that wrong formats would fail + __UNUSED(loadVector1Ddefined); //avoid unused variable warnings Real currentTime = cSystemData.GetCData().currentState.time; for (Index j = 0; j < nLoads; j++) @@ -3250,13 +3257,13 @@ TimerStructureRegistrator TSRreactionForces2("TSreactionForces2", TSreactionForc //! ode2ReactionForces += C_{q2}^T * \lambda void CSystem::ComputeODE2ProjectedReactionForces(TemporaryComputationDataArray& tempArray, const Vector& reactionForces, Vector& ode2ReactionForces) { - Index nAE = cSystemData.GetNumberOfCoordinatesAE(); - Index nODE2 = cSystemData.GetNumberOfCoordinatesODE2(); + //Index nAE = cSystemData.GetNumberOfCoordinatesAE(); + //Index nODE2 = cSystemData.GetNumberOfCoordinatesODE2(); //Index nODE1 = cSystemData.GetNumberOfCoordinatesODE1(); TemporaryComputationData& temp = tempArray[0]; - CHECKandTHROW(reactionForces.NumberOfItems() == nAE, "CSystem::ComputeODE2ProjectedReactionForces: reactionForces size mismatch!"); - CHECKandTHROW(ode2ReactionForces.NumberOfItems() == nODE2, "CSystem::ComputeODE2ProjectedReactionForces: ode2ReactionForces size mismatch!"); + CHECKandTHROW(reactionForces.NumberOfItems() == cSystemData.GetNumberOfCoordinatesAE(), "CSystem::ComputeODE2ProjectedReactionForces: reactionForces size mismatch!"); + CHECKandTHROW(ode2ReactionForces.NumberOfItems() == cSystemData.GetNumberOfCoordinatesODE2(), "CSystem::ComputeODE2ProjectedReactionForces: ode2ReactionForces size mismatch!"); int nItemsObjectsNoUF = cSystemData.listObjectProjectedReactionForcesODE2NoUF.NumberOfItems(); int nItemsNodesObjectsNoUF = nItemsObjectsNoUF + cSystemData.nodesODE2WithAE.NumberOfItems(); @@ -3517,10 +3524,10 @@ void CSystem::ComputeConstraintJacobianDerivative(TemporaryComputationData& temp void CSystem::ComputeConstraintJacobianTimesVector(TemporaryComputationData& temp, const Vector& v, Vector& result) { Index nAE = cSystemData.GetNumberOfCoordinatesAE(); - Index nODE2 = cSystemData.GetNumberOfCoordinatesODE2(); + //Index nODE2 = cSystemData.GetNumberOfCoordinatesODE2(); //Index nODE1 = cSystemData.GetNumberOfCoordinatesODE1(); - CHECKandTHROW(v.NumberOfItems() == nODE2, "CSystem::ComputeConstraintJacobianTimesVector: v size mismatch!"); + CHECKandTHROW(v.NumberOfItems() == cSystemData.GetNumberOfCoordinatesODE2(), "CSystem::ComputeConstraintJacobianTimesVector: v size mismatch!"); result.SetNumberOfItems(nAE); result.SetAll(0.); diff --git a/main/src/Main/rendererPythonInterface.cpp b/main/src/Main/rendererPythonInterface.cpp index ac24507a..6d792293 100644 --- a/main/src/Main/rendererPythonInterface.cpp +++ b/main/src/Main/rendererPythonInterface.cpp @@ -685,7 +685,7 @@ void PyProcessAskQuit() try { //open window to execute a python command ... - float alphaTransparency = GetGlfwRenderer().GetVisualizationSettings()->dialogs.alphaTransparency; + //float alphaTransparency = GetGlfwRenderer().GetVisualizationSettings()->dialogs.alphaTransparency; PyWriteToSysDictionary("quitResponse", py::cast((int)1) ); std::string str = R"( diff --git a/main/src/Objects/CObjectBeamGeometricallyExact.cpp b/main/src/Objects/CObjectBeamGeometricallyExact.cpp index 129bee07..46598e91 100644 --- a/main/src/Objects/CObjectBeamGeometricallyExact.cpp +++ b/main/src/Objects/CObjectBeamGeometricallyExact.cpp @@ -289,11 +289,13 @@ void CObjectBeamGeometricallyExact::ComputeJacobianODE2_ODE2(EXUmath::MatrixCont //jacobianODE2.GetInternalDenseMatrix().SetScalarMatrix(dimJacobian, 0.); const Index nDim3D = 3; - Index nNode0 = GetCNode(0)->GetNumberOfODE2Coordinates(); - Index nNode1 = GetCNode(1)->GetNumberOfODE2Coordinates(); - CHECKandTHROW( (nNode0 + nNode1 == dimJacobian) && + + Index nNode0 = GetCNode(0)->GetNumberOfODE2Coordinates(); + + //put this check into checkPreAssembleConsistencies.cpp + CHECKandTHROW( (nNode0 + GetCNode(1)->GetNumberOfODE2Coordinates() == dimJacobian) && (nNode0 <= (CNodeRigidBody::maxRotationCoordinates + nDim3D) ) && - (nNode1 <= (CNodeRigidBody::maxRotationCoordinates + nDim3D) ), + (GetCNode(1)->GetNumberOfODE2Coordinates() <= (CNodeRigidBody::maxRotationCoordinates + nDim3D) ), "CObjectBeamGeometricallyExact::ComputeJacobianODE2_ODE2: nodal coordinates mismatch; the nodes cannot be used with this beam element"); //const Index nDisplacementCoordinates = 3; diff --git a/main/src/Objects/CObjectConnectorReevingSystemSprings.cpp b/main/src/Objects/CObjectConnectorReevingSystemSprings.cpp index b4c37972..d85eb93c 100644 --- a/main/src/Objects/CObjectConnectorReevingSystemSprings.cpp +++ b/main/src/Objects/CObjectConnectorReevingSystemSprings.cpp @@ -23,7 +23,13 @@ Real CObjectConnectorReevingSystemSprings::ComputeForce(Real L, Real L0, Real L_ { Real invL0 = 1e3; //use minimum reference length (1mm), leads to very high stiffness ... should never happen if (L0 != 0.) { invL0 = 1. / L0; } - return ((L - L0)*EA + (L_t - L0_t) * DA) * invL0; + Real F = ((L - L0)*EA + (L_t - L0_t) * DA) * invL0; + + if (parameters.regularizationForce > 0 && F < 0) + { + F = parameters.regularizationForce * tanh(F / parameters.regularizationForce); + } + return F; } else { return 0.; } } diff --git a/main/src/Objects/CObjectFFRFreducedOrder.cpp b/main/src/Objects/CObjectFFRFreducedOrder.cpp index 4d3846f8..41eefd20 100644 --- a/main/src/Objects/CObjectFFRFreducedOrder.cpp +++ b/main/src/Objects/CObjectFFRFreducedOrder.cpp @@ -578,12 +578,10 @@ void CObjectFFRFreducedOrder::GetAccessFunctionBody(AccessFunctionType accessTyp if (parameters.mPhitTPsi.NumberOfRows() != 0) //otherwise it uses the user function ... { Index nODE2Rigid = GetCNode(rigidBodyNodeNumber)->GetNumberOfODE2Coordinates(); //number of rigid body coordinates - Index nODE2FF = GetCNode(genericNodeNumber)->GetNumberOfODE2Coordinates(); - - //pout << "nODE2FF =" << nODE2FF << "\n"; CHECKandTHROW((parameters.mPhitTPsi.NumberOfRows() == CNodeRigidBody::nDim3D) && - (parameters.mPhitTPsi.NumberOfColumns() == nODE2FF), "CObjectFFRFreducedOrder::GetAccessFunctionBody:DisplacementMassIntegral_q: inconsistent dimensions of matrix mPhitTPsi"); + (parameters.mPhitTPsi.NumberOfColumns() == GetCNode(genericNodeNumber)->GetNumberOfODE2Coordinates()), + "CObjectFFRFreducedOrder::GetAccessFunctionBody:DisplacementMassIntegral_q: inconsistent dimensions of matrix mPhitTPsi"); //EXUmath::MultMatrixTransposedMatrixTemplate(parameters.mPhitTPsi, A.GetTransposed(), tempMatrix); EXUmath::MultMatrixMatrixTemplate(A, parameters.mPhitTPsi, tempMatrix); diff --git a/main/src/Objects/CObjectKinematicTree.cpp b/main/src/Objects/CObjectKinematicTree.cpp index 903b405e..1e94bb7d 100644 --- a/main/src/Objects/CObjectKinematicTree.cpp +++ b/main/src/Objects/CObjectKinematicTree.cpp @@ -46,6 +46,7 @@ void CObjectKinematicTree::ComputeMassMatrix(EXUmath::MatrixContainer& massMatri { Index rv = massMatrixC.GetInternalDenseMatrix().InvertSpecial(tempMatrix, tempArrayIndex, false); CHECKandTHROW(rv == -1, "CObjectKinematicTree::ComputeMassMatrix: inverse failed; check if mass parameters are non-zero or set computeMassMatrixInversePerBody=False"); + __UNUSED(rv); //avoid unused variable warnings } } diff --git a/main/src/Objects/checkPreAssembleConsistencies.cpp b/main/src/Objects/checkPreAssembleConsistencies.cpp index 38630829..bb4fb769 100644 --- a/main/src/Objects/checkPreAssembleConsistencies.cpp +++ b/main/src/Objects/checkPreAssembleConsistencies.cpp @@ -773,6 +773,12 @@ bool MainObjectConnectorReevingSystemSprings::CheckPreAssembleConsistency(const } } + if (cObject->GetParameters().regularizationForce == 0.) + { + errorString = "CObjectConnectorReevingSystemSprings: regularizationForce may not be zero"; + return false; + } + Index npr = cObject->GetParameters().sheavesRadii.NumberOfItems(); if (nRigidBodyMarkers != npr) diff --git a/main/src/Pymodules/PyMatrixContainer.cpp b/main/src/Pymodules/PyMatrixContainer.cpp index 66ce793f..d3853d3e 100644 --- a/main/src/Pymodules/PyMatrixContainer.cpp +++ b/main/src/Pymodules/PyMatrixContainer.cpp @@ -27,7 +27,12 @@ PyMatrixContainer::PyMatrixContainer(const py::object& matrix) { //pout << "PyMatrixContainer::PyMatrixContainer:\n"; //py::print(matrix); - if (py::isinstance(matrix)) + if (matrix.is_none()) + { + useDenseMatrix = true; + denseMatrix = ResizableMatrix(); + } + else if (py::isinstance(matrix)) { //pout << "works2: PyMatrixContainer::PyMatrixContainer:\n"; *this = py::cast(matrix); @@ -92,7 +97,7 @@ PyMatrixContainer::PyMatrixContainer(const py::object& matrix) } else { - CHECKandTHROWstring("MatrixContainer: can only initialize with empty list [], list of lists or with 2D numpy array"); + CHECKandTHROWstring("MatrixContainer: can only initialize with None, empty list [], list of lists or with 2D numpy array"); } //pout << "PyMatrixContainer::PyMatrixContainer:READY\n"; diff --git a/main/src/Pymodules/PyMatrixVector.h b/main/src/Pymodules/PyMatrixVector.h index 6ccf8e93..0a605534 100644 --- a/main/src/Pymodules/PyMatrixVector.h +++ b/main/src/Pymodules/PyMatrixVector.h @@ -23,14 +23,18 @@ class PyVectorList : public VectorList public: //! create empty (dense) container //?remove default constructor to enable conversion from py::object in constructor? - PyVectorList() : VectorList () {} + PyVectorList() : VectorList() {} - PyVectorList(const VectorList & other) : VectorList(other) {} + PyVectorList(const VectorList& other) : VectorList(other) {} //! initialize array with list of py::array or with emtpy list (default value) PyVectorList(const py::object& listOfArrays) { - if (py::isinstance(listOfArrays)) + if (listOfArrays.is_none()) + { + *this = VectorList(); + } + else if (py::isinstance(listOfArrays)) { py::list pyList = py::cast(listOfArrays); this->SetMaxNumberOfItems((Index)pyList.size()); @@ -40,11 +44,10 @@ class PyVectorList : public VectorList { this->PyAppend((const py::object&)item); } - return; } else { - PyError(STDstring("Vector" + EXUstd::ToString(dataSize) + "DList: Expected list of " + EXUstd::ToString(dataSize) + "D numpy arrays, but received '" + + PyError(STDstring("Vector" + EXUstd::ToString(dataSize) + "DList: Expected empty list, None, or list of " + EXUstd::ToString(dataSize) + "D numpy arrays, but received '" + EXUstd::ToString(listOfArrays) + "'")); } } @@ -159,7 +162,11 @@ class PyMatrixList : public MatrixList //! initialize array with list of py::array or with emtpy list (default value) PyMatrixList(const py::object& listOfArrays) { - if (py::isinstance(listOfArrays)) + if (listOfArrays.is_none()) + { + *this = MatrixList(); + } + else if (py::isinstance(listOfArrays)) { py::list pyList = py::cast(listOfArrays); this->SetMaxNumberOfItems((Index)pyList.size()); @@ -169,11 +176,10 @@ class PyMatrixList : public MatrixList { this->PyAppend((const py::object&)item); } - return; } else { - PyError(STDstring("Matrix" + EXUstd::ToString(numberOfRowsColumns) + "DList: Expected list of " + EXUstd::ToString(numberOfRowsColumns) + "D numpy matrices, but received '" + + PyError(STDstring("Matrix" + EXUstd::ToString(numberOfRowsColumns) + "DList: Expected empty list, None, or list of " + EXUstd::ToString(numberOfRowsColumns) + "D numpy matrices, but received '" + EXUstd::ToString(listOfArrays) + "'")); } } @@ -266,7 +272,12 @@ namespace EPyUtils GenericExceptionHandling([&] { - if (py::isinstance(value)) + if (value.is_none()) + { + destination.Flush(); + rv = true; + } + else if (py::isinstance(value)) { py::list pylist = py::cast(value); //also works for numpy arrays (but gives different type!) @@ -274,7 +285,7 @@ namespace EPyUtils if (pylist.size() != 0) { rv = false; - PyError(STDstring("Set " + listType + ": Either empty list [] or " + listType + " allowed, but received: ") + + PyError(STDstring("Set " + listType + ": Either empty list [], None, or " + listType + " allowed, but received: ") + STDstring(py::str(value))); //here we do not use py::cast(value), because value may be Vector3DList directly, which cannot be casted to Python! } rv = true; @@ -293,7 +304,7 @@ namespace EPyUtils else { rv = false; - PyError(STDstring("Set " + listType + ": Either empty list [] or " + listType + " allowed, but received: ") + + PyError(STDstring("Set " + listType + ": Either empty list [], None, or " + listType + " allowed, but received: ") + STDstring(py::str(value))); //here we do not use py::cast(value), because value may be Vector3DList directly, which cannot be casted to Python! } }, "Set [Vector/Matrix][3/6]DList"); diff --git a/main/src/Pymodules/PybindModule.cpp b/main/src/Pymodules/PybindModule.cpp index 96eacfc6..374b93c5 100644 --- a/main/src/Pymodules/PybindModule.cpp +++ b/main/src/Pymodules/PybindModule.cpp @@ -775,7 +775,7 @@ PYBIND11_MODULE(exudynCPP, m) { return STDstring(EXUstd::ToString(item.GetIndex())); }, "return the string representation of the index, which can be, e.g., printed") ; - + ////++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ //NOT needed, should always convert to std::vector //py::class_(m, "ArrayNodeIndex", "ArrayNodeIndex: array of indices which may only be used for nodes") diff --git a/main/src/Pymodules/PybindUtilities.h b/main/src/Pymodules/PybindUtilities.h index da9a8164..74e673de 100644 --- a/main/src/Pymodules/PybindUtilities.h +++ b/main/src/Pymodules/PybindUtilities.h @@ -189,8 +189,11 @@ namespace EPyUtils { //! Expect Index or ArrayNodeIndex; otherwise throws error inline ArrayIndex GetArrayNodeIndexSafely(const py::object& pyObject) { - - if (py::isinstance(pyObject) || py::isinstance(pyObject)) + if (pyObject.is_none()) + { + return ArrayIndex(); //empty list + } + else if (py::isinstance(pyObject) || py::isinstance(pyObject)) { py::list pylist = py::cast(pyObject); //also works for numpy arrays (but gives different type!) ArrayIndex indexList; //initialize empty list @@ -246,7 +249,11 @@ namespace EPyUtils { //! Expect Index or ArrayMarkerIndex; otherwise throws error inline ArrayIndex GetArrayMarkerIndexSafely(const py::object& pyObject) { - if (py::isinstance(pyObject) || py::isinstance(pyObject)) + if (pyObject.is_none()) + { + return ArrayIndex(); //empty list + } + else if (py::isinstance(pyObject) || py::isinstance(pyObject)) { py::list pylist = py::cast(pyObject); //hopefully also works for numpy arrays .. TEST! ArrayIndex indexList; //initialize empty list @@ -277,7 +284,11 @@ namespace EPyUtils { //! Expect Index or ArraySensorIndex; otherwise throws error inline ArrayIndex GetArraySensorIndexSafely(const py::object& pyObject) { - if (py::isinstance(pyObject) || py::isinstance(pyObject)) + if (pyObject.is_none()) + { + return ArrayIndex(); //empty list + } + else if (py::isinstance(pyObject) || py::isinstance(pyObject)) { py::list pylist = py::cast(pyObject); //hopefully also works for numpy arrays .. TEST! ArrayIndex indexList; //initialize empty list diff --git a/main/src/Solver/CSolver.cpp b/main/src/Solver/CSolver.cpp index 538a5319..0243f41e 100644 --- a/main/src/Solver/CSolver.cpp +++ b/main/src/Solver/CSolver.cpp @@ -120,55 +120,56 @@ void SolverLocalData::CleanUpMemory() void SolverLocalData::SetLinearSolverType(LinearSolverType linearSolverType, bool reuseAnalyzedPattern, bool ignoreSingularJacobian, Real pivotThreshold) { - systemJacobian = &systemJacobianDense; - systemMassMatrix = &systemMassMatrixDense; - jacobianAE = &jacobianAEdense; + //std::cout << "SetLinearSolverType" << std::flush; //pout << "linearSolverType=" << linearSolverType << "\n"; if (EXUstd::IsOfType(LinearSolverType::Dense, linearSolverType)) { + //std::cout << "SetLinearSolverType1a" << std::flush; systemJacobian = &systemJacobianDense; systemMassMatrix = &systemMassMatrixDense; jacobianAE = &jacobianAEdense; #ifdef USE_EIGEN_DENSE_SOLVER Index flagEigen = (Index)(linearSolverType == LinearSolverType::EigenDense); - flagEigen += flagEigen * (Index)ignoreSingularJacobian; //flag becomes 0 or 2 + flagEigen += flagEigen * (Index)ignoreSingularJacobian; //flag only added in EigenDense case systemJacobianDense.UseEigenSolverType() = flagEigen; systemMassMatrixDense.UseEigenSolverType() = flagEigen; jacobianAEdense.UseEigenSolverType() = flagEigen; #endif } - else if (linearSolverType == LinearSolverType::EigenSparse) - { - systemJacobian = &systemJacobianSparse; - systemMassMatrix = &systemMassMatrixSparse; - jacobianAE = &jacobianAEsparse; - } - else if (linearSolverType == LinearSolverType::EigenSparseSymmetric) + else { + //std::cout << "SetLinearSolverType1b" << std::flush; systemJacobian = &systemJacobianSparse; systemMassMatrix = &systemMassMatrixSparse; jacobianAE = &jacobianAEsparse; - - systemJacobian->AssumeSymmetric(); - systemMassMatrix->AssumeSymmetric(); - jacobianAE->AssumeSymmetric(); } - else + + //std::cout << "SetLinearSolverType2" << std::flush; + if (linearSolverType == LinearSolverType::EigenSparseSymmetric) { - CHECKandTHROWstring("SolverLocalData::SetLinearSolverType: invalid linearSolverType"); + systemJacobianSparse.AssumeSymmetric(); + systemMassMatrixSparse.AssumeSymmetric(); + jacobianAEsparse.AssumeSymmetric(); } - if (!EXUstd::IsOfType(LinearSolverType::Dense, linearSolverType)) + //{ + // CHECKandTHROWstring("SolverLocalData::SetLinearSolverType: invalid linearSolverType"); + //} + + if (!EXUstd::IsOfType(LinearSolverType::Dense, linearSolverType)) { - systemJacobian->SetReuseAnalyzedPattern(reuseAnalyzedPattern); - systemMassMatrix->SetReuseAnalyzedPattern(reuseAnalyzedPattern); - jacobianAE->SetReuseAnalyzedPattern(reuseAnalyzedPattern); + //std::cout << "SetLinearSolverType3" << std::flush; + systemJacobianSparse.SetReuseAnalyzedPattern(reuseAnalyzedPattern); + systemMassMatrixSparse.SetReuseAnalyzedPattern(reuseAnalyzedPattern); + jacobianAEsparse.SetReuseAnalyzedPattern(reuseAnalyzedPattern); } - systemJacobian->PivotThreshold() = pivotThreshold; + //std::cout << "SetLinearSolverType4" << std::flush; + systemJacobian->PivotThreshold() = pivotThreshold; systemMassMatrix->PivotThreshold() = pivotThreshold; jacobianAE->PivotThreshold() = pivotThreshold; + //std::cout << "SetLinearSolverType5" << std::flush; } diff --git a/main/src/System/CContact.cpp b/main/src/System/CContact.cpp index eedd926f..0ed494c7 100644 --- a/main/src/System/CContact.cpp +++ b/main/src/System/CContact.cpp @@ -2692,6 +2692,7 @@ ArrayIndex* GeneralContact::GetActiveContacts(Contact::TypeIndex selectedTypeInd Index nItemsAvailable = globalContactIndexOffsets[selectedTypeIndex+1] - globalContactIndexOffsets[selectedTypeIndex]; CHECKandTHROW(itemIndex < nItemsAvailable, "GetContactInteractions: itemIndex is out of available range"); + __UNUSED(nItemsAvailable); //avoid unused variable warnings Index globalIndex = itemIndex + globalContactIndexOffsets[selectedTypeIndex]; diff --git a/main/src/Utilities/ReleaseAssert.h b/main/src/Utilities/ReleaseAssert.h index ba504dd7..32f70c0c 100644 --- a/main/src/Utilities/ReleaseAssert.h +++ b/main/src/Utilities/ReleaseAssert.h @@ -35,24 +35,27 @@ //#define __FAST_EXUDYN_LINALG //defined as preprocessor flags #ifndef __FAST_EXUDYN_LINALG -#define __PYTHON_USERFUNCTION_CATCH__ //performs try/catch in all python user functions -#define __EXUDYN_RUNTIME_CHECKS__ //performs several runtime checks, which slows down performance in release or debug mode + #define __PYTHON_USERFUNCTION_CATCH__ //performs try/catch in all python user functions + #define __EXUDYN_RUNTIME_CHECKS__ //performs several runtime checks, which slows down performance in release or debug mode -//!check if _checkExpression is true; if no, trow std::exception(_exceptionMessage); _exceptionMessage will be a const char*, e.g. "VectorBase::operator[]: invalid index" -//!linalg matrix/vector access functions, memory allocation, array classes and solvers will throw exceptions if the errors are not recoverable -//!this, as a consequence leads to a pybind exception translated to python; the message will be visible in python; for __FAST_EXUDYN_LINALG, no checks are performed + //!check if _checkExpression is true; if no, trow std::exception(_exceptionMessage); _exceptionMessage will be a const char*, e.g. "VectorBase::operator[]: invalid index" + //!linalg matrix/vector access functions, memory allocation, array classes and solvers will throw exceptions if the errors are not recoverable + //!this, as a consequence leads to a pybind exception translated to python; the message will be visible in python; for __FAST_EXUDYN_LINALG, no checks are performed -#define CHECKandTHROW(_checkExpression,_exceptionMessage) ((_checkExpression) ? 0 : throw EXUexception(_exceptionMessage)) -#define CHECKandTHROWcond(_checkExpression) ((_checkExpression) ? 0 : throw EXUexception("unexpected EXUDYN internal error")) -//always throw: -#define CHECKandTHROWstring(_exceptionMessage) (throw EXUexception(_exceptionMessage)) + #define CHECKandTHROW(_checkExpression,_exceptionMessage) ((_checkExpression) ? 0 : throw EXUexception(_exceptionMessage)) + #define CHECKandTHROWcond(_checkExpression) ((_checkExpression) ? 0 : throw EXUexception("unexpected EXUDYN internal error")) + //always throw: + #define CHECKandTHROWstring(_exceptionMessage) (throw EXUexception(_exceptionMessage)) #else //no checks in __FAST_EXUDYN_LINALG mode -#define CHECKandTHROW(_checkExpression,_exceptionMessage) -#define CHECKandTHROWcond(_checkExpression) -#define CHECKandTHROWstring(_exceptionMessage) + #define CHECKandTHROW(_checkExpression,_exceptionMessage) + #define CHECKandTHROWcond(_checkExpression) + #define CHECKandTHROWstring(_exceptionMessage) #endif +//add some macro to define unused variable, not trowing compiler warning, especially in case of __FAST_EXUDYN_LINALG where some variables will not be used any more +#define __UNUSED(x) ((void)(true ? 0 : (x))) + #define __EXUDYN_invalid_local_node0 "Object:GetNodeNumber: invalid call to local node number" //workaround to avoid string in object definition file #define __EXUDYN_invalid_local_node "Object:GetNodeNumber: invalid local node number > 0" //workaround to avoid string in object definition file #define __EXUDYN_invalid_local_node1 "Object:GetNodeNumber: invalid local node number > 1" //workaround to avoid string in object definition file diff --git a/main/src/Utilities/ResizableArray.h b/main/src/Utilities/ResizableArray.h index d0d947d0..ee692ba1 100644 --- a/main/src/Utilities/ResizableArray.h +++ b/main/src/Utilities/ResizableArray.h @@ -41,6 +41,7 @@ #include typedef ResizableArray ArrayReal; +typedef ResizableArray ArrayFloat; typedef ResizableArray ArrayIndex; typedef std::vector StdArrayIndex; //needed for user functions diff --git a/main/src/pythonGenerator/autoGenerateHelper.py b/main/src/pythonGenerator/autoGenerateHelper.py index 895bdc0b..3a9ea567 100644 --- a/main/src/pythonGenerator/autoGenerateHelper.py +++ b/main/src/pythonGenerator/autoGenerateHelper.py @@ -72,6 +72,7 @@ def Str2Latex(s, isDefaultValue=False, replaceCurlyBracket=True): #replace _ and (s.find('Vector') != -1) or (s.find('Matrix') != -1) or (s.find('Transformations66List') != -1) or (s.find('Matrix3DList') != -1) or (s.find('JointTypeList') != -1) ): + s = s.replace('ArrayFloat','') #correct python notation s = s.replace('ArrayIndex','') #correct python notation s = s.replace('JointTypeList','') #KinematicTree s = s.replace('Vector3DList','') #KinematicTree @@ -138,7 +139,11 @@ def DefaultValue2Python(s): s = s.replace('EXUmath::zeroMatrix3D','IIDiagMatrix(rowsColumns=3,value=0)') #replace with itemInterface diagonal matrix s = s.replace('Matrix()','[]') #replace empty matrix with emtpy list s = s.replace('MatrixI()','[]') #replace empty matrix with emtpy list - s = s.replace('PyMatrixContainer()','[]') #initialization in iteminterface with empty array + s = s.replace('PyMatrixContainer()','None') #initialization in iteminterface with empty array + s = s.replace('Vector2DList()','None') #initialization in iteminterface with empty array + s = s.replace('Vector3DList()','None') #initialization in iteminterface with empty array + s = s.replace('Vector6DList()','None') #initialization in iteminterface with empty array + s = s.replace('Matrix3DList()','None') #initialization in iteminterface with empty array s = s.replace('BeamSectionGeometry()','exudyn.BeamSectionGeometry()') #initialization in iteminterface with empty array s = s.replace('BeamSection()','exudyn.BeamSection()') #initialization in iteminterface with empty array @@ -161,11 +166,16 @@ def DefaultValue2Python(s): ): s = s.replace('ArrayIndex','') #correct python notation s = s.replace('JointTypeList','') #KinematicTree - s = s.replace('Vector6DList','') #KinematicTree - s = s.replace('Vector3DList','') #KinematicTree - s = s.replace('Matrix3DList','') #KinematicTree - s = s.replace('Vector2DList','') #BeamSectionGeometry - s = s.replace('PyVector2DList','') #BeamSectionGeometry + # s = s.replace('Vector2DList','') #BeamSectionGeometry + # s = s.replace('Vector3DList','') #KinematicTree + # s = s.replace('Vector6DList','') #KinematicTree + # s = s.replace('Matrix3DList','') #KinematicTree + + #s = s.replace('PyVector2DList','') #BeamSectionGeometry + if s.find('PyVector2DList') != -1: + print(s) + raise ValueError('autoGenerateHelper(): unexpected PyVector2DList found') + s = s.replace('Vector9D','') #correct python notation s = s.replace('Vector7D','') #correct python notation; rigid body coordinates s = s.replace('Vector6D','') #correct python notation; inertia parameters diff --git a/main/src/pythonGenerator/autoGeneratePyBindings.py b/main/src/pythonGenerator/autoGeneratePyBindings.py index 23cd15ff..a2109d50 100644 --- a/main/src/pythonGenerator/autoGeneratePyBindings.py +++ b/main/src/pythonGenerator/autoGeneratePyBindings.py @@ -1045,7 +1045,10 @@ plr.DefLatexFinishTable()#only finalize latex table -plr.DefLatexStartClass('MainSystem Python extensions','This section represents [experimental] 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 \\texttt{exudyn.mainSystemExtensions} or \\texttt{exudyn.utilities}', subSection=True,labelName='sec:mainsystem:pythonExtensions') +#%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +#++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +#create extensions +plr.DefLatexStartClass('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 \\texttt{exudyn.mainSystemExtensions} or \\texttt{exudyn.utilities}", subSection=True,labelName='sec:mainsystem:pythonExtensionsCreate') plr.AddDocuCodeBlock(code=""" import exudyn as exu @@ -1056,16 +1059,33 @@ # #create rigid body b1=mbs.CreateRigidBody(inertia = InertiaCuboid(density=5000, sideLengths=[0.1,0.1,1]), - referencePosition = [1,0,0], - gravity = [0,0,-9.81]) + referencePosition = [1,0,0], + gravity = [0,0,-9.81]) +""") + +plr.sLatex += '\\input{MainSystemCreateExt.tex}\n\n' + +with open('generated/MainSystemCreateExt.rst', 'r') as f: + plr.sRST += f.read() + +#%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +#++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +#function extensions +plr.DefLatexStartClass('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 \\texttt{exudyn.mainSystemExtensions} or \\texttt{exudyn.utilities}', subSection=True,labelName='sec:mainsystem:pythonExtensions') + +plr.AddDocuCodeBlock(code=""" +#this example sketches the usage +#for complete examples see Examples/ or TestModels/ folders +#create some multibody system (mbs) first: +# ... +# +#compute system degree of freedom: +mbs.ComputeSystemDegreeOfFreedom(verbose=True) # -mbs.Assemble() #call solver function directly from mbs: -mbs.ComputeSystemDegreeOfFreedom() -simulationSettings = exu.SimulationSettings() -mbs.SolveDynamic(simulationSettings) +mbs.SolveDynamic(exu.SimulationSettings()) # -#plot sensor sBody0 directly from mbs: +#plot sensor directly from mbs: mbs.PlotSensor(...) """) @@ -1074,6 +1094,7 @@ with open('generated/MainSystemExt.rst', 'r') as f: plr.sRST += f.read() + #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ #NODE @@ -2389,6 +2410,24 @@ description="get copy of list item with 'index' as vector", isLambdaFunction = True, ) +#copy and deepcopy according to Pybind11, see https://pybind11.readthedocs.io/en/latest/advanced/classes.html#pickling-support +# .def("__copy__", [](const Copyable &self) { +# return Copyable(self); +# }) +# .def("__deepcopy__", [](const Copyable &self, py::dict) { +# return Copyable(self); +# }, "memo"_a); +plr.DefPyFunctionAccess(cClass=classStr, pyName='__copy__', + cName='[](const PyVector3DList &item) {\n return PyVector3DList(item); }', + description="copy method to be used for copy.copy(...); in fact does already deep copy", + isLambdaFunction = True, + ) + +plr.DefPyFunctionAccess(cClass=classStr, pyName='__deepcopy__', + cName='[](const PyVector3DList &item, py::dict) {\n return PyVector3DList(item); }, "memo"_a', + description="deepcopy method to be used for copy.copy(...)", + isLambdaFunction = True, + ) plr.DefPyFunctionAccess(cClass=classStr, pyName='__repr__', cName='[](const PyVector3DList &item) {\n return EXUstd::ToString(item.GetPythonObject()); }', @@ -2447,6 +2486,18 @@ isLambdaFunction = True, ) +plr.DefPyFunctionAccess(cClass=classStr, pyName='__copy__', + cName='[](const PyVector2DList &item) {\n return PyVector2DList(item); }', + description="copy method to be used for copy.copy(...); in fact does already deep copy", + isLambdaFunction = True, + ) + +plr.DefPyFunctionAccess(cClass=classStr, pyName='__deepcopy__', + cName='[](const PyVector2DList &item, py::dict) {\n return PyVector2DList(item); }, "memo"_a', + description="deepcopy method to be used for copy.copy(...)", + isLambdaFunction = True, + ) + plr.DefPyFunctionAccess(cClass=classStr, pyName='__repr__', cName='[](const PyVector2DList &item) {\n return EXUstd::ToString(item.GetPythonObject()); }', description="return the string representation of the Vector2DList data, e.g.: print(data)", @@ -2501,6 +2552,18 @@ isLambdaFunction = True, ) +plr.DefPyFunctionAccess(cClass=classStr, pyName='__copy__', + cName='[](const PyVector6DList &item) {\n return PyVector6DList(item); }', + description="copy method to be used for copy.copy(...); in fact does already deep copy", + isLambdaFunction = True, + ) + +plr.DefPyFunctionAccess(cClass=classStr, pyName='__deepcopy__', + cName='[](const PyVector6DList &item, py::dict) {\n return PyVector6DList(item); }, "memo"_a', + description="deepcopy method to be used for copy.copy(...)", + isLambdaFunction = True, + ) + plr.DefPyFunctionAccess(cClass=classStr, pyName='__repr__', cName='[](const PyVector6DList &item) {\n return EXUstd::ToString(item.GetPythonObject()); }', description="return the string representation of the Vector6DList data, e.g.: print(data)", diff --git a/main/src/pythonGenerator/doc2rst.py b/main/src/pythonGenerator/doc2rst.py index f063a414..7668827f 100644 --- a/main/src/pythonGenerator/doc2rst.py +++ b/main/src/pythonGenerator/doc2rst.py @@ -612,7 +612,7 @@ def ParseFile(fileName, header = ''): 'Rot':'rotation', 'Rxyz':'rotation parameterization: consecutive rotations around x, y and z-axis (Tait-Bryan)', 'STL':'STereoLithography', - 'T66':'Pl\"ucker transformation', + 'T66':'Pl\\"ucker transformation', 'trig':'triangle (in graphics)', } @@ -639,7 +639,8 @@ def ParseFile(fileName, header = ''): file.write(abbrvTex) file.close() -file=open(destDir+rstFolder+'Abbreviations.rst','w') +#rst files should be utf8 for special characters +file=io.open(destDir+rstFolder+'Abbreviations.rst','w',encoding='utf8') file.write(abbrvRST) file.close() diff --git a/main/src/pythonGenerator/exudynVersion.py b/main/src/pythonGenerator/exudynVersion.py index c16d52d6..36fe8b1c 100644 --- a/main/src/pythonGenerator/exudynVersion.py +++ b/main/src/pythonGenerator/exudynVersion.py @@ -1,4 +1,4 @@ # version info automatically generated by tracker; generated by Johannes Gerstmayr -# last modified = 2023-06-12 -exudynVersionString = "1.6.164.dev1" +# last modified = 2023-07-19 +exudynVersionString = "1.7.0" diff --git a/main/src/pythonGenerator/generated/MainSystemCreateExt.rst b/main/src/pythonGenerator/generated/MainSystemCreateExt.rst new file mode 100644 index 00000000..fb5a5d90 --- /dev/null +++ b/main/src/pythonGenerator/generated/MainSystemCreateExt.rst @@ -0,0 +1,532 @@ + + +.. _sec-mainsystemextensions-createmasspoint: + +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:'+name + | \ ``referencePosition``\ : 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 point + | \ ``gravity``\ : gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) + | \ ``graphicsDataList``\ : list of GraphicsData for optional mass visualization + | \ ``drawSize``\ : general drawing size of node + | \ ``color``\ : color of node + | \ ``show``\ : True: if graphicsData list is empty, node is shown, otherwise body is shown; otherwise, nothing is shown + | \ ``create2D``\ : if False, create NodePoint2D and MassPoint2D + | \ ``returnDict``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + 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), \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createrigidbody: + +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 = []``\ , \ ``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:'+name + | \ ``referencePosition``\ : 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 graphicsDataUtilities function GraphicsData...(...) + | \ ``drawSize``\ : general drawing size of node + | \ ``color``\ : color of node + | \ ``show``\ : True: if graphicsData list is empty, node is shown, otherwise body is shown; False: nothing is shown + | \ ``create2D``\ : if False, create NodePoint2D and MassPoint2D + | \ ``returnDict``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4red)]) + 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), \ `chatGPTupdate.py `_\ (Ex), \ `graphicsDataExample.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createspringdamper: + +Function: CreateSpringDamper +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateSpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``referenceLength = None``\ , \ ``stiffness = 0.``\ , \ ``damping = 0.``\ , \ ``force = 0.``\ , \ ``velocityOffset = 0.``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) + +- | \ *function description*\ : + | helper function to create SpringDamper connector, using arguments from ObjectConnectorSpringDamper; similar interface as CreateDistanceConstraint(...) + | - NOTE that this function is added to MainSystem via Python function MainSystemCreateSpringDamper. +- | \ *input*\ : + | \ ``name``\ : name string for connector; markers get Marker0:name and Marker1:name + | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types + | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number + | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number + | \ ``referenceLength``\ : if None, length is computed from reference position of bodies or nodes; if not None, this scalar reference length is used for spring + | \ ``stiffness``\ : scalar stiffness coefficient + | \ ``damping``\ : scalar damping coefficient + | \ ``force``\ : scalar additional force applied + | \ ``velocityOffset``\ : scalar offset: if referenceLength is changed over time, the velocityOffset may be changed accordingly to emulate a reference motion + | \ ``show``\ : if True, connector visualization is drawn + | \ ``drawSize``\ : general drawing size of connector + | \ ``color``\ : color of connector +- | \ *output*\ : + | ObjectIndex; returns index of newly created object +- | \ *example*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + 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() + 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: + + \ `chatGPTupdate.py `_\ (Ex), \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createcartesianspringdamper: + +Function: CreateCartesianSpringDamper +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateCartesianSpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``stiffness = [0.,0.,0.]``\ , \ ``damping = [0.,0.,0.]``\ , \ ``offset = [0.,0.,0.]``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types + | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number + | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number + | \ ``stiffness``\ : 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) + | \ ``show``\ : if True, connector visualization is drawn + | \ ``drawSize``\ : general drawing size of connector + | \ ``color``\ : color of connector +- | \ *output*\ : + | ObjectIndex; returns index of newly created object +- | \ *example*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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=color4blue) + oGround = mbs.AddObject(ObjectGround()) + oSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[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: + + \ `chatGPTupdate.py `_\ (Ex), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createrigidbodyspringdamper: + +Function: CreateRigidBodySpringDamper +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateRigidBodySpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [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``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) + +- | \ *function description*\ : + | helper function to create RigidBodySpringDamper connector, using arguments from ObjectConnectorRigidBodySpringDamper + | - NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBodySpringDamper. +- | \ *input*\ : + | \ ``name``\ : name string for connector; markers get Marker0:name and Marker1:name + | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types + | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number + | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number + | \ ``stiffness``\ : 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 frame + | \ ``useGlobalFrame``\ : if False, the rotationMatrixJoint is defined in the local coordinate system of body0 + | \ ``show``\ : if True, connector visualization is drawn + | \ ``drawSize``\ : general drawing size of connector + | \ ``color``\ : color of connector +- | \ *output*\ : + | ObjectIndex; returns index of newly created object +- | \ *example*\ : + +.. code-block:: python + + #TODO + + +Relevant Examples (Ex) and TestModels (TM) with weblink to github: + + \ `bricardMechanism.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createrevolutejoint: + +Function: CreateRevoluteJoint +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateRevoluteJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``axis = []``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axisRadius = 0.1``\ , \ ``axisLength = 0.4``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be rigid body or ground object + | \ ``position``\ : 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 body0 + | \ ``axis``\ : a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 + | \ ``useGlobalFrame``\ : if False, the point and axis vectors are defined in the local coordinate system of body0 + | \ ``show``\ : if True, connector visualization is drawn + | \ ``axisRadius``\ : radius of axis for connector graphical representation + | \ ``axisLength``\ : length of axis for connector graphical representation + | \ ``color``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4steelblue)]) + 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), \ `chatGPTupdate.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `solutionViewerTest.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `perf3DRigidBodies.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createprismaticjoint: + +Function: CreatePrismaticJoint +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreatePrismaticJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``axis = []``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axisRadius = 0.1``\ , \ ``axisLength = 0.4``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be rigid body or ground object + | \ ``position``\ : 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 body0 + | \ ``axis``\ : a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration + | \ ``useGlobalFrame``\ : if False, the point and axis vectors are defined in the local coordinate system of body0 + | \ ``show``\ : if True, connector visualization is drawn + | \ ``axisRadius``\ : radius of axis for connector graphical representation + | \ ``axisLength``\ : length of axis for connector graphical representation + | \ ``color``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4steelblue)]) + 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), \ `mainSystemExtensionsTests.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createsphericaljoint: + +Function: CreateSphericalJoint +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateSphericalJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``constrainedAxes = [1,1,1]``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``jointRadius = 0.1``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be mass point, rigid body or ground object + | \ ``position``\ : 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 body0 + | \ ``constrainedAxes``\ : 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 body0 + | \ ``show``\ : if True, connector visualization is drawn + | \ ``jointRadius``\ : radius of sphere for connector graphical representation + | \ ``color``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + 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) + + + +.. _sec-mainsystemextensions-creategenericjoint: + +Function: CreateGenericJoint +^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateGenericJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``rotationMatrixAxes = np.eye(3)``\ , \ ``constrainedAxes = [1,1,1, 1,1,1]``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axesRadius = 0.1``\ , \ ``axesLength = 0.4``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyNumber0``\ : a object number for body0, must be rigid body or ground object + | \ ``bodyNumber1``\ : a object number for body1, must be rigid body or ground object + | \ ``position``\ : 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 body0 + | \ ``rotationMatrixAxes``\ : 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 joint + | \ ``constrainedAxes``\ : 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 rotation0 + | \ ``useGlobalFrame``\ : if False, the position is defined in the local coordinate system of body0, otherwise it is defined in global coordinates + | \ ``show``\ : if True, connector visualization is drawn + | \ ``axesRadius``\ : radius of axes for connector graphical representation + | \ ``axesLength``\ : length of axes for connector graphical representation + | \ ``color``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + 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: + + \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `rigidBodyCOMtest.py `_\ (TM) + + + +.. _sec-mainsystemextensions-createdistanceconstraint: + +Function: CreateDistanceConstraint +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +`CreateDistanceConstraint `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``distance = None``\ , \ ``show = True``\ , \ ``drawSize = -1.``\ , \ ``color = color4default``\ ) + +- | \ *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:name + | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types + | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number + | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number + | \ ``distance``\ : if None, distance is computed from reference position of bodies or nodes; if not None, this distance (which must be always larger than zero) is prescribed between the two positions + | \ ``show``\ : if True, connector visualization is drawn + | \ ``drawSize``\ : general drawing size of node + | \ ``color``\ : 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*\ : + +.. code-block:: python + + import exudyn as exu + from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], + color=color4orange)]) + m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], + physicsMass=1, drawSize = 0.2) + n1 = mbs.GetObject(m1)['nodeNumber'] + oGround = mbs.AddObject(ObjectGround()) + mbs.CreateDistanceConstraint(bodyOrNodeList=[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), \ `mainSystemExtensionsTests.py `_\ (TM) + diff --git a/main/src/pythonGenerator/generated/MainSystemExt.rst b/main/src/pythonGenerator/generated/MainSystemExt.rst index d029e8a6..53ddf85b 100644 --- a/main/src/pythonGenerator/generated/MainSystemExt.rst +++ b/main/src/pythonGenerator/generated/MainSystemExt.rst @@ -38,543 +38,11 @@ Relevant Examples (Ex) and TestModels (TM) with weblink to github: -.. _sec-mainsystemextensions-createmasspoint: - -Function: CreateMassPoint -^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateMassPoint `__\ (\ ``name = ''``\ , \ ``referenceCoordinates = [0.,0.,0.]``\ , \ ``initialCoordinates = [0.,0.,0.]``\ , \ ``initialVelocities = [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:'+name - | \ ``referenceCoordinates``\ : reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) - | \ ``initialCoordinates``\ : initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) - | \ ``initialVelocities``\ : initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) - | \ ``physicsMass``\ : mass of mass point - | \ ``gravity``\ : gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) - | \ ``graphicsDataList``\ : list of GraphicsData for optional mass visualization - | \ ``drawSize``\ : general drawing size of node - | \ ``color``\ : color of node - | \ ``show``\ : True: if graphicsData list is empty, node is shown, otherwise body is shown; otherwise, nothing is shown - | \ ``create2D``\ : if False, create NodePoint2D and MassPoint2D - | \ ``returnDict``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], - initialVelocities = [2,5,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - 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: - - \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createrigidbody: - -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 = []``\ , \ ``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:'+name - | \ ``referencePosition``\ : 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 graphicsDataUtilities function GraphicsData...(...) - | \ ``drawSize``\ : general drawing size of node - | \ ``color``\ : color of node - | \ ``show``\ : True: if graphicsData list is empty, node is shown, otherwise body is shown; False: nothing is shown - | \ ``create2D``\ : if False, create NodePoint2D and MassPoint2D - | \ ``returnDict``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4red)]) - 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), \ `graphicsDataExample.py `_\ (Ex), \ `rigidBodyTutorial3.py `_\ (Ex), \ `rigidBodyTutorial3withMarkers.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createspringdamper: - -Function: CreateSpringDamper -^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateSpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``referenceLength = None``\ , \ ``stiffness = 0.``\ , \ ``damping = 0.``\ , \ ``force = 0.``\ , \ ``velocityOffset = 0.``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) - -- | \ *function description*\ : - | helper function to create SpringDamper connector, using arguments from ObjectConnectorSpringDamper; similar interface as CreateDistanceConstraint(...) - | - NOTE that this function is added to MainSystem via Python function MainSystemCreateSpringDamper. -- | \ *input*\ : - | \ ``name``\ : name string for connector; markers get Marker0:name and Marker1:name - | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types - | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number - | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number - | \ ``referenceLength``\ : if None, length is computed from reference position of bodies or nodes; if not None, this scalar reference length is used for spring - | \ ``stiffness``\ : scalar stiffness coefficient - | \ ``damping``\ : scalar damping coefficient - | \ ``force``\ : scalar additional force applied - | \ ``velocityOffset``\ : scalar offset: if referenceLength is changed over time, the velocityOffset may be changed accordingly to emulate a reference motion - | \ ``show``\ : if True, connector visualization is drawn - | \ ``drawSize``\ : general drawing size of connector - | \ ``color``\ : color of connector -- | \ *output*\ : - | ObjectIndex; returns index of newly created object -- | \ *example*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2,5,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - 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() - 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: - - \ `springDamperTutorialNew.py `_\ (Ex), \ `mainSystemExtensionsTests.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createcartesianspringdamper: - -Function: CreateCartesianSpringDamper -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateCartesianSpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``stiffness = [0.,0.,0.]``\ , \ ``damping = [0.,0.,0.]``\ , \ ``offset = [0.,0.,0.]``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types - | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number - | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number - | \ ``stiffness``\ : 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) - | \ ``show``\ : if True, connector visualization is drawn - | \ ``drawSize``\ : general drawing size of connector - | \ ``color``\ : color of connector -- | \ *output*\ : - | ObjectIndex; returns index of newly created object -- | \ *example*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities and rigidBodyUtilities - import numpy as np - SC = exu.SystemContainer() - mbs = SC.AddSystem() - b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], - physicsMass = 1, gravity = [0,-9.81,0], - drawSize = 0.5, color=color4blue) - oGround = mbs.AddObject(ObjectGround()) - oSD = mbs.CreateCartesianSpringDamper(bodyOrNodeList=[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: - - \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createrigidbodyspringdamper: - -Function: CreateRigidBodySpringDamper -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateRigidBodySpringDamper `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [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``\ , \ ``show = True``\ , \ ``drawSize = -1``\ , \ ``color = color4default``\ ) - -- | \ *function description*\ : - | helper function to create RigidBodySpringDamper connector, using arguments from ObjectConnectorRigidBodySpringDamper - | - NOTE that this function is added to MainSystem via Python function MainSystemCreateRigidBodySpringDamper. -- | \ *input*\ : - | \ ``name``\ : name string for connector; markers get Marker0:name and Marker1:name - | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types - | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number - | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number - | \ ``stiffness``\ : 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 frame - | \ ``useGlobalFrame``\ : if False, the rotationMatrixJoint is defined in the local coordinate system of body0 - | \ ``show``\ : if True, connector visualization is drawn - | \ ``drawSize``\ : general drawing size of connector - | \ ``color``\ : color of connector -- | \ *output*\ : - | ObjectIndex; returns index of newly created object -- | \ *example*\ : - -.. code-block:: python - - #TODO - - -Relevant Examples (Ex) and TestModels (TM) with weblink to github: - - \ `bricardMechanism.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createrevolutejoint: - -Function: CreateRevoluteJoint -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateRevoluteJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``axis = []``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axisRadius = 0.1``\ , \ ``axisLength = 0.4``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be rigid body or ground object - | \ ``position``\ : 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 body0 - | \ ``axis``\ : a 3D vector as list or np.array: if useGlobalFrame=True it describes the global rotation axis of the joint in reference configuration; else: local axis in body0 - | \ ``useGlobalFrame``\ : if False, the point and axis vectors are defined in the local coordinate system of body0 - | \ ``show``\ : if True, connector visualization is drawn - | \ ``axisRadius``\ : radius of axis for connector graphical representation - | \ ``axisLength``\ : length of axis for connector graphical representation - | \ ``color``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4steelblue)]) - 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), \ `rigidBodyTutorial3.py `_\ (Ex), \ `solutionViewerTest.py `_\ (Ex), \ `bricardMechanism.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `perf3DRigidBodies.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createprismaticjoint: - -Function: CreatePrismaticJoint -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreatePrismaticJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``axis = []``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axisRadius = 0.1``\ , \ ``axisLength = 0.4``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be rigid body or ground object - | \ ``position``\ : 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 body0 - | \ ``axis``\ : a 3D vector as list or np.array containing the global translation axis of the joint in reference configuration - | \ ``useGlobalFrame``\ : if False, the point and axis vectors are defined in the local coordinate system of body0 - | \ ``show``\ : if True, connector visualization is drawn - | \ ``axisRadius``\ : radius of axis for connector graphical representation - | \ ``axisLength``\ : length of axis for connector graphical representation - | \ ``color``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4steelblue)]) - 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), \ `mainSystemExtensionsTests.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createsphericaljoint: - -Function: CreateSphericalJoint -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateSphericalJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``constrainedAxes = [1,1,1]``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``jointRadius = 0.1``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyNumbers``\ : a list of object numbers for body0 and body1; must be mass point, rigid body or ground object - | \ ``position``\ : 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 body0 - | \ ``constrainedAxes``\ : 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 body0 - | \ ``show``\ : if True, connector visualization is drawn - | \ ``jointRadius``\ : radius of sphere for connector graphical representation - | \ ``color``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - 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) - - - -.. _sec-mainsystemextensions-creategenericjoint: - -Function: CreateGenericJoint -^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateGenericJoint `__\ (\ ``name = ''``\ , \ ``bodyNumbers = [None, None]``\ , \ ``position = []``\ , \ ``rotationMatrixAxes = np.eye(3)``\ , \ ``constrainedAxes = [1,1,1, 1,1,1]``\ , \ ``useGlobalFrame = True``\ , \ ``show = True``\ , \ ``axesRadius = 0.1``\ , \ ``axesLength = 0.4``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyNumber0``\ : a object number for body0, must be rigid body or ground object - | \ ``bodyNumber1``\ : a object number for body1, must be rigid body or ground object - | \ ``position``\ : 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 body0 - | \ ``rotationMatrixAxes``\ : 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 joint - | \ ``constrainedAxes``\ : 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 rotation0 - | \ ``useGlobalFrame``\ : if False, the position is defined in the local coordinate system of body0, otherwise it is defined in global coordinates - | \ ``show``\ : if True, connector visualization is drawn - | \ ``axesRadius``\ : radius of axes for connector graphical representation - | \ ``axesLength``\ : length of axes for connector graphical representation - | \ ``color``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - 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: - - \ `bricardMechanism.py `_\ (TM), \ `computeODE2AEeigenvaluesTest.py `_\ (TM), \ `driveTrainTest.py `_\ (TM), \ `mainSystemExtensionsTests.py `_\ (TM), \ `rigidBodyCOMtest.py `_\ (TM) - - - -.. _sec-mainsystemextensions-createdistanceconstraint: - -Function: CreateDistanceConstraint -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -`CreateDistanceConstraint `__\ (\ ``name = ''``\ , \ ``bodyOrNodeList = [None, None]``\ , \ ``localPosition0 = [0.,0.,0.]``\ , \ ``localPosition1 = [0.,0.,0.]``\ , \ ``distance = None``\ , \ ``show = True``\ , \ ``drawSize = -1.``\ , \ ``color = color4default``\ ) - -- | \ *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:name - | \ ``bodyOrNodeList``\ : a list of object numbers (with specific localPosition0/1) or node numbers; may also be of mixed types - | \ ``localPosition0``\ : local position (as 3D list or numpy array) on body0, if not a node number - | \ ``localPosition1``\ : local position (as 3D list or numpy array) on body1, if not a node number - | \ ``distance``\ : if None, distance is computed from reference position of bodies or nodes; if not None, this distance (which must be always larger than zero) is prescribed between the two positions - | \ ``show``\ : if True, connector visualization is drawn - | \ ``drawSize``\ : general drawing size of node - | \ ``color``\ : 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*\ : - -.. code-block:: python - - import exudyn as exu - from exudyn.utilities import * #includes itemInterface, graphicsDataUtilities 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 = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], - color=color4orange)]) - m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], - physicsMass=1, drawSize = 0.2) - n1 = mbs.GetObject(m1)['nodeNumber'] - oGround = mbs.AddObject(ObjectGround()) - mbs.CreateDistanceConstraint(bodyOrNodeList=[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: - - \ `mainSystemExtensionsTests.py `_\ (TM) - - - .. _sec-mainsystemextensions-plotsensor: 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``\ ) +`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. @@ -615,6 +83,8 @@ Function: PlotSensor | \ ``[*kwargs]``\ : | \ ``minorTicksXon``\ : if True, turn minor ticks for x-axis on | \ ``minorTicksYon``\ : if True, turn minor ticks for y-axis on + | \ ``logScaleX``\ : use log scale for x-axis + | \ ``logScaleY``\ : use log scale for y-axis | \ ``fileCommentChar``\ : if exists, defines the comment character in files (\#, | \ ``fileDelimiterChar``\ : if exists, defines the character indicating the columns for data (',', ' ', ';', ...) - | \ *output*\ : @@ -779,8 +249,8 @@ Function: ComputeLinearizedSystem SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # @@ -837,8 +307,8 @@ Function: ComputeODE2Eigenvalues SC = exu.SystemContainer() mbs = SC.AddSystem() # - b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], - initialVelocities = [2*0,5,0], + b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], + initialVelocity = [2*0,5,0], physicsMass = 1, gravity = [0,-9.81,0], drawSize = 0.5, color=color4blue) # diff --git a/main/src/pythonGenerator/generated/stubAutoBindingsExt.pyi b/main/src/pythonGenerator/generated/stubAutoBindingsExt.pyi index 7804e816..4f9304c0 100644 --- a/main/src/pythonGenerator/generated/stubAutoBindingsExt.pyi +++ b/main/src/pythonGenerator/generated/stubAutoBindingsExt.pyi @@ -4,7 +4,7 @@ class MainSystem: def SolutionViewer(self, solution=None, rowIncrement=1, timeout=0.04, runOnStart=True, runMode=2, fontSize=12, title='', checkRenderEngineStopFlag=True) -> None: ... @overload - def CreateMassPoint(self, name='', referenceCoordinates=[0.,0.,0.], initialCoordinates=[0.,0.,0.], initialVelocities=[0.,0.,0.], physicsMass=0, gravity=[0.,0.,0.], graphicsDataList=[], drawSize=-1, color=[-1.,-1.,-1.,-1.], show=True, create2D=False, returnDict=False) -> Union[dict, ObjectIndex]: ... + def CreateMassPoint(self, 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) -> Union[dict, ObjectIndex]: ... @overload def CreateRigidBody(self, 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=[], drawSize=-1, color=[-1.,-1.,-1.,-1.], show=True, create2D=False, returnDict=False) -> Union[dict, ObjectIndex]: ... diff --git a/main/src/pythonGenerator/generated/stubSystemStructures.pyi b/main/src/pythonGenerator/generated/stubSystemStructures.pyi index a1bb3e1a..62a1264a 100644 --- a/main/src/pythonGenerator/generated/stubSystemStructures.pyi +++ b/main/src/pythonGenerator/generated/stubSystemStructures.pyi @@ -307,8 +307,29 @@ class VSettingsLoads: show: bool showNumbers: bool +#information for VSettingsSensorTraces +class VSettingsSensorTraces: + lineWidth: float + listOfPositionSensors: ArrayIndex + listOfTriadSensors: ArrayIndex + listOfVectorSensors: ArrayIndex + positionsShowEvery: int + sensorsMbsNumber: int + showCurrent: bool + showFuture: bool + showPast: bool + showPositionTrace: bool + showTriads: bool + showVectors: bool + traceColors: ArrayFloat + triadSize: float + triadsShowEvery: int + vectorScaling: float + vectorsShowEvery: int + #information for VSettingsSensors class VSettingsSensors: + traces: VSettingsSensorTraces defaultColor: Tuple[float,float,float,float] defaultSize: float drawSimplified: bool diff --git a/main/src/pythonGenerator/mainSystemExtensionsHeader.py b/main/src/pythonGenerator/mainSystemExtensionsHeader.py index 915405fd..bb09438a 100644 --- a/main/src/pythonGenerator/mainSystemExtensionsHeader.py +++ b/main/src/pythonGenerator/mainSystemExtensionsHeader.py @@ -85,9 +85,9 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr #**input: # mbs: the MainSystem where items are created # name: name string for object, node is 'Node:'+name -# referenceCoordinates: reference coordinates for point node (always a 3D vector, no matter if 2D or 3D mass) -# initialCoordinates: initial displacements for point node (always a 3D vector, no matter if 2D or 3D mass) -# initialVelocities: initial velocities for point node (always a 3D vector, no matter if 2D or 3D mass) +# referencePosition: 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 point # gravity: gravity vevtor applied (always a 3D vector, no matter if 2D or 3D mass) # graphicsDataList: list of GraphicsData for optional mass visualization @@ -105,8 +105,8 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0=mbs.CreateMassPoint(referenceCoordinates = [0,0,0], -# initialVelocities = [2,5,0], +# b0=mbs.CreateMassPoint(referencePosition = [0,0,0], +# initialVelocity = [2,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -117,9 +117,9 @@ def JointPreCheckCalc(where, mbs, name, bodyNumbers, position, show, useGlobalFr # mbs.SolveDynamic(simulationSettings = simulationSettings) def MainSystemCreateMassPoint(mbs, name = '', - referenceCoordinates = [0.,0.,0.], - initialCoordinates = [0.,0.,0.], - initialVelocities = [0.,0.,0.], + referencePosition = [0.,0.,0.], + initialDisplacement = [0.,0.,0.], + initialVelocity = [0.,0.,0.], physicsMass=0, gravity = [0.,0.,0.], graphicsDataList = [], @@ -133,12 +133,12 @@ def MainSystemCreateMassPoint(mbs, if not exudyn.__useExudynFast: if not isinstance(name, str): RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='name', received = name, expectedType = ExpectedType.String) - if not IsVector(referenceCoordinates, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='referenceCoordinates', received = referenceCoordinates, expectedType = ExpectedType.Vector, dim=3) - if not IsVector(initialCoordinates, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialCoordinates', received = initialCoordinates, expectedType = ExpectedType.Vector, dim=3) - if not IsVector(initialVelocities, 3): - RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialVelocities', received = initialVelocities, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(referencePosition, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='referencePosition', received = referencePosition, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(initialDisplacement, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialDisplacement', received = initialDisplacement, expectedType = ExpectedType.Vector, dim=3) + if not IsVector(initialVelocity, 3): + RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='initialVelocity', received = initialVelocity, expectedType = ExpectedType.Vector, dim=3) if not IsVector(gravity, 3): RaiseTypeError(where='MainSystem.CreateMassPoint(...)', argumentName='gravity', received = gravity, expectedType = ExpectedType.Vector, dim=3) @@ -162,9 +162,9 @@ def MainSystemCreateMassPoint(mbs, if not create2D: nodeNumber = mbs.AddNode(eii.NodePoint(name = nodeName, - referenceCoordinates = referenceCoordinates, - initialCoordinates=initialCoordinates, - initialVelocities=initialVelocities, + referenceCoordinates = referencePosition, + initialCoordinates=initialDisplacement, + initialVelocities=initialVelocity, visualization = eii.VNodePoint(show = show and (graphicsDataList == []), drawSize = drawSize, color = color), )) bodyNumber = mbs.AddObject(eii.MassPoint(name = name, @@ -174,9 +174,9 @@ def MainSystemCreateMassPoint(mbs, graphicsData = graphicsDataList) )) else: nodeNumber = mbs.AddNode(eii.NodePoint2D(name = nodeName, - referenceCoordinates = referenceCoordinates[0:2], - initialCoordinates=initialCoordinates[0:2], - initialVelocities=initialVelocities[0:2], + referenceCoordinates = referencePosition[0:2], + initialCoordinates=initialDisplacement[0:2], + initialVelocities=initialVelocity[0:2], visualization = eii.VNodePoint2D(show = show and (graphicsDataList == []), drawSize = drawSize, color = color), )) bodyNumber = mbs.AddObject(eii.MassPoint2D(name = name, @@ -447,8 +447,8 @@ def AngularVelocity2RotationVector_t(angularVelocity, rotMatrix): # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [2,0,0], -# initialVelocities = [2,5,0], +# b0 = mbs.CreateMassPoint(referencePosition = [2,0,0], +# initialVelocity = [2,5,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -583,7 +583,7 @@ def MainSystemCreateSpringDamper(mbs, # SC = exu.SystemContainer() # mbs = SC.AddSystem() # -# b0 = mbs.CreateMassPoint(referenceCoordinates = [7,0,0], +# b0 = mbs.CreateMassPoint(referencePosition = [7,0,0], # physicsMass = 1, gravity = [0,-9.81,0], # drawSize = 0.5, color=color4blue) # @@ -1185,7 +1185,7 @@ def MainSystemCreateGenericJoint(mbs, name='', bodyNumbers=[None, None], # gravity = [0,-9.81,0], # graphicsDataList = [GraphicsDataOrthoCubePoint(size=[1,0.1,0.1], # color=color4orange)]) -# m1 = mbs.CreateMassPoint(referenceCoordinates=[5.5,-1,0], +# m1 = mbs.CreateMassPoint(referencePosition=[5.5,-1,0], # physicsMass=1, drawSize = 0.2) # n1 = mbs.GetObject(m1)['nodeNumber'] # diff --git a/main/src/pythonGenerator/objectDefinition.py b/main/src/pythonGenerator/objectDefinition.py index 9700c73c..08b5ea3e 100644 --- a/main/src/pythonGenerator/objectDefinition.py +++ b/main/src/pythonGenerator/objectDefinition.py @@ -1009,7 +1009,7 @@ def UFgraphics(mbs, objectNum): sims=exu.SimulationSettings() sims.timeIntegration.numberOfSteps = 10000000 #many steps to see graphics exu.StartRenderer() #perform zoom all (press 'a' several times) after startup to see the sphere - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) exu.StopRenderer() \end{lstlisting} %%RSTCOMPATIBLE @@ -1104,7 +1104,7 @@ class = ObjectMassPoint #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -1198,7 +1198,7 @@ class = ObjectMassPoint2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -1294,7 +1294,7 @@ class = ObjectMass1D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current mass position at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(mass, exu.OutputVariableType.Position, [0,0,0])[0] @@ -1397,7 +1397,7 @@ class = ObjectRotationalMass1D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result, get current rotor z-rotation at local position [0,0,0] exudynTestGlobals.testResult = mbs.GetObjectOutputBody(rotor, exu.OutputVariableType.Rotation, [0,0,0]) @@ -1737,7 +1737,7 @@ class = ObjectRigidBody2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -1969,7 +1969,7 @@ def UFgraphics(mbs, itemNumber): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] @@ -2147,7 +2147,7 @@ def UFrhs(mbs, t, itemNumber, q): sims=exu.SimulationSettings() solverType = exu.DynamicSolverType.RK44 - exu.SolveDynamic(mbs, solverType=solverType, simulationSettings=sims) + mbs.SolveDynamic(solverType=solverType, simulationSettings=sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nODE1, exu.OutputVariableType.Coordinates)[0] @@ -2297,7 +2297,7 @@ class = ObjectKinematicTree which denotes the transformation from joint coordinate (scalar) to rotations and translations. We can compute the local joint angular velocity $\tomega_i$ and translational velocity $\wv_i$, as a 6D vector $\vv^J_i$, from \be - \vv^J_i = \vp{\tomega_i}{\wv_i} = \tPhi_i \, q_i + \vv^J_i = \vp{\tomega_i}{\wv_i} = \tPhi_i \, \dot q_i \ee % The joint coordinates, which can be rotational or translational, are stored in the vector @@ -2496,7 +2496,7 @@ class = ObjectKinematicTree simulationSettings = exu.SimulationSettings() #takes currently set values or default values simulationSettings.timeIntegration.numberOfSteps = 1000 #gives very accurate results - exu.SolveDynamic(mbs, simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! + mbs.SolveDynamic(simulationSettings , solverType=exu.DynamicSolverType.RK67) #highly accurate! #check final value of angle: q0 = mbs.GetNodeOutput(nGeneric, exu.OutputVariableType.Coordinates) @@ -3624,7 +3624,7 @@ class = ObjectANCFCable2D #assemble and solve system for default parameters mbs.Assemble() - exu.SolveStatic(mbs) + mbs.SolveStatic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(lastNode, exu.OutputVariableType.Displacement)[0] @@ -4237,7 +4237,7 @@ def UFforce(mbs, t, itemNumber, u, v, k, d, F0): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[0] @@ -4428,7 +4428,7 @@ def UFforce(mbs, t, itemNumber, u, v, k, d, offset): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[1] @@ -4615,7 +4615,7 @@ def UFforce(mbs, t, itemNumber, displacement, rotation, velocity, angularVelocit #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[1] @@ -4774,7 +4774,7 @@ def UFforce(mbs, t, itemNumber, displacement, velocity, stiffness, damping, offs #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Displacement)[0] @@ -4931,7 +4931,7 @@ def UFforce(mbs, t, itemNumber, rotation, angularVelocity, stiffness, damping, o #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] @@ -5092,7 +5092,7 @@ def springForce(mbs, t, itemNumber, u, v, k, d, offset): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, @@ -5471,7 +5471,7 @@ class = ObjectConnectorGravity mbs.Assemble() sims = exu.SimulationSettings() sims.timeIntegration.endTime = tEnd - exu.SolveDynamic(mbs, sims, solverType=exu.DynamicSolverType.RK67) + mbs.SolveDynamic(sims, solverType=exu.DynamicSolverType.RK67) #check result at default integration time #expect y=x after one period of orbiting (got: 100000.00000000479) @@ -5713,7 +5713,7 @@ class = ObjectConnectorHydraulicActuatorSimple #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ class = ObjectConnectorReevingSystemSprings -classDescription = "A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by $nr$ rigid body markers $[m_0, \, m_1, \, \ldots, \, m_{nr-1}]$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by $m_{c0}$ and $m_{c1}$ ." +classDescription = "A rD reeving system defined by a list of torque-free and friction-free sheaves or points that are connected with one rope (modelled as massless spring). NOTE that the spring can undergo tension AND compression (in order to avoid compression, use a PreStepUserFunction to turn off stiffness and damping in this case!). The force is assumed to be constant all over the rope. The sheaves or connection points are defined by $nr$ rigid body markers $[m_0, \, m_1, \, \ldots, \, m_{nr-1}]$. At both ends of the rope there may be a prescribed motion coupled to a coordinate marker each, given by $m_{c0}$ and $m_{c1}$ ." cParentClass = CObjectConnector mainParentClass = MainObjectConnector visuParentClass = VisualizationObject @@ -5832,10 +5832,21 @@ class = ObjectConnectorReevingSystemSprings \dot L_0 = f_0 \cdot \dot q_{m_{c0}} + f_1 \cdot \dot q_{m_{c1}}, \quad \ee while we set $L_0 = L_{ref}$ and $\dot L_0=0$ otherwise. - The force in the reeving system (assumed to be constant all over the rope) reads + The linear force in the reeving system (assumed to be constant all over the rope) is computed as \be - F = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} + F_{lin} = (L-L_{0}) \frac{EA}{L_0} + (\dot L - \dot L_0)\frac{DA}{L_0} \ee + The rope force is computed from + \be + F = \begin{cases} F_{lin} \quad \mathrm{if} \quad F_{lin} > 0 \\ + F_{reg} \cdot \mathrm{tanh}(F_{lin}/F_{reg})\quad \mathrm{else} + \end{cases} + \ee + Which allows small compressive forces $F_{reg}$. + In case that $F_{reg} < 0$, compressive forces are not regularized (linear spring). + The case $F_{reg} = 0$ will be used in future only in combination with a data node, + which allows switching similar as in friction and contact elements. + Note that in case of $L_0=0$, the term $\frac{1}{L_0}$ is replaced by $1000$. However, this case must be avoided by the user by choosing appropriate parameters for the system. @@ -5856,6 +5867,7 @@ class = ObjectConnectorReevingSystemSprings V, CP, dampingPerLength, , , UReal, "0.", , IO, "$DA$axial damping per length [SI:N/(m/s)/m] of rope; the effective damping coefficient of the reeving system is computed as $DA/L$ in which $L$ is the current length of the rope" V, CP, dampingTorsional, , , UReal, "0.", , IO, "$DT$torsional damping [SI:Nms] between sheaves; this effect can damp rotations around the rope axis, pairwise between sheaves; this parameter is experimental" V, CP, dampingShear, , , UReal, "0.", , IO, "$DS$damping of shear motion [SI:Ns] between sheaves; this effect can damp motion perpendicular to the rope between each pair of sheaves; this parameter is experimental" +V, CP, regularizationForce, , , Real, "0.1", , IO, "$F_{reg}$small regularization force [SI:N] in order to avoid large compressive forces; this regularization force can either be $<0$ (using a linear tension/compression spring model) or $>0$, which restricts forces in the rope to be always $\ge -F_{reg}$. Note that smaller forces lead to problems in implicit integrators and smaller time steps. For explicit integrators, this force can be chosen close to zero." V, CP, referenceLength, , , Real, "0.", , IO, "$L_{ref}$reference length for computation of roped force" V, CP, sheavesAxes, , , Vector3DList,"Vector3DList()", , I, "$\lv_a = [\LU{m0}{\av_0},\, \LU{m1}{\av_1},\, \ldots ] in [\Rcal^{3}, ...]$list of local vectors axes of sheaves; vectors refer to rigid body markers given in list of markerNumbers; first and last axes are ignored, as they represent the attachment of the rope ends" V, CP, sheavesRadii, , , Vector, "Vector()", , I, "$\lv_r = [r_0,\, r_1,\, \ldots]\tp \in \Rcal^{n}$radius for each sheave, related to list of markerNumbers and list of sheaveAxes; first and last radii must always be zero." @@ -5964,7 +5976,7 @@ class = ObjectConnectorDistance sims=exu.SimulationSettings() sims.timeIntegration.generalizedAlpha.spectralRadius=0.7 - exu.SolveDynamic(mbs, sims) + mbs.SolveDynamic(sims) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Position)[0] @@ -6136,7 +6148,7 @@ def OffsetUF(mbs, t, itemNumber, lOffset): #gives 0.05 at t=1 #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass, exu.OutputVariableType.Displacement)[0] @@ -7622,7 +7634,7 @@ class = ObjectJointRevoluteZ #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, exu.SimulationSettings()) + mbs.SolveDynamic(exu.SimulationSettings()) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nBody, exu.OutputVariableType.Rotation)[2] @@ -8794,7 +8806,7 @@ class = MarkerSuperElementPosition #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs, solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) + mbs.SolveDynamic(solverType = exudyn.DynamicSolverType.TrapezoidalIndex2) #check result at default integration time exudynTestGlobals.testResult = mbs.GetNodeOutput(nMass1, exu.OutputVariableType.Position)[0] @@ -9460,7 +9472,7 @@ class = LoadMassProportional #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() #check result exudynTestGlobals.testResult = mbs.GetNodeOutput(node, exu.OutputVariableType.Position)[2] @@ -9847,7 +9859,7 @@ def UFsensor(mbs, t, sensorNumbers, factors, configuration): #assemble and solve system for default parameters mbs.Assemble() - exu.SolveDynamic(mbs) + mbs.SolveDynamic() if False: from exudyn.plot import PlotSensor diff --git a/main/src/pythonGenerator/pythonAutoGenerateObjects.py b/main/src/pythonGenerator/pythonAutoGenerateObjects.py index 2982edf9..e1f53d6b 100644 --- a/main/src/pythonGenerator/pythonAutoGenerateObjects.py +++ b/main/src/pythonGenerator/pythonAutoGenerateObjects.py @@ -74,27 +74,80 @@ def DestinationNr(strDest): #StdVector3D=std::array does not accept numpy::array 'PyFunctionVector3DScalarVector3D': 'std::function', #LoadForceVector, LoadTorqueVector, LoadMassProportional } -#this function finds out, if a parameter is set with a special Set...Safely function in C++ -def IsASetSafelyParameter(parameterType): - if ((parameterType == 'String') or - (parameterType == 'ItemName') or - (parameterType == 'Vector2D') or - (parameterType == 'Vector3DList') or - (parameterType == 'Matrix3DList') or - # (parameterType == 'PyVector3DList') or - # (parameterType == 'PyMatrix3DList') or +#this for mutable args +def IsASafelyVector(parameterType): + if ((parameterType == 'Vector2D') or (parameterType == 'Vector3D') or (parameterType == 'Vector4D') or (parameterType == 'Vector6D') or (parameterType == 'Vector7D') or (parameterType == 'Vector9D') or - (parameterType == 'Matrix3D') or + (parameterType == 'NumpyVector') + ): + return True + else: + return False + +def IsAVector(parameterType): + if ((parameterType == 'Vector') + or (parameterType == 'Float4') + or IsASafelyVector(parameterType) + ): + return True + else: + return False + +#this for mutable args +def IsASimpleMatrix(parameterType): + if ((parameterType == 'Matrix3D') or (parameterType == 'Matrix6D') or (parameterType == 'NumpyMatrix') or - (parameterType == 'NumpyMatrixI') or #for index arrays, mesh, ... - (parameterType == 'PyMatrixContainer') or - (parameterType == 'NumpyVector') - #or (parameterType in pyFunctionTypeConversion) + (parameterType == 'NumpyMatrixI') + ): + return True + else: + return False + +def IsAMatrixVectorSpecial(parameterType): + if ((parameterType == 'Vector3DList') or + (parameterType == 'Matrix3DList') or + (parameterType == 'PyMatrixContainer') + ): + return True + else: + return False + +def IsAArrayIndex(parameterType): + if ((parameterType == 'ArrayNodeIndex') or + (parameterType == 'NodeIndex2') or + (parameterType == 'NodeIndex3') or + (parameterType == 'ArrayObjectIndex') or #unused + (parameterType == 'ArrayMarkerIndex') or + (parameterType == 'ArrayLoadIndex') or #unused + (parameterType == 'ArraySensorIndex') + ): + return True + else: + return False + +#this function finds out, if a parameter is set with a special Set...Safely function in C++ +def IsASetSafelyParameter(parameterType): + if (IsASafelyVector(parameterType) or + IsASimpleMatrix(parameterType) or + IsAMatrixVectorSpecial(parameterType) or + (parameterType == 'String') or + (parameterType == 'ItemName') + # (parameterType == 'Vector2D') or + # (parameterType == 'Vector3D') or + # (parameterType == 'Vector4D') or + # (parameterType == 'Vector6D') or + # (parameterType == 'Vector7D') or + # (parameterType == 'Vector9D') or + # (parameterType == 'NumpyVector') or + # (parameterType == 'Matrix3D') or + # (parameterType == 'Matrix6D') or + # (parameterType == 'NumpyMatrix') or + # (parameterType == 'NumpyMatrixI') or #for index arrays, mesh, ... ): return True else: @@ -370,7 +423,7 @@ def WriteFile(parseInfo, parameterList, typeConversion): sList = [sParamComp, sParamMain, sComp, sMain, sVisu] nClasses = 5 #number of different classes indexComp = 2 #index in sList - indexMain = 3 #index in slist + # indexMain = 3 #index in slist #************************************ #class definition: @@ -703,6 +756,27 @@ def WriteFile(parseInfo, parameterList, typeConversion): if IsTypeWithRangeCheck(parameter['type']): parameterWithCheck = 'CheckForValid' + parameter['type'] + '(' + parameter['pythonName'] + ',' parameterWithCheck += '"' + parameter['pythonName'] +'","' + parseInfo['class'] + '")' + if (IsAVector(parameter['type']) + or IsASimpleMatrix(parameter['type']) + #or IsAMatrixVectorSpecial(parameter['type']) #defaults to None! + ): + parameterWithCheck = 'np.array('+parameterWithCheck+')' + elif (IsAArrayIndex(parameter['type']) + or parameter['type'] == 'BodyGraphicsData' #in this case, flat copy is ok + or parameter['type'] == 'BodyGraphicsDataList' #in this case, flat copy is ok + or parameter['type'] == 'JointTypeList' + or parameter['type'] == 'ArrayIndex' + ): + parameterWithCheck = 'copy.copy('+parameterWithCheck+')' #flat copy is sufficient + elif defaultValueStr.strip().startswith('['): + print('WARNING: unresolved default [...] with',parameter['pythonName']) + elif defaultValueStr.strip().startswith('{'): #for now, only visualization + print('WARNING: unresolved default {...} with',parameter['pythonName']) + + #this does not work, because MatrixContainer or similar does not provide copy method + # elif defaultValueStr.strip() == '[]': #for some special matrices, etc. + # parameterWithCheck = 'copy.copy('+parameterWithCheck+')' + #future: also add size check ... tempPythonClassInit = sIndent+sIndent+'self.' + parameter['pythonName'] + ' = ' + parameterWithCheck + '\n' @@ -730,7 +804,7 @@ def WriteFile(parseInfo, parameterList, typeConversion): sPythonClass += ', visualization = ' + vDefaultDict + '):\n' #add visualization structure (must always be there...) #sPythonClass += ', visualization = {}):\n' #add visualization structure (must always be there...) #OLD MODE: sPythonClass += ', visualization = V' + parseInfo['class'] + '()):\n' #add visualization structure (must always be there...) - sPythonClass += sPythonClassInit + sIndent+sIndent+'self.visualization = visualization\n\n' + sPythonClass += sPythonClassInit + sIndent+sIndent+'self.visualization = CopyDictLevel1(visualization)\n\n' sPythonClass += sIndent+'def __iter__(self):\n' sPythonClass += sPythonIter + '\n' sPythonClass += sIndent+'def __repr__(self):\n' @@ -1695,7 +1769,22 @@ def CutString(theString, numberOfCutLines): #s += 'from exudyn import OutputVariableType\n\n' #do not import exudyn, causes problems e.g. with exudynFast, ... s += '#item interface diagonal matrix creator\n' s += '\n' - s += 'import exudyn #for exudyn.InvalidIndex() and other exudyn native structures needed in RigidBodySpringDamper\n\n' + s += 'import exudyn #for exudyn.InvalidIndex() and other exudyn native structures needed in RigidBodySpringDamper\n' + s += 'import numpy as np\n' + s += 'import copy \n\n' + + s += '#helper function for level-1 copy of dicts (for visualization default args!)\n' + s += '#visualization dictionaries (which may be huge, are only flat copied, which is sufficient)\n' + s += 'def CopyDictLevel1(originalDict):\n' + s += space4+'if isinstance(originalDict,dict): #copy only required if default dict is used\n' + s += space4+' copyDict = {}\n' + s += space4+' for key, value in originalDict.items():\n' + s += space4+' copyDict[key] = copy.copy(value)\n' + s += space4+' return copyDict\n' + s += space4+'else:\n' + s += space4+' return originalDict #fast track for everything else\n' + s += space4+'\n' + s += '#helper function diagonal matrices, not needing numpy\n' s += 'def IIDiagMatrix(rowsColumns, value):\n' s += space4+'m = []\n' diff --git a/main/src/pythonGenerator/pythonAutoGenerateSystemStructures.py b/main/src/pythonGenerator/pythonAutoGenerateSystemStructures.py index c63ce384..b18dea6e 100644 --- a/main/src/pythonGenerator/pythonAutoGenerateSystemStructures.py +++ b/main/src/pythonGenerator/pythonAutoGenerateSystemStructures.py @@ -18,7 +18,7 @@ typeCasts = {'Bool':'bool', 'Int':'Index', 'Real':'Real', 'UInt':'Index', 'PInt':'Index', 'UReal':'Real', 'PReal':'Real', 'UFloat':'float', 'PFloat':'float', 'Vector':'std::vector', 'Vector3D':'std::vector', #'Matrix':'Matrix', 'SymmetricMatrix':'Matrix', - 'ArrayIndex':'std::vector', 'String':'std::string', 'FileName':'std::string', + 'ArrayIndex':'std::vector', 'ArrayFloat':'std::vector', 'String':'std::string', 'FileName':'std::string', 'Float2': 'std::array', 'Float3': 'std::array', 'Float4': 'std::array', #e.g. for OpenGL vectors 'Float9': 'std::array', 'Float16': 'std::array', #e.g. for OpenGL rotation matrix and homogenous transformation 'UInt2': 'std::array', 'UInt3': 'std::array', 'UInt4': 'std::array', @@ -30,8 +30,11 @@ } #convert parameter types to C++/DYNALFEX types #conversion rules for dictionary 'type'; this type conversion adds rules for the user's values in the dictionary -convertToDict = {'ResizableVector':'Vector', 'StdArray33F':'MatrixFloat', 'NumpyVector':'Vector', 'NumpyMatrix':'Matrix', - 'Index2':'IndexArray', 'Index4':'IndexArray', 'Float4':'VectorFloat', 'Float3':'VectorFloat' #,'String':'std::string' +convertToDict = {'ResizableVector':'Vector', 'StdArray33F':'MatrixFloat', + 'NumpyVector':'Vector', 'NumpyMatrix':'Matrix', + 'Index2':'IndexArray', 'Index4':'IndexArray', + 'ArrayIndex':'IndexArray', 'ArrayFloat':'VectorFloat', + 'Float4':'VectorFloat', 'Float3':'VectorFloat' #,'String':'std::string' } #convert special size parameters: diff --git a/main/src/pythonGenerator/systemStructuresDefinition.py b/main/src/pythonGenerator/systemStructuresDefinition.py index b720e9bf..c38576be 100644 --- a/main/src/pythonGenerator/systemStructuresDefinition.py +++ b/main/src/pythonGenerator/systemStructuresDefinition.py @@ -82,7 +82,7 @@ class = SolutionSettings #appendToFile=True #not done in first class writePybindIncludes = True typicalPaths = simulationSettings -latexText = "\n%++++++++++++++++++++++++++++++++++++++\n\mysubsection{Simulation settings}\nThis section includes hierarchical structures for simulation settings, e.g., time integration, static solver, Newton iteration and solution file export.\n" +latexText = "\n%++++++++++++++++++++++++++++++++++++++\n\mysubsectionlabel{Simulation settings}{sec:SimulationSettingsMain}\nThis section includes hierarchical structures for simulation settings, e.g., time integration, static solver, Newton iteration and solution file export.\n" classDescription = "General settings for exporting the solution (results) of a simulation." #V|F, pythonName, cplusplusName, size, type, defaultValue,args, cFlags, parameterDescription # @@ -366,7 +366,7 @@ class = SimulationSettings #++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ class = VSettingsGeneral appendToFile=False -latexText = "\n%++++++++++++++++++++++++++++++++++++++\n\mysubsection{Visualization settings}\nThis section includes hierarchical structures for visualization settings, e.g., drawing of nodes, bodies, connectors, loads and markers and furthermore openGL, window and save image options. For further information, see \refSection{sec:overview:basics:visualizationsettings}.\n" +latexText = "\n%++++++++++++++++++++++++++++++++++++++\n\mysubsectionlabel{Visualization settings}{sec:VisualizationSettingsMain}\nThis section includes hierarchical structures for visualization settings, e.g., drawing of nodes, bodies, connectors, loads and markers and furthermore openGL, window and save image options. For further information, see \refSection{sec:overview:basics:visualizationsettings}.\n" writePybindIncludes = True typicalPaths = SC.visualizationSettings classDescription = "General settings for visualization." @@ -395,7 +395,7 @@ class = VSettingsGeneral V, showSolutionInformation, , , bool, true, , P, "true = show solution information (from simulationSettings.solution)" V, showSolverInformation, , , bool, true, , P, "true = solver name and further information shown in render window" V, showSolverTime, , , bool, true, , P, "true = solver current time shown in render window" -V, renderWindowString, , , String, "", , P, "string shown in render window (use this, e.g., for debugging, etc.; written below EXUDYN, similar to solutionInformation in SimulationSettings.solutionSettings)" +V, renderWindowString, , , String, "", , P, "string shown in render window (use this, e.g., for debugging, etc.; written below EXUDYN, similar to solutionInformation in SimulationSettings.solutionSettings)" V, pointSize, , , float, "0.01f", , P, "global point size (absolute)" V, circleTiling, , , PInt, "16", , P, "global number of segments for circles; if smaller than 2, 2 segments are used (flat)" V, cylinderTiling, , , PInt, "16", , P, "global number of segments for cylinders; if smaller than 2, 2 segments are used (flat)" @@ -555,6 +555,40 @@ class = VSettingsLoads # writeFile=VisualizationSettings.h +#%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ +class = VSettingsSensorTraces +appendToFile=True +writePybindIncludes = True +typicalPaths = SC.visualizationSettings +classDescription = "Visualization settings for traces of sensors. Note that a large number of time points (influenced by simulationSettings.solutionSettings.sensorsWritePeriod) may lead to slow graphics." +#V|F, pythonName, cplusplusName, size, type, defaultValue,args, cFlags, parameterDescription +V, listOfPositionSensors, , -1, ArrayIndex, "ArrayIndex()", , P, "list of position sensors which can be shown as trace inside render window if sensors have storeInternal=True; if this list is empty and showPositionTrace=True, then all available sensors are shown" +V, listOfVectorSensors, , -1, ArrayIndex, "ArrayIndex()", , P, "list of sensors with 3D vector quantities; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showVectors=True; the vector quantity is drawn relative to the related position" +V, listOfTriadSensors, , -1, ArrayIndex, "ArrayIndex()", , P, "list of sensors of with OutputVariableType RotationMatrix; this non-empty list needs to coincide in length with the listOfPositionSensors to be shown if showTriads=True; the triad is drawn at the related position" +V, showPositionTrace, , , bool, false, , P, "show position trace of all position sensors if listOfPositionSensors=[] or of specified sensors; sensors need to activate storeInternal=True" +V, showVectors, , , bool, false, , P, "if True, show vector quantities according to description in showPositionTrace" +V, showTriads, , , bool, false, , P, "if True, show basis vectors from rotation matrices provided by sensors" +V, sensorsMbsNumber, , , Index, "0", , P, "number of main system which is used to for sensor lists; if only 1 mbs is in the SystemContainer, use 0; if there are several mbs, it needs to specify the number" +V, showPast, , , bool, true, , P, "show trace previous to current visualization state" +V, showCurrent, , , bool, true, , P, "show current trace position (and especially vector quantity) related to current visualization state; this only works in solution viewer if sensor values are stored at time grid points of the solution file (up to a precision of 1e-10) and may therefore be temporarily unavailable" +V, showFuture, , , bool, false, , P, "show trace future to current visualization state if already computed (e.g. in SolutionViewer)" +V, positionsShowEvery, , , PInt, 1, , P, "integer value i; out of available sensor data, show every i-th position" +V, vectorsShowEvery, , , PInt, 1, , P, "integer value i; out of available sensor data, show every i-th vector" +V, triadsShowEvery, , , PInt, 1, , P, "integer value i; out of available sensor data, show every i-th triad" +V, vectorScaling, , , float, "0.01f", , P, "scaling of vector quantities; if, e.g., loads, this factor has to be adjusted significantly" +V, triadSize, , , float, "0.1f ", , P, "length of triad axes if shown" +V, lineWidth, , , UFloat, "2.f", , P, "line width for traces" +V, traceColors, , -1, ArrayFloat, "ArrayFloat({0.2f,0.2f,0.2f,1.f, 0.8f,0.2f,0.2f,1.f, 0.2f,0.8f,0.2f,1.f, 0.2f,0.2f,0.8f,1.f, 0.2f,0.8f,0.8f,1.f, 0.8f,0.2f,0.8f,1.f, 0.8f,0.4f,0.1f,1.f})", , P, "RGBA float values for traces in one array; using 6x4 values gives different colors for 6 traces; in case of triads, the 0/1/2-axes are drawn in red, green, and blue" +# + +writeFile=VisualizationSettings.h + +# settings and list of sensors provided in visualizationSettings.sensors.traces with +# list of sensors, showPositionTrace, listOfPositionSensors=[] +# (empty means all position sensors, listOfVectorSensors=[] which can provide according vector quantities for positions; +# showVectors, vectorScaling=0.001, showPast=True, showFuture=False, showCurrent=True, lineWidth=2 + + #%%++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ class = VSettingsSensors appendToFile=True @@ -566,7 +600,8 @@ class = VSettingsSensors V, showNumbers, , , bool, false, , P, "flag to decide, whether the sensor numbers are shown" V, drawSimplified, , , bool, true, , P, "draw sensors with simplified symbols" V, defaultSize, , , float, "-1.f", , P, "global sensor size; if -1.f, sensor size is relative to maxSceneSize" -V, defaultColor, , 4, Float4, "Float4({0.6f,0.6f,0.1f,1.f})",, P, "default cRGB color for sensors; 4th value is alpha-transparency" +V, defaultColor, , 4, Float4, "Float4({0.6f,0.6f,0.1f,1.f})",, P, "default cRGB color for sensors; 4th value is alpha-transparency" +V, traces, , , VSettingsSensorTraces, , , PS, "settings for showing (position) sensor traces and vector plots in the render window" # writeFile=VisualizationSettings.h diff --git a/main/src/pythonGenerator/utilitiesDocuGenerator.py b/main/src/pythonGenerator/utilitiesDocuGenerator.py index 8dc44b28..2d8ba585 100644 --- a/main/src/pythonGenerator/utilitiesDocuGenerator.py +++ b/main/src/pythonGenerator/utilitiesDocuGenerator.py @@ -651,6 +651,10 @@ def WriteFunctionDescription2LatexRST(functionDict, moduleNamePython, pythonFile pyiExtensions = {} #for stub files of C++ extension functions pyExtensions = '' #for extension of C++ class, added lateron to mainSystemExtensions; ONLY one string +#special strings, to put MainSystemExtensions (CreateMassPoint, ...) on top of RST and Latex description! +latexExtensionsMainSystem = '' +rstExtensionsMainSystem = '' + with open('mainSystemExtensionsHeader.py','r') as f: pyExtensions = f.read() @@ -762,24 +766,32 @@ def WriteFunctionDescription2LatexRST(functionDict, moduleNamePython, pythonFile #exu.MainSystem.PlotSensor = exu.plot.PlotSensor moduleAdd = ('exu.'+moduleNamePython+'.')*(moduleNamePython!='mainSystemExtensions') - + sPy = '\n#link '+belongsTo+' function to Python function:\n' sPy += 'exu.'+belongsTo+'.'+funcDict['functionName']+ '=' + moduleAdd+functionName + '\n\n' - - latexExtensions[belongsTo] += sFuncLatex+'\n' - rstExtensions[belongsTo] += '\n'+sFuncRST + + latexTemp = '' + rstTemp = '' + latexTemp += sFuncLatex+'\n' + rstTemp += '\n'+sFuncRST pyiExtensions[belongsTo] += sPyi pyExtensions += sPy - + if addExampleReferences: - latexExtensions[belongsTo] += sExamples - rstExtensions[belongsTo] += '\n'+sExamplesRST + latexTemp += sExamples + rstTemp += '\n'+sExamplesRST #for original function description: - funcDict['function'] = functionDescription funcDict['functionName'] = functionName + if moduleNamePython != 'mainSystemExtensions': + latexExtensions[belongsTo] += latexTemp + rstExtensions[belongsTo] += rstTemp + else: + latexExtensionsMainSystem += latexTemp + rstExtensionsMainSystem += rstTemp + #add remaining part to original latex and RST if moduleNamePython != 'mainSystemExtensions': #no description for this! [sFuncLatex, sFuncRST, sPyi, sPy] = WriteFunctionDescription2LatexRST(funcDict, moduleNamePython, fileName, @@ -961,6 +973,18 @@ def WriteFunctionDescription2LatexRST(functionDict, moduleNamePython, pythonFile file.write(pyiExtensions[key]) file.close() +#%%++++++++++++++++++++++ +if True: + file=io.open('generated/MainSystemCreateExt.rst','w',encoding='utf8') #clear file by one write access + file.write(rstExtensionsMainSystem) + file.close() + + file=io.open(theDocDir+'/MainSystemCreateExt.tex','w',encoding='utf8') #clear file by one write access + file.write(latexExtensionsMainSystem) + file.close() + + +#%%++++++++++++++++++++++ file=io.open(fileDir+'mainSystemExtensions.py','w',encoding='utf8') #clear file by one write access file.write(pyExtensions)