-
Notifications
You must be signed in to change notification settings - Fork 285
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Add friction direction unit vector and frame parameters #1427
Changes from all commits
ed3a488
d1d8073
0195b7a
843b40b
ed85373
1962ef3
a932d87
5fe40b7
cddef7a
b3438cb
691fa12
d2b9e0d
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change | ||||||||||||||||||||||||||||||||||||||||||||||||||
---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|---|
|
@@ -57,7 +57,9 @@ DynamicsAspectProperties::DynamicsAspectProperties( | |||||||||||||||||||||||||||||||||||||||||||||||||||
const double frictionCoeff, const double restitutionCoeff) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
: mFrictionCoeff(frictionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mRestitutionCoeff(restitutionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mSecondaryFrictionCoeff(frictionCoeff) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mSecondaryFrictionCoeff(frictionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mFirstFrictionDirection(Eigen::Vector3d::Zero()), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Currently, the first friction direction will be set to z-direction in world coordinates (unless it's parallel to the contact normal). Maybe we want to set the default direction to non-zero direction (e.g., There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. my intent was that an unset vector with zero length would use the global friction direction, and that only friction directions that are explicitly set to have a nonzero length would use their custom direction and frame. See the following logic in ContactConstraint.cpp
does that make sense? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Yeah, I read the logic but was suggesting changing the default behavior to using local friction direction (by setting Downside of it is that it changes the default simulation behavior (from using global friction direction to local friction direction) though. I'm okay to leave as it is as long as the logic is documented. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. a tricky aspect of the friction directions is choosing which to use when custom directions are set for both bodies. I've added logic in this PR to choose the direction from the body with the smaller primary friction coefficient, since that would be the dominant parameter, which makes sense to me, but I haven't tested it, and I'd be wary of making a big behavior change like that without testing. Is the logic sufficiently documented? If not, I'll add the necessary documentation. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Agreed to not changing the default behavior. It's well documented in the implementation, but it'd be great if it's also documented in the header as well (maybe on the constructor?). There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. how does cddef7a look to you? There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Looks awesome! Thank you for adding it. |
||||||||||||||||||||||||||||||||||||||||||||||||||||
mFirstFrictionDirectionFrame(nullptr) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
// Do nothing | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
@@ -66,10 +68,14 @@ DynamicsAspectProperties::DynamicsAspectProperties( | |||||||||||||||||||||||||||||||||||||||||||||||||||
DynamicsAspectProperties::DynamicsAspectProperties( | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const double primaryFrictionCoeff, | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const double secondaryFrictionCoeff, | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const double restitutionCoeff) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const double restitutionCoeff, | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const Eigen::Vector3d& firstFrictionDirection, | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const Frame* firstFrictionDirectionFrame) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
: mFrictionCoeff(primaryFrictionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mRestitutionCoeff(restitutionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mSecondaryFrictionCoeff(secondaryFrictionCoeff) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mSecondaryFrictionCoeff(secondaryFrictionCoeff), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mFirstFrictionDirection(firstFrictionDirection), | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mFirstFrictionDirectionFrame(firstFrictionDirectionFrame) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
// Do nothing | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
@@ -195,9 +201,8 @@ void DynamicsAspect::setFrictionCoeff(const double& value) | |||||||||||||||||||||||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||||||||||||||||||||||||
double DynamicsAspect::getFrictionCoeff() const | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
return 0.5 * ( | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mProperties.mFrictionCoeff + | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mProperties.mSecondaryFrictionCoeff); | ||||||||||||||||||||||||||||||||||||||||||||||||||||
return 0.5 | ||||||||||||||||||||||||||||||||||||||||||||||||||||
* (mProperties.mFrictionCoeff + mProperties.mSecondaryFrictionCoeff); | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||||||||||||||||||||||||
void DynamicsAspect::setPrimaryFrictionCoeff(const double& value) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
@@ -210,6 +215,18 @@ const double& DynamicsAspect::getPrimaryFrictionCoeff() const | |||||||||||||||||||||||||||||||||||||||||||||||||||
return mProperties.mFrictionCoeff; | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||||||||||||||||||||||||
//============================================================================== | ||||||||||||||||||||||||||||||||||||||||||||||||||||
void DynamicsAspect::setFirstFrictionDirectionFrame(const Frame* value) | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
mProperties.mFirstFrictionDirectionFrame = value; | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||||||||||||||||||||||||
//============================================================================== | ||||||||||||||||||||||||||||||||||||||||||||||||||||
const Frame* DynamicsAspect::getFirstFrictionDirectionFrame() const | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
return mProperties.mFirstFrictionDirectionFrame; | ||||||||||||||||||||||||||||||||||||||||||||||||||||
} | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
||||||||||||||||||||||||||||||||||||||||||||||||||||
//============================================================================== | ||||||||||||||||||||||||||||||||||||||||||||||||||||
ShapeFrame::~ShapeFrame() | ||||||||||||||||||||||||||||||||||||||||||||||||||||
{ | ||||||||||||||||||||||||||||||||||||||||||||||||||||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
It's not the part of this change, but I would like to negate the direction of
tangent
so thatT.col(0).cross(T.col(1)) == n
(currently, it'sT.col(1).cross(T.col(0)) == n
) because I believe it'd be more intuitive. This change wouldn't affect the behavior (but just flipping the sign of impulse for the second tangential friction).It can be done by changing the order of all the cross products in this function. For example, line 813 should be changed to:
Eigen::Vector3d tangent = n.cross(mFirstFrictionalDirection);
or simply negating the final
tangent
. I'd prefer changing the order of the cross products though.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I'm not opposed to that, but I'll bring @azeey into the conversation since he made this specific change
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
Negating the direction of
tangent
sounds fine to me if it doesn't affect the behavior. I think the main change here is thatT.col(0)
has to be parallel to the first frictional direction.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
reversed in 5fe40b7