Skip to content
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

Merged
merged 12 commits into from
Dec 7, 2019

Conversation

scpeters
Copy link
Collaborator

@scpeters scpeters commented Nov 26, 2019

Currently the ContactConstraint uses a friction pyramid with 2 directions. In #1424, we added an additional parameter to allow the friction coefficient to be specified separately in each direction. This pull request allows the friction direction to be specified with a unit vector FirstFrictionDirection and pointer to a frame FirstFrictionDirectionFrame in which the unit vector is expressed. If FirstFrictionDirection is a vector of zeros (which is its default value), it is ignored and the default friction directions are used. If the frame pointer is nullptr (which is its default value), the body-fixed frame of that ShapeNode is used.

I've added two bodies to test_Friction with friction direction set using the default body-fixed frame and also using the world frame. In these tests, the friction is set to zero along one direction, and the lateral gravity component pushes along a diagonal.


Before creating a pull request

  • Document new methods and classes
  • Format new code files using clang-format

Before merging a pull request

  • Set version target by selecting a milestone on the right side
  • Summarize this change in CHANGELOG.md
  • Add unit test(s) for this change

@scpeters
Copy link
Collaborator Author

cc @azeey

@codecov
Copy link

codecov bot commented Nov 26, 2019

Codecov Report

Merging #1427 into master will increase coverage by <.01%.
The diff coverage is 78%.

@@            Coverage Diff             @@
##           master    #1427      +/-   ##
==========================================
+ Coverage   57.99%   57.99%   +<.01%     
==========================================
  Files         412      412              
  Lines       29832    29861      +29     
==========================================
+ Hits        17302    17319      +17     
- Misses      12530    12542      +12
Impacted Files Coverage Δ
dart/constraint/ContactConstraint.hpp 100% <ø> (ø) ⬆️
dart/dynamics/detail/ShapeFrameAspect.hpp 88.88% <ø> (ø) ⬆️
dart/dynamics/ShapeFrame.hpp 83.33% <100%> (+1.51%) ⬆️
dart/constraint/ContactConstraint.cpp 68.89% <75.6%> (-0.43%) ⬇️
dart/dynamics/ShapeFrame.cpp 72.22% <87.5%> (+1.06%) ⬆️
dart/dynamics/Skeleton.cpp 66.16% <0%> (-0.17%) ⬇️

@scpeters
Copy link
Collaborator Author

scpeters commented Dec 2, 2019

@mxgrey and @jslee02 we are getting close to a release of ignition citadel, and we'd really like to get these changes from our fork into dartsim

there is another pull request scheduled to come after this too that adds slip parameters

any time you could spend on a review would be greatly appreciated

Copy link
Member

@jslee02 jslee02 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Thank you for this set of changes and sorry for taking so long to review this PR. Overall, it looks good to me. I left several comments.

dart/constraint/ContactConstraint.cpp Outdated Show resolved Hide resolved
dart/constraint/ContactConstraint.cpp Outdated Show resolved Hide resolved
Comment on lines +913 to +916
// The first column is the same as mFirstFrictionalDirection unless
// mFirstFrictionalDirection is parallel to the normal
T.col(0) = Eigen::Quaterniond(Eigen::AngleAxisd(0.5_pi, n)) * tangent;
T.col(1) = tangent;
Copy link
Member

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 that T.col(0).cross(T.col(1)) == n (currently, it's T.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.

Copy link
Collaborator Author

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

Copy link
Contributor

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 that T.col(0) has to be parallel to the first frictional direction.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

reversed in 5fe40b7

@@ -57,7 +57,9 @@ DynamicsAspectProperties::DynamicsAspectProperties(
const double frictionCoeff, const double restitutionCoeff)
: mFrictionCoeff(frictionCoeff),
mRestitutionCoeff(restitutionCoeff),
mSecondaryFrictionCoeff(frictionCoeff)
mSecondaryFrictionCoeff(frictionCoeff),
mFirstFrictionDirection(Eigen::Vector3d::Zero()),
Copy link
Member

@jslee02 jslee02 Dec 2, 2019

Choose a reason for hiding this comment

The 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., Eigen::Vector3d::UnitZ()) so that the default behavior is more consistent in terms of the friction direction?

Copy link
Collaborator Author

Choose a reason for hiding this comment

The 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

  • // only consider custom friction direction if one has nonzero length
    if (nonzeroDirA || nonzeroDirB)
    {
    // if A and B are both set, choose one with smaller friction coefficient
    // since it's friction properties will dominate
    if (nonzeroDirA && nonzeroDirB)
    {
    if (primaryFrictionCoeffA <= primaryFrictionCoeffB)
    {
    mFirstFrictionalDirection = frictionDirA.normalized();
    }
    else
    {
    mFirstFrictionalDirection = frictionDirB.normalized();
    }
    }
    else if (nonzeroDirA)
    {
    mFirstFrictionalDirection = frictionDirA.normalized();
    }
    else
    {
    mFirstFrictionalDirection = frictionDirB.normalized();
    }
    }

does that make sense?

Copy link
Member

Choose a reason for hiding this comment

The 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 mFirstFrictionDirection to non-zero vector intentionally) because first/second friction coefficients would make more sense when they're aligned with local directions (if they have different values).

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.

Copy link
Collaborator Author

Choose a reason for hiding this comment

The 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.

Copy link
Member

Choose a reason for hiding this comment

The 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?).

Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

how does cddef7a look to you?

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks awesome! Thank you for adding it.

@scpeters scpeters added this to the DART 6.10.0 milestone Dec 6, 2019
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

3 participants