Bullet Collision Detection & Physics Library
Public Member Functions | Public Attributes | Protected Member Functions | List of all members
btGeneric6DofConstraint Class Reference

btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis location in local space More...

#include <btGeneric6DofConstraint.h>

Inheritance diagram for btGeneric6DofConstraint:
Inheritance graph
[legend]
Collaboration diagram for btGeneric6DofConstraint:
Collaboration graph
[legend]

Public Member Functions

 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
 btGeneric6DofConstraint (btRigidBody &rbA, btRigidBody &rbB, const btTransform &frameInA, const btTransform &frameInB, bool useLinearReferenceFrameA)
 
 btGeneric6DofConstraint (btRigidBody &rbB, const btTransform &frameInB, bool useLinearReferenceFrameB)
 
void calculateTransforms (const btTransform &transA, const btTransform &transB)
 Calcs global transform of the offsets. More...
 
void calculateTransforms ()
 
const btTransformgetCalculatedTransformA () const
 Gets the global transform of the offset for body A. More...
 
const btTransformgetCalculatedTransformB () const
 Gets the global transform of the offset for body B. More...
 
const btTransformgetFrameOffsetA () const
 
const btTransformgetFrameOffsetB () const
 
btTransformgetFrameOffsetA ()
 
btTransformgetFrameOffsetB ()
 
virtual void buildJacobian ()
 performs Jacobian calculation, and also calculates angle differences and axis More...
 
virtual void getInfo1 (btConstraintInfo1 *info)
 internal method used by the constraint solver, don't use them directly More...
 
void getInfo1NonVirtual (btConstraintInfo1 *info)
 
virtual void getInfo2 (btConstraintInfo2 *info)
 internal method used by the constraint solver, don't use them directly More...
 
void getInfo2NonVirtual (btConstraintInfo2 *info, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB)
 
void updateRHS (btScalar timeStep)
 
btVector3 getAxis (int axis_index) const
 Get the rotation axis in global coordinates. More...
 
btScalar getAngle (int axis_index) const
 Get the relative Euler angle. More...
 
btScalar getRelativePivotPosition (int axis_index) const
 Get the relative position of the constraint pivot. More...
 
void setFrames (const btTransform &frameA, const btTransform &frameB)
 
bool testAngularLimitMotor (int axis_index)
 Test angular limit. More...
 
void setLinearLowerLimit (const btVector3 &linearLower)
 
void getLinearLowerLimit (btVector3 &linearLower) const
 
void setLinearUpperLimit (const btVector3 &linearUpper)
 
void getLinearUpperLimit (btVector3 &linearUpper) const
 
void setAngularLowerLimit (const btVector3 &angularLower)
 
void getAngularLowerLimit (btVector3 &angularLower) const
 
void setAngularUpperLimit (const btVector3 &angularUpper)
 
void getAngularUpperLimit (btVector3 &angularUpper) const
 
btRotationalLimitMotorgetRotationalLimitMotor (int index)
 Retrieves the angular limit informacion. More...
 
btTranslationalLimitMotorgetTranslationalLimitMotor ()
 Retrieves the limit informacion. More...
 
void setLimit (int axis, btScalar lo, btScalar hi)
 
bool isLimited (int limitIndex) const
 Test limit. More...
 
virtual void calcAnchorPos (void)
 
int get_limit_motor_info2 (btRotationalLimitMotor *limot, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB, btConstraintInfo2 *info, int row, btVector3 &ax1, int rotational, int rotAllowed=false)
 
bool getUseFrameOffset () const
 
void setUseFrameOffset (bool frameOffsetOnOff)
 
bool getUseLinearReferenceFrameA () const
 
void setUseLinearReferenceFrameA (bool linearReferenceFrameA)
 
virtual void setParam (int num, btScalar value, int axis=-1)
 override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5). More...
 
virtual btScalar getParam (int num, int axis=-1) const
 return the local value of parameter More...
 
void setAxis (const btVector3 &axis1, const btVector3 &axis2)
 
virtual int getFlags () const
 
virtual int calculateSerializeBufferSize () const
 
virtual const char * serialize (void *dataBuffer, btSerializer *serializer) const
 fills the dataBuffer and returns the struct name (and 0 on failure) More...
 
- Public Member Functions inherited from btTypedConstraint
 BT_DECLARE_ALIGNED_ALLOCATOR ()
 
virtual ~btTypedConstraint ()
 
 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA)
 
 btTypedConstraint (btTypedConstraintType type, btRigidBody &rbA, btRigidBody &rbB)
 
int getOverrideNumSolverIterations () const
 
void setOverrideNumSolverIterations (int overideNumIterations)
 override the number of constraint solver iterations used to solve this constraint -1 will use the default number of iterations, as specified in SolverInfo.m_numIterations More...
 
virtual void setupSolverConstraint (btConstraintArray &ca, int solverBodyA, int solverBodyB, btScalar timeStep)
 internal method used by the constraint solver, don't use them directly More...
 
void internalSetAppliedImpulse (btScalar appliedImpulse)
 internal method used by the constraint solver, don't use them directly More...
 
btScalar internalGetAppliedImpulse ()
 internal method used by the constraint solver, don't use them directly More...
 
btScalar getBreakingImpulseThreshold () const
 
void setBreakingImpulseThreshold (btScalar threshold)
 
bool isEnabled () const
 
void setEnabled (bool enabled)
 
virtual void solveConstraintObsolete (btSolverBody &, btSolverBody &, btScalar)
 internal method used by the constraint solver, don't use them directly More...
 
const btRigidBodygetRigidBodyA () const
 
const btRigidBodygetRigidBodyB () const
 
btRigidBodygetRigidBodyA ()
 
btRigidBodygetRigidBodyB ()
 
int getUserConstraintType () const
 
void setUserConstraintType (int userConstraintType)
 
void setUserConstraintId (int uid)
 
int getUserConstraintId () const
 
void setUserConstraintPtr (void *ptr)
 
void * getUserConstraintPtr ()
 
void setJointFeedback (btJointFeedback *jointFeedback)
 
const btJointFeedbackgetJointFeedback () const
 
btJointFeedbackgetJointFeedback ()
 
int getUid () const
 
bool needsFeedback () const
 
void enableFeedback (bool needsFeedback)
 enableFeedback will allow to read the applied linear and angular impulse use getAppliedImpulse, getAppliedLinearImpulse and getAppliedAngularImpulse to read feedback information More...
 
btScalar getAppliedImpulse () const
 getAppliedImpulse is an estimated total applied impulse. More...
 
btTypedConstraintType getConstraintType () const
 
void setDbgDrawSize (btScalar dbgDrawSize)
 
btScalar getDbgDrawSize ()
 
- Public Member Functions inherited from btTypedObject
 btTypedObject (int objectType)
 
int getObjectType () const
 

Public Attributes

bool m_useSolveConstraintObsolete
 for backwards compatibility during the transition to 'getInfo/getInfo2' More...
 
- Public Attributes inherited from btTypedObject
int m_objectType
 

Protected Member Functions

btGeneric6DofConstraintoperator= (btGeneric6DofConstraint &other)
 
int setAngularLimits (btConstraintInfo2 *info, int row_offset, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB)
 
int setLinearLimits (btConstraintInfo2 *info, int row, const btTransform &transA, const btTransform &transB, const btVector3 &linVelA, const btVector3 &linVelB, const btVector3 &angVelA, const btVector3 &angVelB)
 
void buildLinearJacobian (btJacobianEntry &jacLinear, const btVector3 &normalWorld, const btVector3 &pivotAInW, const btVector3 &pivotBInW)
 
void buildAngularJacobian (btJacobianEntry &jacAngular, const btVector3 &jointAxisW)
 
void calculateLinearInfo ()
 
void calculateAngleInfo ()
 calcs the euler angles between the two bodies. More...
 
- Protected Member Functions inherited from btTypedConstraint
btScalar getMotorFactor (btScalar pos, btScalar lowLim, btScalar uppLim, btScalar vel, btScalar timeFact)
 internal method used by the constraint solver, don't use them directly More...
 

Protected Attributes

btTransform m_frameInA
 relative_frames More...
 
btTransform m_frameInB
 the constraint space w.r.t body B More...
 
btJacobianEntry m_jacLinear [3]
 Jacobians. More...
 
btJacobianEntry m_jacAng [3]
 3 orthogonal angular constraints More...
 
btTranslationalLimitMotor m_linearLimits
 Linear_Limit_parameters. More...
 
btRotationalLimitMotor m_angularLimits [3]
 hinge_parameters More...
 
btScalar m_timeStep
 temporal variables More...
 
btTransform m_calculatedTransformA
 
btTransform m_calculatedTransformB
 
btVector3 m_calculatedAxisAngleDiff
 
btVector3 m_calculatedAxis [3]
 
btVector3 m_calculatedLinearDiff
 
btScalar m_factA
 
btScalar m_factB
 
bool m_hasStaticBody
 
btVector3 m_AnchorPos
 
bool m_useLinearReferenceFrameA
 
bool m_useOffsetForConstraintFrame
 
int m_flags
 
- Protected Attributes inherited from btTypedConstraint
btRigidBodym_rbA
 
btRigidBodym_rbB
 
btScalar m_appliedImpulse
 
btScalar m_dbgDrawSize
 
btJointFeedbackm_jointFeedback
 

Additional Inherited Members

- Static Public Member Functions inherited from btTypedConstraint
static btRigidBodygetFixedBody ()
 

Detailed Description

btGeneric6DofConstraint between two rigidbodies each with a pivotpoint that descibes the axis location in local space

btGeneric6DofConstraint can leave any of the 6 degree of freedom 'free' or 'locked'. currently this limit supports rotational motors

Definition at line 279 of file btGeneric6DofConstraint.h.

Constructor & Destructor Documentation

btGeneric6DofConstraint::btGeneric6DofConstraint ( btRigidBody rbA,
btRigidBody rbB,
const btTransform frameInA,
const btTransform frameInB,
bool  useLinearReferenceFrameA 
)

Definition at line 38 of file btGeneric6DofConstraint.cpp.

btGeneric6DofConstraint::btGeneric6DofConstraint ( btRigidBody rbB,
const btTransform frameInB,
bool  useLinearReferenceFrameB 
)

not providing rigidbody A means implicitly using worldspace for body A

Definition at line 52 of file btGeneric6DofConstraint.cpp.

Member Function Documentation

btGeneric6DofConstraint::BT_DECLARE_ALIGNED_ALLOCATOR ( )
void btGeneric6DofConstraint::buildAngularJacobian ( btJacobianEntry jacAngular,
const btVector3 jointAxisW 
)
protected

Definition at line 433 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::buildJacobian ( )
virtual

performs Jacobian calculation, and also calculates angle differences and axis

Reimplemented from btTypedConstraint.

Definition at line 458 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::buildLinearJacobian ( btJacobianEntry jacLinear,
const btVector3 normalWorld,
const btVector3 pivotAInW,
const btVector3 pivotBInW 
)
protected

Definition at line 415 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::calcAnchorPos ( void  )
virtual

Definition at line 739 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::calculateAngleInfo ( )
protected

calcs the euler angles between the two bodies.

Definition at line 353 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::calculateLinearInfo ( )
protected

Definition at line 760 of file btGeneric6DofConstraint.cpp.

int btGeneric6DofConstraint::calculateSerializeBufferSize ( ) const
inlinevirtual

Reimplemented from btTypedConstraint.

Reimplemented in btGeneric6DofSpringConstraint.

Definition at line 612 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::calculateTransforms ( const btTransform transA,
const btTransform transB 
)

Calcs global transform of the offsets.

Calcs the global transform for the joint offset for body A an B, and also calcs the agle differences between the bodies.

See also
btGeneric6DofConstraint.getCalculatedTransformA , btGeneric6DofConstraint.getCalculatedTransformB, btGeneric6DofConstraint.calculateAngleInfo

Definition at line 389 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::calculateTransforms ( )

Definition at line 384 of file btGeneric6DofConstraint.cpp.

int btGeneric6DofConstraint::get_limit_motor_info2 ( btRotationalLimitMotor limot,
const btTransform transA,
const btTransform transB,
const btVector3 linVelA,
const btVector3 linVelB,
const btVector3 angVelA,
const btVector3 angVelB,
btConstraintInfo2 info,
int  row,
btVector3 ax1,
int  rotational,
int  rotAllowed = false 
)

Definition at line 773 of file btGeneric6DofConstraint.cpp.

btScalar btGeneric6DofConstraint::getAngle ( int  axis_index) const

Get the relative Euler angle.

Precondition
btGeneric6DofConstraint::calculateTransforms() must be called previously.

Definition at line 732 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::getAngularLowerLimit ( btVector3 angularLower) const
inline

Definition at line 481 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::getAngularUpperLimit ( btVector3 angularUpper) const
inline

Definition at line 493 of file btGeneric6DofConstraint.h.

btVector3 btGeneric6DofConstraint::getAxis ( int  axis_index) const

Get the rotation axis in global coordinates.

Precondition
btGeneric6DofConstraint.buildJacobian must be called previously.

Definition at line 720 of file btGeneric6DofConstraint.cpp.

const btTransform& btGeneric6DofConstraint::getCalculatedTransformA ( ) const
inline
const btTransform& btGeneric6DofConstraint::getCalculatedTransformB ( ) const
inline
virtual int btGeneric6DofConstraint::getFlags ( ) const
inlinevirtual

Definition at line 566 of file btGeneric6DofConstraint.h.

const btTransform& btGeneric6DofConstraint::getFrameOffsetA ( ) const
inline

Definition at line 392 of file btGeneric6DofConstraint.h.

btTransform& btGeneric6DofConstraint::getFrameOffsetA ( )
inline

Definition at line 403 of file btGeneric6DofConstraint.h.

const btTransform& btGeneric6DofConstraint::getFrameOffsetB ( ) const
inline

Definition at line 397 of file btGeneric6DofConstraint.h.

btTransform& btGeneric6DofConstraint::getFrameOffsetB ( )
inline

Definition at line 408 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::getInfo1 ( btConstraintInfo1 info)
virtual

internal method used by the constraint solver, don't use them directly

Implements btTypedConstraint.

Definition at line 520 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::getInfo1NonVirtual ( btConstraintInfo1 info)

Definition at line 554 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::getInfo2 ( btConstraintInfo2 info)
virtual

internal method used by the constraint solver, don't use them directly

Implements btTypedConstraint.

Reimplemented in btGeneric6DofSpringConstraint.

Definition at line 569 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::getInfo2NonVirtual ( btConstraintInfo2 info,
const btTransform transA,
const btTransform transB,
const btVector3 linVelA,
const btVector3 linVelB,
const btVector3 angVelA,
const btVector3 angVelB 
)

Definition at line 594 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::getLinearLowerLimit ( btVector3 linearLower) const
inline

Definition at line 460 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::getLinearUpperLimit ( btVector3 linearUpper) const
inline

Definition at line 470 of file btGeneric6DofConstraint.h.

btScalar btGeneric6DofConstraint::getParam ( int  num,
int  axis = -1 
) const
virtual

return the local value of parameter

Implements btTypedConstraint.

Definition at line 994 of file btGeneric6DofConstraint.cpp.

btScalar btGeneric6DofConstraint::getRelativePivotPosition ( int  axis_index) const

Get the relative position of the constraint pivot.

Precondition
btGeneric6DofConstraint::calculateTransforms() must be called previously.

Definition at line 726 of file btGeneric6DofConstraint.cpp.

btRotationalLimitMotor* btGeneric6DofConstraint::getRotationalLimitMotor ( int  index)
inline

Retrieves the angular limit informacion.

Definition at line 500 of file btGeneric6DofConstraint.h.

btTranslationalLimitMotor* btGeneric6DofConstraint::getTranslationalLimitMotor ( )
inline

Retrieves the limit informacion.

Definition at line 506 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::getUseFrameOffset ( ) const
inline

Definition at line 552 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::getUseLinearReferenceFrameA ( ) const
inline

Definition at line 555 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::isLimited ( int  limitIndex) const
inline

Test limit.

  • free means upper < lower,
  • locked means upper == lower
  • limited means upper > lower
  • limitIndex: first 3 are linear, next 3 are angular

Definition at line 535 of file btGeneric6DofConstraint.h.

btGeneric6DofConstraint& btGeneric6DofConstraint::operator= ( btGeneric6DofConstraint other)
inlineprotected

Definition at line 329 of file btGeneric6DofConstraint.h.

const char * btGeneric6DofConstraint::serialize ( void *  dataBuffer,
btSerializer serializer 
) const
inlinevirtual

fills the dataBuffer and returns the struct name (and 0 on failure)

Reimplemented from btTypedConstraint.

Reimplemented in btGeneric6DofSpringConstraint.

Definition at line 618 of file btGeneric6DofConstraint.h.

int btGeneric6DofConstraint::setAngularLimits ( btConstraintInfo2 info,
int  row_offset,
const btTransform transA,
const btTransform transB,
const btVector3 linVelA,
const btVector3 linVelB,
const btVector3 angVelA,
const btVector3 angVelB 
)
protected

Definition at line 669 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::setAngularLowerLimit ( const btVector3 angularLower)
inline

Definition at line 475 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::setAngularUpperLimit ( const btVector3 angularUpper)
inline

Definition at line 487 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::setAxis ( const btVector3 axis1,
const btVector3 axis2 
)

Definition at line 1046 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::setFrames ( const btTransform frameA,
const btTransform frameB 
)

Definition at line 710 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::setLimit ( int  axis,
btScalar  lo,
btScalar  hi 
)
inline

Definition at line 512 of file btGeneric6DofConstraint.h.

int btGeneric6DofConstraint::setLinearLimits ( btConstraintInfo2 info,
int  row,
const btTransform transA,
const btTransform transB,
const btVector3 linVelA,
const btVector3 linVelB,
const btVector3 angVelA,
const btVector3 angVelB 
)
protected

Definition at line 621 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::setLinearLowerLimit ( const btVector3 linearLower)
inline

Definition at line 455 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::setLinearUpperLimit ( const btVector3 linearUpper)
inline

Definition at line 465 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::setParam ( int  num,
btScalar  value,
int  axis = -1 
)
virtual

override the default global value of a parameter (such as ERP or CFM), optionally provide the axis (0..5).

If no axis is provided, it uses the default axis for this constraint.

Implements btTypedConstraint.

Definition at line 945 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::setUseFrameOffset ( bool  frameOffsetOnOff)
inline

Definition at line 553 of file btGeneric6DofConstraint.h.

void btGeneric6DofConstraint::setUseLinearReferenceFrameA ( bool  linearReferenceFrameA)
inline

Definition at line 556 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::testAngularLimitMotor ( int  axis_index)

Test angular limit.

Calculates angular correction and returns true if limit needs to be corrected.

Precondition
btGeneric6DofConstraint::calculateTransforms() must be called previously.

Definition at line 446 of file btGeneric6DofConstraint.cpp.

void btGeneric6DofConstraint::updateRHS ( btScalar  timeStep)

Definition at line 703 of file btGeneric6DofConstraint.cpp.

Member Data Documentation

btVector3 btGeneric6DofConstraint::m_AnchorPos
protected

Definition at line 320 of file btGeneric6DofConstraint.h.

btRotationalLimitMotor btGeneric6DofConstraint::m_angularLimits[3]
protected

hinge_parameters

Definition at line 303 of file btGeneric6DofConstraint.h.

btVector3 btGeneric6DofConstraint::m_calculatedAxis[3]
protected

Definition at line 314 of file btGeneric6DofConstraint.h.

btVector3 btGeneric6DofConstraint::m_calculatedAxisAngleDiff
protected

Definition at line 313 of file btGeneric6DofConstraint.h.

btVector3 btGeneric6DofConstraint::m_calculatedLinearDiff
protected

Definition at line 315 of file btGeneric6DofConstraint.h.

btTransform btGeneric6DofConstraint::m_calculatedTransformA
protected

Definition at line 311 of file btGeneric6DofConstraint.h.

btTransform btGeneric6DofConstraint::m_calculatedTransformB
protected

Definition at line 312 of file btGeneric6DofConstraint.h.

btScalar btGeneric6DofConstraint::m_factA
protected

Definition at line 316 of file btGeneric6DofConstraint.h.

btScalar btGeneric6DofConstraint::m_factB
protected

Definition at line 317 of file btGeneric6DofConstraint.h.

int btGeneric6DofConstraint::m_flags
protected

Definition at line 325 of file btGeneric6DofConstraint.h.

btTransform btGeneric6DofConstraint::m_frameInA
protected

relative_frames

the constraint space w.r.t body A

Definition at line 285 of file btGeneric6DofConstraint.h.

btTransform btGeneric6DofConstraint::m_frameInB
protected

the constraint space w.r.t body B

Definition at line 286 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::m_hasStaticBody
protected

Definition at line 318 of file btGeneric6DofConstraint.h.

btJacobianEntry btGeneric6DofConstraint::m_jacAng[3]
protected

3 orthogonal angular constraints

Definition at line 292 of file btGeneric6DofConstraint.h.

btJacobianEntry btGeneric6DofConstraint::m_jacLinear[3]
protected

Jacobians.

3 orthogonal linear constraints

Definition at line 291 of file btGeneric6DofConstraint.h.

btTranslationalLimitMotor btGeneric6DofConstraint::m_linearLimits
protected

Linear_Limit_parameters.

Definition at line 297 of file btGeneric6DofConstraint.h.

btScalar btGeneric6DofConstraint::m_timeStep
protected

temporal variables

Definition at line 310 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::m_useLinearReferenceFrameA
protected

Definition at line 322 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::m_useOffsetForConstraintFrame
protected

Definition at line 323 of file btGeneric6DofConstraint.h.

bool btGeneric6DofConstraint::m_useSolveConstraintObsolete

for backwards compatibility during the transition to 'getInfo/getInfo2'

Definition at line 360 of file btGeneric6DofConstraint.h.


The documentation for this class was generated from the following files: