5.8.2.3. Rigid Dynamics Command Objects Library

The following Rigid Dynamics command objects are available:

Actuator

The actuator is the base class for all Loads, Body Loads, and Drivers.

ID table: CS_Actuator

Members:
Condition

All actuators can be conditional. See Condition to create this condition.

AppliedValue

Measure that stores the evaluation of the actuator variable. Can be useful when the applied value depends on a measure other than time.

EnergyMeasure

Measure that stores the energy generated by the actuator.

Member Functions:

There are two ways to define the value of the load: using a variable, or by defining a table of input measures (in which case a variable is defined automatically).

SetVariable(variable)

variable is a list of input measures in table form.

SetInputMeasure(measure)

measure is typically the time measure object, but other measures can be used as well. When using an expression to define a load variation, the measure must have only one component (it cannot be a vector measure). The variation can be defined by a constant, an expression, or a table.

SetConstantValues(value)

value is a Python float constant. See Relation object for defining a constant.

SetTable(table)

table is a CS_Table .

SetFunc(string, is_degree)

string is similar to the expression used in the user interface to define a joint condition by a function. Note that the literal variable is always called time, even if you are using another measure as input.

is_degree is a boolean argument. If the expression uses trigonometric function, it specifies that the input variable should be expressed in degrees.

Basis

A basis is a material frame moving with a body. Each coordinate system has a basis, but multiple coordinate systems can share the same basis.

ID table: CS_Basis

Constructors:
CS_Basis()
CS_Basis(Angle1, Angle2, Angle3)
Members:
double [,]Matrix

Sets or gets function of the transformation matrix

Body

A body corresponds to a Part in the geometry node of the Mechanical tree, or can be created by a command snippet. The preset _bid variable can be used to find a corresponding body.

ID table: CS_Body

Example:

MyBody = CS_Body.Find(_bid)
print MyBody.Name

Constructors:
CS_Body()
CS_Body(Id)
Members:
Name

Name of the body.

Origin

Origin Coordinate System of the body. This Coordinate System is the moving coordinate system of one of the joints connected to the body. The choice of this joint, called parent joint, is the result of an optimization that minimizes the number of degrees of freedom of the system.

InertiaBodyCoordinateSystem

Inertia body coordinate system of the body.

BodyType

Type of body, values in E_UnknownType, E_Ground, E_Rigid, E_CMS, E_General, E_Fictitious, E_RigidLeaf, E_RigidSubModel, E_PointMass, E_Beam

Member Functions:
SetMassAndInertia(double mass, double Ixx, double Iyy, double Izz, double Ixy, double Iyz, double Ixz)

Overwrites the mass and inertia values of a body.

SetCenterOfMassAndOrientationAngles(double Xg, double Yg, double Zg, double XYAngle, double YZAngle, double XZAngle) and SetCenterOfMassAndOrientationMatrix(double Xg, double Yg, double Zg, double mxx, double mxy, double mxz, double myx, double myy, double myz, double mzx, double mzy, double mzz)

Overwrites the position of the center of mass and the orientation of the inertia coordinate system.

SetVariableMassAndPrincipalInertia(CS_Variable mass, CS_Variable Ixx, CS_Variable Iyy, CS_Variable Izz)

Overwrites the constant mass and principal inertia properties by variable properties. During the solution process, the mass and inertia variation rate needs to be evaluated. Therefore, only Point Table, Polynomial and Function can be used to define the variation. Python user tables cannot be used to define kinetic properties variations. You can make some of the properties (mass, Ixx, Iyy and Izz) constants by using constant variables.


Note:  The principal axis needs to be defined when the principal inertia is being assigned. If the body is created by a command, SetCenterOfMassAndOrientationAngles or SetCenterOfMassAndOrientationMatrix must be called before calling SetVariableMassAndPrincipalInertia.


This function only applies to rigid bodies.


Note:  All quantities used in the solver must use a consistent unit system, which sometimes differs from the user interface unit system. For example if the user interface unit system is "mm,kg,N,s", the solver unit system will be “mm,t,N,s". When using SetMassAndInertia or SetVariableMassAndPrincipalInertia, the values of mass and inertia have to be entered using the solver unit system.


Derived Classes:

CS_FlexibleBody

Body Coordinate System

The body coordinate system is used to connect a body to joints, hold the center of mass, or define a load. See Joint or Body to access existing coordinate systems. Coordinate systems can also be created.

ID table: CS_BodyCoordinateSystem

Constructors:
CS_BodyCoordinateSystem(body, type, xyz, basis)
Members:

Basis

Member Functions:
RotateArrayThroughTimeToLocal(MeasureValues)

Rotates the transient values of a measure to a coordinate system. MeasureValues is a python two-dimensional array, such as that coming out of FillValuesThroughTime or FillDerivativesThroughTime. This function works for 3D vectors such as relative translation between two coordinate systems or 6-D vectors such as forces/moments.

RotateArrayThroughTimeToGlobal(MeasureValues)

Rotates the transient values of a measure from a coordinate system to the global coordinate system.

Type

Type of coordinate system, values in E_Unknown, E_Ground, E_Part, E_Joint, E_Inertia, E_BodyTransform, E_Contact, E_SplitJoint.

Derived Classes:

None

Example:

forceInGlobal=joint.GetForce()

valuesInGlobal=forceInGlobal.FillValuesThroughTime()

for i in range(0,valuesInGlobal.GetLength(0)):
    print '{0:e} {1:e} {2:e} {3:e}'.format(valuesInGlobal[i,0],
	valuesInGlobal[i,1],valuesInGlobal[i,2],valuesInGlobal[i,3])

mobileCS=joint.MobileCoordinateSystem

valuesInLocal=valuesInGlobal.Clone()

mobileCS.RotateArrayThroughTimeToLocal(valuesInLocal)

for i in range(0,valuesInGlobal.GetLength(0)):
    print '{0:e} {1:e} {2:e} {3:e}'.format(valuesInLocal[i,0],
    valuesInLocal[i,1],valuesInLocal[i,2],valuesInLocal[i,3])

Body Load

A body load is a load that is applied to all bodies in the system. Gravity or global acceleration are body loads.

The body load must implement a GetAccelerationVector method. This vector is applied to the center of mass of each body. In order to maintain the energy balance of the system, the body load must also implement a ComputeEnergy method.

Example: Acceleration varying with time

HalfTime = 1.0
HalfAmplitude = 10.0

Env=CS_Environment.GetDefault() 
Sys=Env.System
(ret,found,time) = Sys.FindOrCreateInternalMeasure(CS_Measure.E_MeasureType.E_Time) 

class MyBodyLoad(CS_UserBodyLoad):
    def __init__(self):
        CS_UserBodyLoad.__init__(self)
        self.value = 0.0

    def GetAccelerationVector(self,Mass,xyz,vel,bodyLoadForce):
        values = time.Values
        print 'MyBodyLoad::GetAccelerationVector'
        bodyLoadForce[0] = 0.0
        bodyLoadForce[1] = 0.0
        bodyLoadForce[2] = Mass*HalfAmplitude*math.sin(values[0]*3.14/(2.*HalfTime))

    def ComputeEnergy(self,Mass,xyz,vel):
        print 'MBodyLoad::ComputeEnergy'
        return 0.0

load=MyBodyLoad()
load.value = 10.0

Env=CS_Environment.GetDefault()

Env.BodyLoads.Add(load)
CMSBody

A CMSBody represents a condensed part in the Mechanical tree.

Constructors:

None.

Members:
CondensedPartId (read only)

The ID of the condensed part in the Mechanical tree.

PartIds (read only)

The vector of the IDs of the Mechanical parts that are used in the condensed part.

Member Functions:

None.

Derived Classes:

None.

Condition

Condition causes a load or a joint condition to be active only under defined circumstances. A condition is expressed in one of the following forms:

  1. MeasureComponent operator threshold

  2. LeftThreshold < MeasureComponent < RightThreshold

  3. LeftCondition operator RightCondition

For case 1:

  • MeasureComponent is a scalar Measure.

  • Operator is one of the following math operators:

    E_GreaterThan
    E_LessThan
    E_DoubleEqual
    E_ExactlyEqual
  • Threshold is the threshold value.


Note:  A condition cannot be shared between various actuators. For example, if two joint conditions must be deactivated at the same time, two conditions must be created.


Example:

DispCond = CS_Condition(CS_Condition.E_ConditionType.E_GreaterThan,DispX,0.1)

For case 2:

  • MeasureComponent is a scalar Measure.

  • LeftThreshold and RightThreshold are the bounds within which the condition will be true.

Example:

RangeCond = CS_Condition(DispX,0.0,0.1)

For case 3:

  • LeftThreshold and RightThreshold are two conditions (case 1, 2 or 3).

  • Operator is one of the following boolean operators:

    E_Or
    E_And

Example:

BoolCond = CS_Condition(CS_Condition.E_ConditionType.E_Or, RangeCond, DispCond)

Contact

A Contact corresponds to a contact pair between two bodies.

Corresponding ID table: CS_Contact


Note:  If multiple contact objects have been defined between the same two bodies (with different surfaces), the solver merges them into one single pair. In that case, only one of the contact pairs exists and the call to CS_Contact.Find(_cid) will fail for all contact objects other than the one that was used to handle the pair of bodies.


Constants:

None

Members:

None

Member Functions:
GetOutputContactForce()

Retrieves a measure that contains the total contact force between the two linked bodies.

ContactDebugMask

The ContactDebugMask object allows you to activate and customize the output of contact points. It can also be used to modify the default behaviour of contact. ContactDebugMask uses a set of switches that can be toggled on or off.

ID table: CS_ContactDebugMask

Constants:
        E_DEBUG_Flag.E_None,
   (*)E_DEBUG_Flag.E_Point1: point on the side 1 (contact)
     E_DEBUG_Flag.E_Point2: point on the side 2 (target)
     E_DEBUG_Flag.E_Normal: contact normal
     E_DEBUG_Flag.E_Normal1: normal on side 1 (Reference)
     E_DEBUG_Flag.E_Normal2: normal on side 2 (Target)
     E_DEBUG_Flag.E_Violation: contact violation (rd.n = P1P2.n)
     E_DEBUG_Flag.E_MaterialVelocity: material normal velocity (V2-V1).n
  (*)E_DEBUG_Flag.E_TotalVelocity: total normal velocity (material velocity + sliding velocity)
     E_DEBUG_Flag.E_EntityId1: geometric entity Id on side 1 (contact)
     E_DEBUG_Flag.E_EntityId2: geometric entity Id on side 2 (target)
     E_DEBUG_Flag.E_SurfaceId1: surface Id on side 1 (contact)
     E_DEBUG_Flag.E_SurfaceId2: surface Id on side 2 (target)
  (*)E_DEBUG_Flag.E_EntityType: type of geometric entities (vertex/edge/surface)
  (*)E_DEBUG_Flag.E_GeometricStatus: status of the contact position and velocity (touching,separated,...)
     E_DEBUG_Flag.E_Accepted: points that are finally kept
     E_DEBUG_Flag.E_InconsistentPoint: points not consistent with rank analysis
     E_DEBUG_Flag.E_ReceivedPoint: all points send by the contact
     E_DEBUG_Flag.E_DeletedPoint: points deleted during Geometric Filtering
     E_DEBUG_Flag.E_TrackedPoint: points successfully tracked
     E_DEBUG_Flag.E_TrackedPointFailure: points that failed for tracking
     E_DEBUG_Flag.E_NormalAngle: angle between normal (in degrees)
     E_DEBUG_Flag.E_SlidingVelocity1: sliding velocity on side 1 (contact) in global coordinates 
     E_DEBUG_Flag.E_SlidingVelocity2: sliding velocity on side 2 (target) in global coordinates
     E_DEBUG_Flag.E_FailSafeFilteringMode: adjust contact radius to accept at least one point
     E_DEBUG_Flag.E_CheckIntegration: check consistency of integration between solver and contact
     E_DEBUG_Flag.E_RankAnalysis: result from rank analysis
     E_DEBUG_Flag.E_Transition: result from edge transitions analysis
  (*)E_DEBUG_Flag.E_NewTimeStep: at beginning of time step 
     E_DEBUG_Flag.E_BeforeCorrection: before external loop of correction 
     E_DEBUG_Flag.E_BeforeCorrectionPlus: before geometric correction
     E_DEBUG_Flag.E_All
Members:

None

Member Functions:
SetOn(E_DEBUG_Flag flag)

Enable output of contact points information specified by flag.

SetOff(E_DEBUG_Flag flag)

Disable output of contact points information specified by flag.

Example:

CS_ContactDebugMask.SetOn(E_DEBUG_Flag.E_Accepted)

ContactOptions

The ContactOptions object allows you to customize the behaviour of a contact server. ContactOptions uses a set of numerical values (real or integer) that can be get or set. When used as a switch, 0 means off and 1 is on.

Constants:

None

Members:
TimeOut

Time in second (=30.0 by default)

Verbose

Enable verbose mode in contact.out file (=0, disabled by default)

NumberOfThreads

Number of parallel threads used for contact detection (=2 by default)

Member Functions:

None

Example:

cOpts=CS_ContactOptions()
cOpts.Verbose=1

Driver

A driver is a position, velocity or acceleration, or translational or rotational joint condition. Drivers derive from the Actuator class.

Corresponding ID table: CS_Actuator

Constants:

E_Acceleration, E_Position, E_Velocity

Members:

None

Member Functions:
CS_Driver(CS_Joint joint, int[] components, E_MotionType driverMotionType)

Creation of a joint driver, on joint joint, degree of freedom components, and with motion type driverMotionType. Note that the same driver can prescribe more than one joint motion at the same time. This is useful if you want to add the same condition to all components of a prescribed motion for example. Components must be ordered, are zero based, and refer to the actual free degrees of freedom of the joint.

Environment

This is the top level of the Rigid Dynamics model.

ID table: CS_Environment

Members:
System:

Corresponding system.

Example:

Env=CS_Environment.FindFirstNonNull()
Sys = Env.System

Ground:

Ground body.

Example:

Env = CS_Environment.FindFirstNonNull()
Ground = Env.Ground
Loads:

The vector of existing loads. This includes Springs that are considered by the solver as loads, as well as force and torque joint conditions.

Example:

Xdof = 0
Friction=CS_JointDOFLoad(PlanarJoint,Xdof)
Env.Loads.Add(Friction)

BodyLoads:

The vector of Body Loads.

Example:

MyBodyLoad = CS_BodyLoad()
…
Env.BodyLoads.Add(MyBodyLoad)
Relations:

The vector of external constraint equations.

Example:

rel3=CS_Relation()
rel3.MotionType=CS_Relation.E_MotionType.E_Velocity

var30=CS_ConstantVariable()
var30.SetConstantValues(System.Array[float]([0.]))

var31=CS_ConstantVariable()
var31.SetConstantValues(System.Array[float]([23.]))

var32=CS_ConstantVariable()
var32.SetConstantValues(System.Array[float]([37.]))

var33=CS_ConstantVariable()
var33.SetConstantValues(System.Array[float]([-60.+37.]))

rel3.SetVariable(var30)
rel3.AddTerm(jp,0,var31)
rel3.AddTerm(js3,0,var32)
rel3.AddTerm(jps,0,var33)

Env.Relations.Add(rel3)

Drivers:

The vector of Displacements, Velocity and Acceleration joint conditions.

InitialConditions:

The vector of Displacements, Velocity, and Acceleration joint conditions to be used only at time=0.

PotentialEnergy:

Gets the Potential Energy Measure.

KineticEnergy:

Gets the Kinetic Energy Measure.

TotalEnergy:

Gets the Total Energy Measure.

ActuatorEnergy:

Gets the Actuator Energy Measure.

RestartTime

Specifies the starting time in a restart analysis

Member Functions:
FindFirstNonNull():

Returns the first environment in the global list. The table usually contains only one environment, thus it is a common way to access the current environment.

Example:

Env=CS_Environment.FindFirstNonNull()

AlterSimulationEndTime(endTime)

Overwrites the end time of the simulation.

Solve()

Solves the current analysis.

Derived Classes:

None

FlexibleBody

A Flexible Body is used by RBD for bodies that have flexible behavior, for instance a CMSBody.

Constructors:

None.

Members:
AlphaDamping

Uses a variable to define the amount of alpha Rayleigh damping (proportional to the mass matrix) to be considered for the flexible body. The variable can be either dependent or constant.

Example:

aFlexibleBody.AlphaDamping=100

Or equivalently:

var=CS_Variable()
var.SetConstantValues(System.Array[float]([100.]))
aFlexibleBody.AlphaDamping=var
BetaDamping

Uses a variable to define the amount of beta Rayleigh damping (proportional to the mass matrix) to be considered for the flexible body. The variable can be either dependent or constant.

Example:

Env=CS_Environment.GetDefault()
Sys=Env.System
 
array=System.Array.CreateInstance(float,4,2)
array[0,0]=0.0
array[0,1]=5.e-6
array[1,0]=0.05
array[1,1]=5.e-6
array[2,0]=0.051
array[2,1]=1.e-4
array[3,0]=0.1
array[3,1]=1.e-4
 
table=CS_PointsTable(array)
 
(err,found,time)=Sys.FindOrCreateInternalMeasure(CS_Measure.E_MeasureType.E_Time)
 
var=CS_Variable()
var.AddInputMeasure(time)
var.SetTable(table)
 
aFlexibleBody.BetaDamping = var
CMatrixScaleFactor

Define a factor to be used to multiply the default damping matrix. For instance, with a CMSBody, this matrix can be created during the generation pass. When the damping matrix is generated for a Condensed Part (CMSBody), it will be automatically taken into account in the RBD use pass with a factor equal to 1.0.

Member Functions:
SetModalDamping(iDof, variable)

Define the amount of damping used for the degree of freedom specified by iDof (index starts at 0). The variable can be either dependent or constant.

GetModalDamping(iDof)

Retrieve the damping variable defined for the degree of freedom iDof (index starts at 0).

SetLoadVectorScaleFactor(iLV, variable)

Define a scale factor applied to the flexible body internal load specified by iLV (index starts at 0). By default, the first load vector uses a constant scale factor equal to 1.0.

GetLoadVectorScaleFactor(iLV, variable)

Retrieve the variable associated to the factor specified by iLV (index starts at 0).

Derived Classes:

CS_CMSBody

GILTable

A general multi-input interpolated table based on an unstructured cloud of points.

Corresponding ID table: CS_GILTable

Member Functions:
CS_GILTable(sizeIn,sizeOut)

Creates a GIL table with sizeIn inputs and sizeOut outputs

CS_GILTable(sizeIn, sizeOut, filename, scale, separator, noHeader)

Creates a GIL table from a text file; filename is the name of the file containing the points (typically a .CSV file). This file must be in ASCII format, with one data point per row. Each row must contain sizeIn + sizeOut columns. The columns must be separated by a character specified by the argument separator. The default value of separator is ,. scale is an optional argument that scales all the output values. The default value, used if the optional argument is not specified, is 1.0. noHeader is a boolean, optional argument that should be true if there is no first row with labels.

Example file:

Velocity, Deflection, Force
0.,0.,10.0
100.,0.,200.0
...
AddInterpolationPoint(values)

Adds an interpolation point to the General Interpolation Table. values is a one dimensional array of size sizeIn+sizeOut. The first sizeIn values in array values corresponds to the values of the input variables. The following sizeOut values in array values correspond to the output values.

Example 5.1: Creation of a Nonlinear Stiffness Value That Depends on Spin Velocity (Omega) and on Deflection (dY)

VarForceY = CS_Variable();
#
# Variable 0: spin
VarForceY.AddInputMeasure(SpinMeasure )
#
# Variable 1: Y displacement
VarForceY.AddInputMeasure( TransY )
# 
# Create table with 2 input and 1 output
EvalY = CS_GILTable(2,1)

Omega = -1.0
dY = -1e-4
stiff = -9.0

values=System.Array.CreateInstance(float,3)

values[0] = Omega
values[1] = dY
values[2] = stiff
EvalY.AddInterpolationPoint( values )

Omega = 11.0
dY = -1e-4
stiff = -21.0
values[0] = Omega
values[1] = dY
values[2] = stiff
EvalY.AddInterpolationPoint( values )
…

AddInterpolationPointArray(values)

Adds a set of points to the General Interpolation Table. values is a two dimensional array of size (numberOfPoints, sizeIn+sizeOut). On each row of the array, first sizeIn values in array values corresponds to the values of the input variables. The following sizeOut values in array values correspond to the output values. Each row contains a single interpolation point in the cloud of points.

Example 5.2: Creation of a Nonlinear Force Value (F) That Depends on Deflection (dX)

ForceVariable = CS_Variable()
ForceVariable.AddInputMeasure( TransX )
Evaluator = CS_GILTable( 1,1 )
values = System.Array.CreateInstance( float, 6, 2 )
dX = 0.0
F = 0.0
values[0,0] = dX
values[0,1] = F

dX = 10.0
F = 1.0
values[1,0] = dX
values[1,1] = F

dX = 30.0
F = 2.0
values[2,0] = dX
values[2,1] = F

dX = 60.0
F = 3.0
values[3,0] = dX
values[3,1] = F

dX = 90.0
F = 4.0
values[4,0] = dX
values[4,1] = F

dX = 130.0
F = 5.0
values[5,0] = dX
values[5,1] = F
Evaluator.AddInterpolationPointArray( values ) 

SetVerbosity(bVerbose)

If bVerbose is set to true, the GILTable will print the output value every time it is evaluated. This can be used for debugging purposes, but it will affect the performance if used on a table in a long simulation.

Limitations:

These tables can only be used to apply forces and moments, not for other joint conditions or remote displacements.

Joint

ID table: CS_Joint

Constants: For the joint type (E_JointType):

E_2DSlotJoint, E_BushingJoint, E_CylindricalJoint, E_GeneralJoint, E_FixedJoint, E_FreeJoint, E_PlanarJoint, E_PointOnCurveJoint, E_RevoluteJoint, E_ScrewJoint, E_SingleRotationGeneralJoint, E_SlotJoint, E_SphericalJoint, E_TranslationalJoint, E_TwoRotationGeneralJoint, E_UniversalJoint,

Members:
Name

Name of the joint

ReferenceCoordinateSystem

Joint reference coordinate system

Example:

J1 = CS_Joint.Find(_jid)
CSR = J1.ReferenceCoordinateSystem

MovingCoordinateSystem

Joint moving coordinate system

Example:

J1 = CS_Joint.Find(_jid)
CSM = J1. MovingCoordinateSystem

Type

Joint type

IsRevert

The internal representation of the joint can use flipped reference and mobile coordinate systems. In that case, all the joint results (for example, forces, moments, rotation, velocities and acceleration) must be multiplied by -1 to go from their internal representation to the user representation. As transient values of joint measures are giving the internal representation, use this IsRevert information to know if results should be negated.

AccelerationFromVelocitiesDerivatives

When extracting joint degrees of freedom on joints that return true, accelerations should be done using the time derivatives of the joint velocity measure. On joints that return false, joint DOF derivatives should be extracted using the joint acceleration measure. It is important to check this flag first. Use of the wrong method to query joint acceleration can result in failure or incorrect results.

Example:

if Universal.AccelerationFromVelocitiesDerivatives:
	UniversalAccelerationValues=UniversalVelocityM.FillDerivativesThroughTime()
else:
	UniversalAcceleration = Universal.GetAcceleration()
	UniversalAccelerationValues=UniversalAcceleration.FillValuesThroughTime()

Stops

Returns the list of the stops defined on the joint.

Member Functions:
GetVelocity()

Returns the joint velocity measure. The size of this measure is the number of degrees of freedom of the joint. The derivatives of this measure give access to the joint accelerations.

GetRotation()

Returns the joint rotation measure. The type of measure depends on the joint number of rotational degrees of freedom (E_1DRotationMeasure, E_3DRotationMeasure, E_UniversalAngles). These rotations components are relative to the reference coordinate system of the joint.

GetTranslation()

Returns the joint translation measure. The length of this measure is the number of translational degrees of freedom of the joint. The translation components are expressed in the reference coordinate system of the joint.

GetForce()

Returns the joint force measure. The length of this measure is always 6 (3 forces components, 3 torque component). This force measure is the total force/moment, including constraint forces/moment, external forces/moment applied to the joint, and joint internal forces/moment, such as elastic moment in a revolute joint that has a stiffness on the Z rotation axis. The force measure components are expressed in the global coordinate system. Note that the sign convention is different from the sign convention used in the Joint Probes in Mechanical.

GetAcceleration()

Returns the joint acceleration measures on the joints that are constraint equations based. See the AccelerationFromVelocitiesDerivatives member to see when this function should be used.

Example:

J1 = CS_Joint.Find(_jid)
jointRotation = J1.GetRotation()
jointVelocity = J1.GetVelocity()
jointAcceleration = J1.GetAcceleration()
jointForce = J1.GetForce()

SetFrictionVariable(var)

Replaces the constant value already given to the friction coefficient with the expression given by var.

Example:

Joint = CS_Joint.Find(_jid)
Var = CS_Variable()
u0 = 0.1
u1 = 0.2
alpha = 0.5
Var.SetFunc('u0+u1exp(-alpha*time)',0)
Var.AddInputMeasure(Joint.GetVelocity())
Joint.SetFrictionVariable(Var)

The command has no effect if no value for the friction coefficient has been provided in the UI. For more information, see Joint Friction

SetFrictionTolerance(tol)

Sets the friction tolerance.

Example:

Joint = CS_Joint.Find(_jid)
Joint = Joint.SetFrictionTolerance(1e-4)

Derived Classes:

On SphericalJoint, SlotJoint, BushingJoint, FreeJoint, GeneralJoint.

Member Function
AddStop(angle_max, restitution_factor)

Adds a spherical stop to a joint that has three rotations. A spherical stop constrains the motion of the X and Y rotational degrees of freedom, to give to the joint the behavior of a loose revolute joint, with a rotational gap. This will allow easier handling of over-constrained systems and building higher fidelity models without having to use contact.

angle_max

The angle between the reference coordinate system Zr axis and the moving coordinate system Zm. Zr is the natural revolute axis.

restitution_factor

The restitution factor, similar to other joint stops.

On CylindricalJoint:
ReplaceByScrew(pitch)

Creates a relation between the translational and the rotational degrees of freedom of a cylindrical joint.


Note:
  • The pitch is in the current length unit. Any stop and/or lock defined on the original cylindrical joint is not transferred to the screw joint. Similarly, any constraint equation defined on the original cylindrical joint is not converted and so will prevent a proper solution.

  • The ReplaceByScrew command is deprecated. It is replaced by the Screw Joint provided in the Mechanical UI.


On Bushing Joint:
GetBushingAngles()

Returns the measure of the joint angles. This measure is used to compute the forces and torques developed in the joint. Note that this is only available for post-processing operations, as the measure does not exist before the solve has been performed.

Creating New Joints:

The following joint can be created by commands:

CS_GeneralJoint(from, to, FreeX, FreeY, FreeZ, FreeRX, FreeRY, FreeRZ)

Where from and to are of type CS_BodyCoordinateSystem and Free* are integers where 0 is no available motion and nonzero is available motion. Selecting two free rotations is not allowed.

JointDOFLoad

JointDOFLoads are loads applied on a given degree of freedom of a joint. The load is applied in the joint reference coordinate system.

JointDOFLoad derives from Load.

Constructor:
CS_JointDOFLoad(joint,dof)
joint

A joint object

dof

An integer that defines the joint degree of freedom to be included in the term. The ordering of the degrees of freedom sets the translation degrees of freedom first. The degrees of freedom numbering is zero based. For example, in a slot joint, the translational degree of freedom is 0, while the third rotational degree of freedom is 3.

Members:

None

Member functions:

None

Load

Loads derive from the Actuator class. They are derived from various types of loads, such as the CS_JointDOFLoad.

Corresponding ID table: CS_Actuator

Members:

None

Members Functions:

None

Measure:

Most useful measures are pre-existing in the Rigid Dynamics model, and can be accessed using other object "get" functions. Additional measures can be created before solving for use in custom post-processing or as input values for joint conditions. For example, measures can be created to express conditions. In this case, the measure must be added to the system to be computed at each time step (see component measure example below).

ID table: CS_Measure

Constants: For the measure type (E_MeasureType):

E_1DRotationJoint, E_3DRotationBody, E_3DRotationJoint, E_Acceleration, E_ActuatorStatus, E_ActuatorEnergy, E_AnsysJointForceAndTorque, E_AXPY, E_BodyAcceleration, E_BodyIntertialBCSQuaternion, E_BodyRotation, E_BodyTranslation, E_CenterOfGravity, E_Component, E_Constant, E_Contact, E_ContactForce, E_ContactVelocity, E_Counter, E_Displacement, E_Distance, E_DistanceDot, E_Divides, E_EigenValue, E_DOFSensitivity, E_Dot, E_ElasticEnergy, E_Energy, E_EulerAngles, E_ForceMagnitude, E_Forces, E_IntegratedOmega, E_JointAcceleration, E_JointDOFFrictionCone, E_JointDriverForce, E_JointForce, E_JointMBDVelocity, E_JointNormalForce, E_JointTranslation, E_JointRotation, E_JointVelocity, E_KineticEnergy, E_MassMomentsOfInertia, E_MeasureDotInDirectionOfLoad, E_Minus, E_Modulus, E_Multiplies, E_Norm, E_Omega, E_OmegaDot, E_OutputContactForce, E_Plus, E_PointOnCurveGeometryMeasure, E_PointOnCurveJointSigmaMeasure, E_PointToPointRotation, E_PointToPointRotationDot, E_Position, E_PotentialEnergy, E_RadialGap, E_ReferenceEnergy, E_RelativeAcceleration, E_RelativePosition, E_RelativeVelocity, E_RotationalRelativeDOF, E_RotationMatrix, E_SphericalStop, E_StopVelocity, E_StopStatus, E_Time, E_TimeStep, E_TranslationalJoint, E_UniversalAngles, E_UnknownType, E_User, E_Velocity, E_Violation, E_XYZAnsysRotationAngles, E_ZYXRotationAngles, E_AngularMomentum

Members:
Length:

Number of components of the measure

Example:

nbValues = Measure.Length

Type:

Measure type

Calculation Method:

A measure can use direct calculation or be time integrated. On a measure that uses direct calculation, it is possible to retrieve the measure value through time. On a measure that is time-integrated, both values and time derivatives can be retrieved.

Name:

Measure Name

Member Functions:
FillValuesThroughTime()

Returns a two dimensional array. This function is to be called after the solution has been performed. The first dimension of the returned array is the number of time values in the transient. The second dimension is the size of the measure plus one. The first column contains the time values, while the subsequent columns contain the corresponding measure values.

Example:

jointRotation = J1.GetRotation()
jointVelocity = J1.GetVelocity()
jointAcceleration = J1.GetAcceleration()
jointForce = J1.GetForce()

jointRotationValues =jointRotation.FillValuesThroughTime()
jointVelocityValues =jointVelocity.FillValuesThroughTime()
jointAccelerationValues =jointAcceleration.FillValuesThroughTime()
jointForceValues =jointForce.FillValuesThroughTime()

nbValues = jointRotationValues.GetLength(0)

print jointRotation.Id

print '  Time     Rotation Velocity Acceleration'
for i in range(0,nbValues):
    print jointRotationValues[i,0],jointRotationValues[i,1],jointVelocityValues[i,1],jointAccelerationValues[i,1]

fich.close()

FillDerivativesThroughTime()

Returns a two dimensional array. This function is to be called after the solution has been performed. The first dimension of the returned array is the number of time values in the transient. The second dimension is the size of the measure plus one: the first column contains the time values, while the subsequent columns contain the corresponding measure derivatives. These derivatives are available on measures that are time integrated. To know if a measure is time integrated, use the CalculationMethod member.

Derived Classes:
CS_JointVelocityMeasure

Both translational and rotational joint velocities are expressed in the joint reference coordinate system. The number of components is the number of translational degrees of freedom plus the number of rotational degrees of freedom. For example, the size of the joint velocity measure for a revolute joint is 1. It contains the relative joint rotation velocity along the z axis of the joint reference coordinate system. The size of the measure for a slot joint is 4: one component for the relative translational velocity, and the 3 components of the relative rotational velocity. The joint velocity measure can be obtained from the joint using the GetVelocity function. Rotational velocities are expressed in radians/second.

CS_JointAccelerationMeasure

Both translational and rotational joint accelerations are expressed in the joint reference coordinate system. The number of components is the number of translational degrees of freedom plus the number of rotational degrees of freedom. The joint acceleration measure can be obtained from the joint using the GetAcceleration function.

CS_JointRotationMeasure
  • For revolute joints, cylindrical joints, or single rotation general joints, this measure has only one component: the relative angle between the reference and the moving coordinate system of the joint. Rotations are expressed in radians.

  • For slots, spherical joints, bushing joints, and 3 rotation vectors, this measure contains values that are not directly usable.

  • For universal joints, this measure contains the two joint axis rotational velocities. (The first one along the X axis of the reference coordinate system and the second along the Z axis of the moving coordinate system.) These angles are expressed in radians.

CS_JointTranslationMeasure

This measure contains only the joint relative translations, expressed in the joint reference coordinate system. The joint translation measure can be obtained from the joint using the GetTranslationfunction.

CS_JointForceMeasure

This measure contains the total forces and moment that develop in the joint. This includes constraint forces, elastic forces, and external forces. The joint velocity measure can be obtained from the joint using the GetForcefunction.

CS_PositionMeasure

This measure allows for tracking of the position of a Body Coordinate System over time.

Example:

CoMBCS = OneBody.InertiaBodyCoordinateSystem
Pos = CS_PositionMeasure(CoMBCS)
Env=CS_Environment.FindFirstNonNull()
Sys = Env.System
Sys.AddMeasure(Pos)
CS_ComponentMeasure

This measure allows the extraction of one component of an existing measure. This component can be expressed in a non default coordinate system. A component of -2 will compute the norm 2 of the vector of values of the measure.

Example:

Planar = CS_Joint.Find(_jid)
Vel = Planar.GetVelocity()
Xglobaldirection = 0
VelX = CS_ComponentMeasure(Vel,Xglobaldirection)
Sys.AddMeasure(VelX)

CS_AXPYMeasure

This measure allows a linear transformation from another measure with a scaling factor and an offset. This can be useful to transform an internal rotation measure that is expressed in radians to a measure in degrees used as an input to a load calculation, for example.

Example:

Revolute = CS_Joint.Find(_jid)
Rot = Revolute.GetRotation()
RotInDegrees = CS_AXPYMeasure( Rot, 180.0/math.pi, 0. )
Sys.AddMeasure(RotInDegrees)

CS_ModulusMeasure

This measure allows you to compute the floating point remainder of value/modulus.

Example:

Revolute = CS_Joint.Find(_jid)
Rot = Revolute.GetRotation()
Rot02pi = CS_ModulusMeasure( Rot, 2.0*math.pi )
Sys.AddMeasure(Rot02pi)

CS_OutputContactForceMeasure

This measure contains four 3D vectors:

  • Values 0 to 2 are the total contact force components between the two bodies, including the normal and tangential contributions.

  • Values 3 to 5 are the coordinates of the point where the interaction between the two bodies is reduced to a force; in other words, the total torque is zero.

  • Values 6 to 8 are the frictional force between the two bodies.

  • Values 9 to 11 are frictional moment components at the reduction point.

CS_AngularMomentumMeasure

This measure computes the Angular Momentum of a list of bodies. Its value is a 3D vector.

Example:

FlyWheel= CS_Body.Find(_bid)
FlyWheelAngularMomentumMeasure = CS_AngularMomentumMeasure()
FlyWheelAngularMomentumMeasure.AddBody(FlyWheel)
Sys.AddMeasure(FlyWheelAngularMomentumMeasure)

MSolverDB

Solver database. The database is both the input and the results file to the solver. It can be used to solve outside the Mechanical session (for example, for co-simulation purposes) or to restart from a previous run.

Members:
SetFileName(FileName)

Set the database file name.

SetDirectoryName(DirectoryName)

Set the database directory.

ReadDatabase()

Read the content of the database.

WriteDatabase()

Write the current database to a file.

DeleteDatabase()

Delete the database.

CloseDatabase()

Close the database file.

OpenDatabase()

Open the database file and reads the database content table.

Dispose()

Clear the content of the database and free memory used by the database.

PointsTable

Corresponding ID table: CS_PointsTable

Members Functions:
CS_PointsTable( tab )

tab is a two dimensional array where the first column contains the input values and the second column contains the corresponding output values.

Example:

tab = System.Array.CreateInstance(float,6,2)
tab[0,0]=-100.
tab[1,0]=-8.
tab[2,0]=-7.9
tab[3,0]= 7.9
tab[4,0]= 8.
tab[5,0]= 100.

tab[0,1]=1.0
tab[1,1]=1.0
tab[2,1]=0.1
tab[3,1]=0.1
tab[4,1]=1.0
tab[5,1]=1.0
Table = CS_PointsTable(tab);

Here, the output (shown as Stiffness in the chart above) varies in a linear, piece-wise manner. For values of input less than -8.0 or greater than 8.0, the output is equal to 1.0. For values between -7.9 and +7.9, the output is 0.1. The transition is linear between -8.0 and -7.9, and as well between +7.9 and +8.0.

PolynomialTable

Corresponding ID: CS_PolynomialTable

Create a polynomial relation between sizeIn inputs and sizeOut outputs using the following function:

Where i denotes the index of input and goes from 1 to n (sizeIn), j denotes the index of output (from 1 to sizeOut).

Member Functions:
CS_PolynomialTable()

Creates an empty polynomial table.

Initialize(constant)

Specialized for 1x1 table. Initializes the table to be a 1 input, 1 output table, and sets the constant term (constant is a float value).

Initialize(sizeIn,sizeOut,constantValues)

(generic version) Initializes the table with sizeIn inputs and sizeOut outputs and sets the constant terms. sizeIn and sizeOut are two integer values, and constantValues is an array of sizeOut float values.

AddTerm(coefficient,order)

Specialized for 1x1 table. Adds one monomial term to the table. The coefficient is a float value and order is an integer value giving the power of the input.

AddTerm(coefficients,orders)

(generic version) Adds one monomial term to the table. The coefficients are given by a sizeOut float array and the power for each input by an array of sizeIn integers.

Relation

The relation object enables you to write constraint equations between degrees of freedom of the model. For example, two independent lines of shaft can be coupled using a relation between their rotational velocities.

If you have a gear coupling between two shafts where the second shaft rotates twice as fast as the first one, you can write the following equation:

2.0 X Ω1 + Ω2 = 0

where Ω1 and Ω2 are joint rotational velocities.

This relation contains two terms and a constant right hand side equal to zero.

The first term (2 X Ω1) can be described using the following information:

  • A joint selection

  • A joint degree of freedom selection

  • The nature of motion that is used in the equation (joint velocities, which is the most common case). For convenience, the nature of motion upon which the constraint equation is formulated is considered as being shared by all the terms in the relation.

This information defines Ω1

  • The factor 2.0 in the equation can be described by a constant variable, whose value is 2.0

    ID table: CS_Actuator

The coefficients of the relation can be constant or variable; however, the use of non-constant coefficients is limited to relations between velocities and relations between accelerations. If non-constant coefficients are used for relations between positions, the solution will not proceed.

Constants:

E_Acceleration, E_Position, E_Velocity

Members:

None

Member Functions:
SetRelationType(type)

Type of relation, with type selected in the previous enumeration.

AddTerm(joint, dof, variable)

Adds a term to the equation.

joint

A joint object

dof

An integer that defines the joint degree of freedom to be included in the term. The ordering of the degrees of freedom sets the translation degrees of freedom first, and that the degrees of freedom numbering is zero based. For example the translational degrees of freedom in a slot joint is 0, while the third rotational degree of freedom is 3.

variable

A variable object

SetVariable(variable)

Sets the right hand side of the relation. "variable" is a variable object.

SolverOptions

The SolverOptions object allows you to customize the behaviour of the RBD solver. The option uses a group of numerical values (real or integer) that can be get or set. When used as a switch, 0 means off and 1 is on.

Corresponding ID table: CS_SolverOptions

Constants:

None

Member Functions:
VelocityToleranceFactor

Multiplicative factor used to determine zero velocity tolerance (=100.0 by default);

ContactRadiusFactor

Contact radius factor used in contact failsafe mode (=2.0 by default);

MaximumNumberOfCorrectionAttempts

Number of external loops for geometric correction (=2 by default));

FrictionForShock

Enable friction for shock solve (=0, disabled by default);

MaximumNumberOfDiagnostics

Number of diagnostics messages given in Mechanical UI (=10 by default);

InactiveTouchingInDynamics

Prevent inactive contact pair from being violated (=1, enabled by default);

DisablePolygonEvent

Disable polygon event for contact (=0, active by default);

PrintDynamicSystem

Print the dynamics system (=0 by default);

PurgeGST

Purge GST file every n steps (=0, never by default);

PrintErrorEstimation

Force output of error estimation (=0, disabled by default);

ExportXLSFileForCMS

Export generalized coordinates for CMS bodies in a CSV file (=0, disabled by default)

HandlePOCTransitionsWithEnergyMinimization

When point on curve joints are used, different solutions (depending on the topology) may be found when crossing curve connections. Furthermore, these solutions do not guarantee the conservation of the kinetic energy at the transition. To remedy this issue, this option makes the transitions using a method that minimizes the kinetic energy in a way similar to the assembly process using the inertia matrix. This solution works well for explicit time integration schemes, but it is not guaranteed for implicit ones. (=0, disabled by default)

Example:
sOpts=CS_SolverOptions()
sOpts.ExportXLSFileForCMS=1
Spring

Corresponding ID table: CS_Actuator

Members:

None

Member Functions:
ToggleCompressionOnly()

Calling this function on a translational spring will make the spring develop elastic forces only if its length is less than the spring free length. The free length has to be defined in the regular spring properties.

ToggleTensionOnly()

Calling this function on a translational spring will make the spring develop elastic forces only if its length is greater than the free length of spring. The free length has to be defined in the regular spring properties.

SetLinearSpringProperties(system, stiffness, freeLength)

Enables you to overwrite the stiffness and free length of a translational spring. This can be useful to parameterize these properties. For example, system is the system object, stiffness and free length are the double precision values of stiffness and free length.

SetNonLinearSpringProperties(table_id)

Enables you to replace the constant stiffness of a spring with a table of ID table_id that gives the force as a function of the elongation of the spring. The table gives the relation between the force and the relative position of the two ends.

GetDamper()

The user interface has stiffness and damping properties of the spring. Internally, the Spring is made of two objects; a spring and a damper. This function enables you to access the internal damper using the Spring object in the GUI.

Derived Classes:

None

System

Corresponding ID table: CS_System

Members:
Bodies

Gets the list of bodies.

Joints

Gets the list of joints.

Member Functions:
AddBody(body)

Adds a body to the system.

AddJoint(joint)

Adds a joint to the system.

PrintTopology()

Prints the topology of the systems (parent/child relation).

AddMeasure(measure)

Adds a measure to the system, to be calculated during the simulation. This function must be called prior to solving so that the measure values through time can be retrieved.

(istat,found,measure)=FindOrCreateInternalMeasure( MeasureType)

Extracts an existing global measure on the system. Supported measure types are: E_Energy, E_PotentialEnergy, E_ElasticEnergy, E_KineticEnergy, and E_Time.

Derived Classes:

None

Table

A table is the base class for Points Tables, Polynomial Tables, User Tables, and GIL Tables.

ID table: CS_Table

Members:

None

Member Functions:
Evaluate(In, Out)

Allows evaluating a table in Python. In and Out are arrays of float, with sizes corresponding to the table input and output sizes. This function can be called from a user table for example.

Dispose()

Explicit destruction of the table. This explicit destructor should be used only when the table hasn’t been assigned to an actuator. When the table is assigned to an actuator, the actuator is calling this destructor. Omitting to call this destructor can cause the evaluation of the results to fail.

UserTable

A user table is a function with i input values and o output values, with an evaluator that is defined in IronPython, allowing complex variation, or even evaluation performed outside the solver.

Example:

LeftVarCoefX = CS_Variable();

# input 0,1,2 of the variable
LeftVarCoefX.AddInputMeasure( LeftRelTrans )

# input 3 to 8 of the variable
LeftVarCoefX.AddInputMeasure( LeftRelVelo )

class XForceTable(CS_UserTable):
    def __init__(self,sizeIn,sizeOut):
        CS_UserTable.__init__(self,sizeIn,sizeOut)

    def Evaluate(self,In,Out):
        TX = In[0]
        VX = In[3]

        Force = 1000.0*TX
        Out[0] = Force
        print 'ForceX = {0:e}'.format(Out[0])
        return 0

LeftForceTableX = XForceTable( 9, 1 )
LeftVarCoefX.SetTable( LeftForceTableX )
Variable

A variable is an n-dimensional vector quantity that varies over time. It is used to define the variation of a load or a joint condition, or to express the coefficients in a relation between degrees of freedom. For convenience, the solver allows the creation of constant variables, where only the value of the constant has to be provided. More complex variables can be built using a function variable. A function variable is a function of input, where input is given by a measure and function is described by a table. In some cases, you are able to replace the table or the measure of an internal variable as used in a joint condition.

ID table: CS_Variable

Members:

None

Member Functions:
SetConstantValues(value)

value is an array, whose size is equal to the size of the table. To create a constant scalar variable, the value can be defined as shown in the following example:

value = System.Array[float]([1.0])

System, Array, and float are part of the Python language. The result of this is an array of size one, containing the value 1.0.

AddInputMeasure(measure)

measure is a measure object. The same variable can have more than one measure. The input variable of the variable is formed by the values of the input measure in the order that they have been added to the list of input measures.

SetTable(table)

table is a CS_PointsTable.

SetFunc(string, is_degree)

string is similar to the expression used in the user interface to define a joint condition by a function. Note that the literal variable is always called "time", even if you are using another measure as input. "is_degree" is a boolean argument. If the expression uses a trigonometric function, it specifies that the input variable should be expressed in degrees.


Note:  Variables cannot be shared by different actuators.


Derived Classes:

ConstantVariable