#include <ShapeFrameAspect.hpp>
|
| DynamicsAspectProperties (const double frictionCoeff=1.0, const double restitutionCoeff=0.0) |
| Constructors The frictionCoeff argument will be used for both primary and secondary friction. More...
|
|
| DynamicsAspectProperties (const double primaryFrictionCoeff, const double secondaryFrictionCoeff, const double restitutionCoeff, const double primarySlipCompliance=-1.0, const double secondarySlipCompliance=-1.0, const Eigen::Vector3d &firstFrictionDirection=Eigen::Vector3d::Zero(), const Frame *firstFrictionDirectionFrame=nullptr) |
| Set primary and secondary friction and restitution coefficients. More...
|
|
virtual | ~DynamicsAspectProperties ()=default |
| Destructor. More...
|
|
◆ DynamicsAspectProperties() [1/2]
dart::dynamics::detail::DynamicsAspectProperties::DynamicsAspectProperties |
( |
const double |
frictionCoeff = 1.0 , |
|
|
const double |
restitutionCoeff = 0.0 |
|
) |
| |
Constructors The frictionCoeff argument will be used for both primary and secondary friction.
◆ DynamicsAspectProperties() [2/2]
dart::dynamics::detail::DynamicsAspectProperties::DynamicsAspectProperties |
( |
const double |
primaryFrictionCoeff, |
|
|
const double |
secondaryFrictionCoeff, |
|
|
const double |
restitutionCoeff, |
|
|
const double |
primarySlipCompliance = -1.0 , |
|
|
const double |
secondarySlipCompliance = -1.0 , |
|
|
const Eigen::Vector3d & |
firstFrictionDirection = Eigen::Vector3d::Zero() , |
|
|
const Frame * |
firstFrictionDirectionFrame = nullptr |
|
) |
| |
Set primary and secondary friction and restitution coefficients.
The first friction direction vector and frame may optionally be set. The vector defaults to a zero-vector, which will cause it to be ignored and the global friction directions used instead. If the vector is set to a non-zero vector, the first friction direction for this shape is computed from this vector expressed in the frame given by the Frame pointer. THe Frame pointer defaults to nullptr, which is interpreted as the body-fixed frame of this Shape. Note that if two objects with custom friction directions come into contact, only one of the directions can be chosen. One approach is to use the first friction direction for the ShapeNode with the smaller primary friction coefficient, since that has the dominant effect. See the ContactConstraint implementation for further details.
◆ ~DynamicsAspectProperties()
virtual dart::dynamics::detail::DynamicsAspectProperties::~DynamicsAspectProperties |
( |
| ) |
|
|
virtualdefault |
◆ mFirstFrictionDirection
Eigen::Vector3d dart::dynamics::detail::DynamicsAspectProperties::mFirstFrictionDirection |
First friction direction unit vector.
◆ mFirstFrictionDirectionFrame
const Frame* dart::dynamics::detail::DynamicsAspectProperties::mFirstFrictionDirectionFrame |
First friction direction frame The first friction direction unit vector is expressed in this frame.
◆ mFrictionCoeff
double dart::dynamics::detail::DynamicsAspectProperties::mFrictionCoeff |
Primary coefficient of friction.
◆ mPrimarySlipCompliance
double dart::dynamics::detail::DynamicsAspectProperties::mPrimarySlipCompliance |
Primary slip compliance coefficient.
◆ mRestitutionCoeff
double dart::dynamics::detail::DynamicsAspectProperties::mRestitutionCoeff |
Coefficient of restitution.
◆ mSecondaryFrictionCoeff
double dart::dynamics::detail::DynamicsAspectProperties::mSecondaryFrictionCoeff |
Secondary coefficient of friction.
◆ mSecondarySlipCompliance
double dart::dynamics::detail::DynamicsAspectProperties::mSecondarySlipCompliance |
Secondary slip compliance coefficient.