Skip to content

Commit

Permalink
create new release; for changes, see issues and bugs section in theDo…
Browse files Browse the repository at this point in the history
…c.pdf
  • Loading branch information
jgerstmayr committed Mar 6, 2024
1 parent 8e36086 commit 05de550
Show file tree
Hide file tree
Showing 35 changed files with 447 additions and 46 deletions.
2 changes: 1 addition & 1 deletion README.rst
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Exudyn

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

Exudyn version = 1.7.121.dev1 (Hall)
Exudyn version = 1.8.0 (Jones)

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

Expand Down
4 changes: 2 additions & 2 deletions docs/RST/Examples/openAIgymNLinkContinuous.rst
Original file line number Diff line number Diff line change
Expand Up @@ -357,7 +357,7 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
model.save("solution/" + modelName)
else:
import torch #stable-baselines3 is based on pytorch
n_cores= os.cpu_count()-1 #should be number of real cores (not threads)
n_cores= max(1,int(os.cpu_count()/2-1)) #should be number of real cores (not threads)
torch.set_num_threads(n_cores) #seems to be ideal to match the size of subprocVecEnv
print('using',n_cores,'cores')
Expand All @@ -373,7 +373,7 @@ You can view and download this file on Github: `openAIgymNLinkContinuous.py <htt
ts = -time.time()
print('start learning of agent with {}'.format(str(model.policy).split('(')[0]))
# model.learn(total_timesteps=50000)
model.learn(total_timesteps=int(1e6))
model.learn(total_timesteps=int(1_000_000))
print('*** learning time total =',ts+time.time(),'***')
#save learned model
Expand Down
7 changes: 4 additions & 3 deletions docs/RST/Examples/symbolicUserFunctionMasses.rst
Original file line number Diff line number Diff line change
Expand Up @@ -125,11 +125,12 @@ You can view and download this file on Github: `symbolicUserFunctionMasses.py <h
listUF = []
if True:
isNew=1
for cc in cList:
if useSymbolicUF:
#create separate user function for each spring-damper!
symbolicFunc = CreateSymbolicUserFunction(mbs, springForceUserFunction, 'springForceUserFunction', cList[0])
symbolicFunc.TransferUserFunction2Item(mbs, cc, 'springForceUserFunction')
#create separate user function for each spring-damper (multithreading)!
symbolicFunc = CreateSymbolicUserFunction(mbs, springForceUserFunction, 'springForceUserFunction', cc)
mbs.SetObjectParameter(cc, 'springForceUserFunction', symbolicFunc)
listUF += [symbolicFunc] #store, such that they are not deleted!!!
else:
mbs.SetObjectParameter(cc, 'springForceUserFunction', springForceUserFunction)
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/Exudyn.rst
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Exudyn

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

Exudyn version = 1.7.121.dev1 (Hall)
Exudyn version = 1.8.0 (Jones)

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

Expand Down
4 changes: 2 additions & 2 deletions docs/RST/TestModels/revoluteJointprismaticJointTest.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,10 @@
.. _testmodels-revolutejointprismaticjointtest:

**********************************
revoluteJointprismaticJointTest.py
revoluteJointPrismaticJointTest.py
**********************************

You can view and download this file on Github: `revoluteJointprismaticJointTest.py <https://github.com/jgerstmayr/EXUDYN/tree/master/main/pythonDev/TestModels/revoluteJointprismaticJointTest.py>`_
You can view and download this file on Github: `revoluteJointPrismaticJointTest.py <https://github.com/jgerstmayr/EXUDYN/tree/master/main/pythonDev/TestModels/revoluteJointPrismaticJointTest.py>`_

.. code-block:: python
:linenos:
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/TestModelsIndex.rst
Original file line number Diff line number Diff line change
Expand Up @@ -64,7 +64,7 @@ This section includes all TestModels for Exudyn.They can also be found and downl
TestModels/plotSensorTest
TestModels/postNewtonStepContactTest
TestModels/reevingSystemSpringsTest
TestModels/revoluteJointprismaticJointTest
TestModels/revoluteJointPrismaticJointTest
TestModels/rigidBodyAsUserFunctionTest
TestModels/rigidBodyCOMtest
TestModels/rigidBodySpringDamperIntrinsic
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/cInterface/GeneralContact.rst
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ Structure to define general and highly efficient contact functionality in multib
gContact.UpdateContacts(mbs)
* | **GetActiveContacts**\ (\ *typeIndex*\ , \ *itemIndex*\ ):
| Get list of global item numbers which are in contact with itemIndex of type typeIndex in case that the global itemIndex is smaller than the abs value of the contact pair index; a negative sign indicates that the contacting (spheres) is in Coloumb friction, a positive sign indicates a regularized friction region; for interpretation of global contact indices, see gContact.GetPythonObject() and documentation; requires either implicit contact computation or UpdateContacts(...) needs to be called prior to this function
| Get list of global item numbers which are in contact with itemIndex of type typeIndex in case that the global itemIndex is smaller than the abs value of the contact pair index; a negative sign indicates that the contacting (spheres) is in Coloumb friction, a positive sign indicates a regularized friction region; in case of itemIndex==-1, it will return the list of numbers of active contacts per item for the contact type; for interpretation of global contact indices, see gContact.GetPythonObject() and documentation; requires either implicit contact computation or UpdateContacts(...) needs to be called prior to this function
| *Example*:
.. code-block:: python
Expand Down
2 changes: 2 additions & 0 deletions docs/RST/cInterface/MainSystem.rst
Original file line number Diff line number Diff line change
Expand Up @@ -98,6 +98,8 @@ This is the class which defines a (multibody) system. The MainSystem shall only
| delete GeneralContact with index generalContactNumber in mbs; other general contacts are resorted (index changes!)
* | **NumberOfGeneralContacts**\ ():
| Return number of GeneralContact objects in mbs
* | **GetAvailableFactoryItems**\ ():
| get all available items to be added (nodes, objects, etc.); this is useful in particular in case of additional user elements to check if they are available; the available items are returned as dictionary, containing lists of strings for Node, Object, etc.
* | **GetDictionary**\ ():
| [UNDER DEVELOPMENT]: return the dictionary of the system data (todo: and state), e.g., to copy the system or for pickling
* | **SetDictionary**\ (\ *systemDict*\ ):
Expand Down
2 changes: 1 addition & 1 deletion docs/RST/confHelper.py
Original file line number Diff line number Diff line change
Expand Up @@ -3,5 +3,5 @@

listClassNames=['SystemContainer', 'MainSystem', 'SystemData', 'symbolic.Real', 'symbolic.Vector', 'symbolic.Matrix', 'symbolic.VariableSet', 'symbolic.UserFunction', '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', 'Demo1', 'Demo2', 'InvalidIndex', 'Reset', 'AddSystem', 'Append', 'NumberOfSystems', 'GetSystem', 'GetDictionary', 'SetDictionary', 'GetRenderState', 'SetRenderState', 'RedrawAndSaveImage', 'WaitForRenderEngineStopFlag', 'RenderEngineZoomAll', 'AttachToRenderEngine', 'DetachFromRenderEngine', 'SendRedrawSignal', 'GetCurrentMouseCoordinates', 'Assemble', 'AssembleCoordinates', 'AssembleLTGLists', 'AssembleInitializeSystemCoordinates', 'AssembleSystemInitialize', 'GetSystemContainer', 'WaitForUserToContinue', 'GetRenderEngineStopFlag', 'SetRenderEngineStopFlag', 'ActivateRendering', 'SetPreStepUserFunction', 'GetPreStepUserFunction', 'SetPostStepUserFunction', 'GetPostStepUserFunction', 'SetPostNewtonUserFunction', 'GetPostNewtonUserFunction', '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', '__init__', 'SetValue', 'Evaluate', 'Diff', 'isfinite', 'abs', 'round', 'ceil', 'floor', 'sqrt', 'exp', 'log', 'sin', 'cos', 'tan', 'asin', 'acos', 'atan', 'sinh', 'cosh', 'tanh', 'asinh', 'acosh', 'atanh', 'sign', 'Not', 'min', 'max', 'mod', 'pow', 'IfThenElse', 'SetRecording', 'GetRecording', 'SetVector', 'NumberOfItems', 'NormL2', 'MultComponents', 'SetMatrix', 'NumberOfRows', 'NumberOfColumns', 'Add', 'Set', 'Get', 'Exists', 'GetNames', '__setitem__', '__getitem__', 'SetUserFunctionFromDict', 'GetPythonObject', 'SetFrictionPairings', 'SetFrictionProportionalZone', 'SetSearchTreeCellSize', 'SetSearchTreeBox', 'AddSphereWithMarker', 'AddANCFCable', 'AddTrianglesRigidBodyBased', 'GetItemsInBox', 'GetSphereMarkerBased', 'SetSphereMarkerBased', 'GetTriangleRigidBodyBased', 'SetTriangleRigidBodyBased', 'ShortestDistanceAlongLine', 'UpdateContacts', 'GetActiveContacts', 'GetSystemODE2RhsContactForces', 'SetWithDenseMatrix', 'SetWithSparseMatrixCSR', 'Convert2DenseMatrix', 'UseDenseMatrix', '__len__', '__copy__', '__deepcopy__', 'visualizationSettings', 'systemData', 'systemIsConsistent', 'interactiveMode', ]
listFunctionNames=['GetVersionString', 'Help', 'RequireVersion', 'StartRenderer', 'StopRenderer', 'IsRendererActive', 'DoRendererIdleTasks', 'SolveStatic', 'SolveDynamic', 'ComputeODE2Eigenvalues', 'SetOutputPrecision', 'SetLinalgOutputFormatPython', 'SetWriteToConsole', 'SetWriteToFile', 'SetPrintDelayMilliSeconds', 'Print', 'SuppressWarnings', 'InfoStat', 'Go', 'Demo1', 'Demo2', 'InvalidIndex', 'Reset', 'AddSystem', 'Append', 'NumberOfSystems', 'GetSystem', 'GetDictionary', 'SetDictionary', 'GetRenderState', 'SetRenderState', 'RedrawAndSaveImage', 'WaitForRenderEngineStopFlag', 'RenderEngineZoomAll', 'AttachToRenderEngine', 'DetachFromRenderEngine', 'SendRedrawSignal', 'GetCurrentMouseCoordinates', 'Assemble', 'AssembleCoordinates', 'AssembleLTGLists', 'AssembleInitializeSystemCoordinates', 'AssembleSystemInitialize', 'GetSystemContainer', 'WaitForUserToContinue', 'GetRenderEngineStopFlag', 'SetRenderEngineStopFlag', 'ActivateRendering', 'SetPreStepUserFunction', 'GetPreStepUserFunction', 'SetPostStepUserFunction', 'GetPostStepUserFunction', 'SetPostNewtonUserFunction', 'GetPostNewtonUserFunction', 'AddGeneralContact', 'GetGeneralContact', 'DeleteGeneralContact', 'NumberOfGeneralContacts', 'GetAvailableFactoryItems', '__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', '__init__', 'SetValue', 'Evaluate', 'Diff', 'isfinite', 'abs', 'round', 'ceil', 'floor', 'sqrt', 'exp', 'log', 'sin', 'cos', 'tan', 'asin', 'acos', 'atan', 'sinh', 'cosh', 'tanh', 'asinh', 'acosh', 'atanh', 'sign', 'Not', 'min', 'max', 'mod', 'pow', 'IfThenElse', 'SetRecording', 'GetRecording', 'SetVector', 'NumberOfItems', 'NormL2', 'MultComponents', 'SetMatrix', 'NumberOfRows', 'NumberOfColumns', 'Add', 'Set', 'Get', 'Exists', 'GetNames', '__setitem__', '__getitem__', 'SetUserFunctionFromDict', 'GetPythonObject', 'SetFrictionPairings', 'SetFrictionProportionalZone', 'SetSearchTreeCellSize', 'SetSearchTreeBox', 'AddSphereWithMarker', 'AddANCFCable', 'AddTrianglesRigidBodyBased', 'GetItemsInBox', 'GetSphereMarkerBased', 'SetSphereMarkerBased', 'GetTriangleRigidBodyBased', 'SetTriangleRigidBodyBased', 'ShortestDistanceAlongLine', 'UpdateContacts', 'GetActiveContacts', 'GetSystemODE2RhsContactForces', 'SetWithDenseMatrix', 'SetWithSparseMatrixCSR', 'Convert2DenseMatrix', 'UseDenseMatrix', '__len__', '__copy__', '__deepcopy__', 'visualizationSettings', 'systemData', 'systemIsConsistent', 'interactiveMode', ]

44 changes: 44 additions & 0 deletions docs/RST/items/MarkerBodyPosition.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,50 @@ The item VMarkerBodyPosition has the following parameters:

DESCRIPTION of MarkerBodyPosition
---------------------------------
The body position marker provides an interface to a object of type body
(\ ``ObjectGround``\ , \ ``ObjectMassPoint``\ , \ ``ObjectRigidBody``\ , ...)
and provides access to kinematic quantities such as \ **position**\ and \ **velocity**\
and to the \ **position jacobian**\ , using a \ ``localPosition``\ \ :math:`\pLocB`\ which is defined within the
local coordinates of the body (\ :math:`b`\ ).
The kinematic quantities are computed according to the definition of output variables in the respective bodies.

The position jacobian represents the derivative of the node position \ :math:`{\mathbf{p}}_\mathrm{n}`\ with all nodal coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}} = \frac{\partial \LU{0}{{\mathbf{p}}_\mathrm{n}}}{\partial {\mathbf{q}}_\mathrm{n}}
and it is usually computed as the derivative of the (global) translational velocity w.r.t.\ velocity coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}} = \frac{\partial \LU{0}{{\mathbf{v}}_\mathrm{n}}}{\partial \dot {\mathbf{q}}_\mathrm{n}}
As an example of the \ ``ObjectRigidBody2D``\ , see Section :ref:`sec-item-objectrigidbody2d`\ , the position and velocity are computed as

.. math::
\LU{0}{{\mathbf{p}}}\cConfig(\pLocB) = \LU{0}{\pRef}\cConfig + \LU{0}{\pRef}\cRef + \LU{0b}{\Rot}\pLocB ,
.. math::
\LU{0}{{\mathbf{v}}}\cConfig(\pLocB) = \LU{0}{\dot{\mathbf{u}}}\cConfig + \LU{0b}{\Rot}(\LU{b}{\tomega} \times \pLocB\cConfig) .
Thus, the position jacobian for \ ``ObjectRigidBody2D``\ reads

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}^{\mathrm{NodeRigidBody2D}}} = \mr{1}{0}{-\sin\theta_0 \LU{b}{b_0} - \cos\theta_0 \LU{b}{b_1}} {0}{1}{\cos\theta_0 \LU{b}{b_0} - \sin\theta_0 \LU{b}{b_1}} {0}{0}{0}
For details, see the respective definition of the body and the C++ implementation.


Relevant Examples and TestModels with weblink:

Expand Down
24 changes: 24 additions & 0 deletions docs/RST/items/MarkerNodePosition.rst
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,30 @@ The item VMarkerNodePosition has the following parameters:

DESCRIPTION of MarkerNodePosition
---------------------------------
The node position marker provides an interface to a node which contains a position
(\ ``NodePoint``\ , \ ``NodePoint2D``\ , \ ``NodeRigidBodyEP``\ , \ ``NodePointSlope``\ , ...)
and accesses \ **position**\ , \ **velocity**\ and the \ **position jacobian**\ .
The position and velocity are computed according to the definition of output variables in the respective nodes.

The position jacobian represents the derivative of the node position \ :math:`{\mathbf{p}}_\mathrm{n}`\ with all nodal coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}} = \frac{\partial \LU{0}{{\mathbf{p}}_\mathrm{n}}}{\partial {\mathbf{q}}_\mathrm{n}}
For details, see the respective definition of the node and the C++ implementation.

In examplary case of a \ ``NodeRigidBody2D``\ , see Section :ref:`sec-item-noderigidbody2d`\ , its coordinates are
\ :math:`{\mathbf{q}}_\mathrm{n}=[q_0,\;q_1,\;\psi_0,\;]\tp`\ , where \ :math:`q_0`\ represents the \ :math:`x`\ -displacement
and \ :math:`q_1`\ represents the \ :math:`y`\ -displacement, such that the jacobian for the 3D position vector reads

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}^{\mathrm{NodeRigidBody2D}}} = \mr{1}{0}{0} {0}{1}{0} {0}{0}{0}
Relevant Examples and TestModels with weblink:

Expand Down
30 changes: 30 additions & 0 deletions docs/RST/items/MarkerNodeRigid.rst
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,36 @@ The item VMarkerNodeRigid has the following parameters:

DESCRIPTION of MarkerNodeRigid
------------------------------
The node rigid body marker provides an interface to a node which contains a position and an orientation
(\ ``NodeRigidBodyEP``\ , \ ``NodeRigidBody2D``\ , ...)
and provides access to kinematic quantities such as \ **position**\ , \ **velocity**\ , \ **orientation**\ (rotation matrix),
\ **angular velocity**\ . It also provides the \ **position jacobian**\ and the \ **rotation jacobian**\ .
The kinematic quantities are computed according to the definition of output variables in the respective nodes.

The position jacobian represents the derivative of the node position \ :math:`{\mathbf{p}}_\mathrm{n}`\ with all nodal coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}} = \frac{\partial \LU{0}{{\mathbf{p}}_\mathrm{n}}}{\partial {\mathbf{q}}_\mathrm{n}}
and it is usually computed as the derivative of the (global) translational velocity w.r.t.\ velocity coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{pos}} = \frac{\partial \LU{0}{{\mathbf{v}}_\mathrm{n}}}{\partial \dot {\mathbf{q}}_\mathrm{n}}
The rotation jacobian is computed as the derivative of the (global) angular velocity w.r.t.\ velocity coordinates,

.. math::
\LU{0}{{\mathbf{J}}_\mathrm{rot}} = \frac{\partial \LU{0}{\tomega_\mathrm{n}}}{\partial \dot {\mathbf{q}}_\mathrm{n}}
This usually results in the velocity transformation matrix.
For details, see the respective definition of the node and the C++ implementation.


Relevant Examples and TestModels with weblink:

Expand Down
Loading

0 comments on commit 05de550

Please sign in to comment.