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 force dependent slip #1505

Merged
merged 9 commits into from
Dec 29, 2020
Merged
Show file tree
Hide file tree
Changes from 6 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
41 changes: 41 additions & 0 deletions dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@
*/

#include "dart/constraint/ConstraintSolver.hpp"
#include <algorithm>
azeey marked this conversation as resolved.
Show resolved Hide resolved

#include "dart/collision/CollisionFilter.hpp"
#include "dart/collision/CollisionGroup.hpp"
Expand Down Expand Up @@ -478,6 +479,29 @@ void ConstraintSolver::updateConstraints()
// Destroy previous soft contact constraints
mSoftContactConstraints.clear();

// Create a mapping of contact pairs to the number of contacts between them
using ContactPair
= std::pair<collision::CollisionObject*, collision::CollisionObject*>;

// Compare contact pairs while ignoring their order in the pair.
struct ContactPairCompare
{
ContactPair SortedPair(const ContactPair& a) const
azeey marked this conversation as resolved.
Show resolved Hide resolved
{
if (a.first < a.second)
return std::make_pair(a.second, a.first);
return a;
}

bool operator()(const ContactPair& a, const ContactPair& b) const
{
// Sort each pair and then do a lexicographical comparison
return SortedPair(a) < SortedPair(b);
}
};

std::map<ContactPair, size_t, ContactPairCompare> contactPairMap;
Copy link
Member

Choose a reason for hiding this comment

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

Consider using std::unordered_map as the order of the pair doesn't matter in the use cases

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I opted for using a std::map because I thought a writing a compare function was easier than writing a hash function. If you think performance would be a problem, I can look into a hash function for ContactPair and using std::unordered_map.

Copy link
Member

Choose a reason for hiding this comment

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

Using std::unordered_map would increase the performance since the find query will be called per contact constraints for every simulation step. But it's not critical for this PR. Let's save it for a future change.


// Create new contact constraints
for (auto i = 0u; i < mCollisionResult.getNumContacts(); ++i)
{
Expand Down Expand Up @@ -515,6 +539,10 @@ void ConstraintSolver::updateConstraints()
}
else
{
// Increment the count of contacts between the two collision objects
++contactPairMap[std::make_pair(
contact.collisionObject1, contact.collisionObject2)];

mContactConstraints.push_back(
std::make_shared<ContactConstraint>(contact, mTimeStep));
}
Expand All @@ -523,6 +551,19 @@ void ConstraintSolver::updateConstraints()
// Add the new contact constraints to dynamic constraint list
for (const auto& contactConstraint : mContactConstraints)
{
// update the slip compliances of the contact constraints based on the
// number of contacts between the collision objects.
auto& contact = contactConstraint->getContact();
std::size_t numContacts = 1;
auto it = contactPairMap.find(
std::make_pair(contact.collisionObject1, contact.collisionObject2));
if (it != contactPairMap.end())
numContacts = it->second;

contactConstraint->setPrimarySlipCompliance(
contactConstraint->getPrimarySlipCompliance() * numContacts);
contactConstraint->setSecondarySlipCompliance(
contactConstraint->getSecondarySlipCompliance() * numContacts);
Comment on lines +568 to +571
Copy link
Member

Choose a reason for hiding this comment

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

Could you let me know why we need to multiply the slip compliance by the number of contacts?

If I understand correctly, the slip effect will be applied per contact anyway when there were multiple contacts for the same object pair. Suppose we have two contacts for the same object pair and multiply the slip compliance by two, then the doubled slip effect will happen at the two contact points.

Copy link
Collaborator

Choose a reason for hiding this comment

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

A similar change was made in gazebosim/gazebo-classic@402b9d3 (see also bitbucket PR 2965). The analogy between slip and linear damping is useful here as well. Each contact point with slip acts like an extra damper acting in parallel, which increases the total slip acting on the body. This multiplication aims to make the total slip invariant of the number of contact points.

Copy link
Member

@jslee02 jslee02 Dec 28, 2020

Choose a reason for hiding this comment

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

This description seems very useful. Could we add a note about that something like these lines?

    // The slip compliance acts like a damper at each contact point so the total
    // damping for each collision is multiplied by the number of contact points
    // (numContacts). To eliminate this dependence on numContacts, the inverse
    // damping is multiplied by numContacts.

I tried to edit it myself, but it seems the fork doesn't exist anymore. If that's the case then it's okay to merge this as it is and then add the comment in a new PR.

Never mind, it's edited.

contactConstraint->update();

if (contactConstraint->isActive())
Expand Down
106 changes: 106 additions & 0 deletions dart/constraint/ContactConstraint.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,7 @@ double ContactConstraint::mConstraintForceMixing = DART_CFM;

constexpr double DART_DEFAULT_FRICTION_COEFF = 1.0;
constexpr double DART_DEFAULT_RESTITUTION_COEFF = 0.0;
constexpr double DART_DEFAULT_SLIP_COMPLIANCE = 0.0;
const Eigen::Vector3d DART_DEFAULT_FRICTION_DIR = Eigen::Vector3d::UnitZ();

//==============================================================================
Expand All @@ -84,6 +85,8 @@ ContactConstraint::ContactConstraint(
.get()),
mContact(contact),
mFirstFrictionalDirection(DART_DEFAULT_FRICTION_DIR),
mSlipCompliance(DART_DEFAULT_SLIP_COMPLIANCE),
mSecondarySlipCompliance(DART_DEFAULT_SLIP_COMPLIANCE),
mIsFrictionOn(true),
mAppliedImpulseIndex(dynamics::INVALID_INDEX),
mIsBounceOn(false),
Expand Down Expand Up @@ -136,6 +139,18 @@ ContactConstraint::ContactConstraint(
{
mIsFrictionOn = true;

// Compute slip compliance
const double slipComplianceA = computeSlipCompliance(shapeNodeA);
const double slipComplianceB = computeSlipCompliance(shapeNodeB);
const double secondarySlipComplianceA
= computeSecondarySlipCompliance(shapeNodeA);
const double secondarySlipComplianceB
= computeSecondarySlipCompliance(shapeNodeB);
// Combine slip compliances through addition
mSlipCompliance = slipComplianceA + slipComplianceB;
mSecondarySlipCompliance
= secondarySlipComplianceA + secondarySlipComplianceB;

// Check shapeNodes for valid friction direction unit vectors
auto frictionDirA = computeWorldFirstFrictionDir(shapeNodeA);
auto frictionDirB = computeWorldFirstFrictionDir(shapeNodeB);
Expand Down Expand Up @@ -627,6 +642,17 @@ void ContactConstraint::getVelocityChange(double* vel, bool withCfm)
{
vel[mAppliedImpulseIndex]
+= vel[mAppliedImpulseIndex] * mConstraintForceMixing;
switch (mAppliedImpulseIndex)
{
case 1:
vel[1] += (mSlipCompliance / mTimeStep);
break;
case 2:
vel[2] += (mSecondarySlipCompliance / mTimeStep);
break;
default:
break;
}
}
}

Expand Down Expand Up @@ -786,6 +812,57 @@ double ContactConstraint::computeSecondaryFrictionCoefficient(
return dynamicAspect->getSecondaryFrictionCoeff();
}

//==============================================================================
double ContactConstraint::computeSlipCompliance(
const dynamics::ShapeNode* shapeNode)
{
assert(shapeNode);

auto dynamicAspect = shapeNode->getDynamicsAspect();

if (dynamicAspect == nullptr)
{
dtwarn << "[ContactConstraint] Attempt to extract slip compliance "
<< "from a ShapeNode that doesn't have DynamicAspect. The default "
<< "value (" << DART_DEFAULT_SLIP_COMPLIANCE << ") will be used "
<< "instead.\n";
return DART_DEFAULT_SLIP_COMPLIANCE;
}

double slipCompliance = dynamicAspect->getSlipCompliance();
if (slipCompliance < 0)
Copy link
Member

Choose a reason for hiding this comment

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

Correct me if I'm wrong. It seems a negative slip also makes sense, unlike friction. For example, a rotating tire could make slip either left or right.

Copy link
Collaborator

Choose a reason for hiding this comment

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

I understand slip compliance to be similar to a linear damping coefficient (actually the inverse, see gazebo's WheelSlipPlugin documentation), with a positive value corresponding to a dissipative effect. A negative value, on the other hand, would be non-dissipative and non-physical, similar to having a negative coefficient of friction.

Copy link
Contributor Author

Choose a reason for hiding this comment

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

Yeah, I agree with @scpeters. In the rotating tire example, the tire can slip left or right, but that will be determined by the force applied on the tire. The slip velocity will always be in the same direction as the net external force. A negative slip parameter would mean a velocity opposite to the net external force, which seems non-physical.

Quoting from the ODE manual:

FDS is an effect that causes the contacting surfaces to side past each other with a velocity that is proportional to the force that is being applied tangentially to that surface.

Consider a contact point where the coefficient of friction mu is infinite. Normally, if a force f is applied to the two contacting surfaces, to try and get them to slide past each other, they will not move. However, if the FDS coefficient is set to a positive value k then the surfaces will slide past each other, building up to a steady velocity of kf relative to each other.

Copy link
Member

Choose a reason for hiding this comment

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

Makes sense to me. Thanks for the explanation

{
return DART_DEFAULT_SLIP_COMPLIANCE;
}
return slipCompliance;
}

//==============================================================================
double ContactConstraint::computeSecondarySlipCompliance(
const dynamics::ShapeNode* shapeNode)
{
assert(shapeNode);

auto dynamicAspect = shapeNode->getDynamicsAspect();

if (dynamicAspect == nullptr)
{
dtwarn << "[ContactConstraint] Attempt to extract "
<< "secondary slip compliance "
<< "from a ShapeNode that doesn't have DynamicAspect. The default "
<< "value (" << DART_DEFAULT_SLIP_COMPLIANCE << ") will be used "
<< "instead.\n";
return DART_DEFAULT_SLIP_COMPLIANCE;
}

double slipCompliance = dynamicAspect->getSecondarySlipCompliance();
if (slipCompliance < 0)
{
return DART_DEFAULT_SLIP_COMPLIANCE;
}
return slipCompliance;
}

//==============================================================================
Eigen::Vector3d ContactConstraint::computeWorldFirstFrictionDir(
const dynamics::ShapeNode* shapeNode)
Expand Down Expand Up @@ -950,5 +1027,34 @@ void ContactConstraint::uniteSkeletons()
}
}

//==============================================================================
double ContactConstraint::getPrimarySlipCompliance() const
{
return mSlipCompliance;
}

//==============================================================================
void ContactConstraint::setPrimarySlipCompliance(double slip)
{
mSlipCompliance = slip;
}

//==============================================================================
double ContactConstraint::getSecondarySlipCompliance() const
{
return mSecondarySlipCompliance;
}

//==============================================================================
void ContactConstraint::setSecondarySlipCompliance(double slip)
{
mSecondarySlipCompliance = slip;
}

//==============================================================================
const collision::Contact& ContactConstraint::getContact() const
{
return mContact;
}
azeey marked this conversation as resolved.
Show resolved Hide resolved
} // namespace constraint
} // namespace dart
29 changes: 29 additions & 0 deletions dart/constraint/ContactConstraint.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -144,6 +144,9 @@ class ContactConstraint : public ConstraintBase
const dynamics::ShapeNode* shapeNode);
static double computeSecondaryFrictionCoefficient(
const dynamics::ShapeNode* shapeNode);
static double computeSlipCompliance(const dynamics::ShapeNode* shapeNode);
azeey marked this conversation as resolved.
Show resolved Hide resolved
static double computeSecondarySlipCompliance(
const dynamics::ShapeNode* shapeNode);
static Eigen::Vector3d computeWorldFirstFrictionDir(
const dynamics::ShapeNode* shapenode);
static double computeRestitutionCoefficient(
Expand All @@ -163,6 +166,26 @@ class ContactConstraint : public ConstraintBase
///
TangentBasisMatrix getTangentBasisMatrixODE(const Eigen::Vector3d& n);

// The following functions for getting and setting slip compliance and
// accessing the contact object are meant to be used by ConstraintSolver to
// update the slip compliances based on the number of contacts between the
// collision objects.
//
/// Get primary slip compliance
double getPrimarySlipCompliance() const;

/// Set primary slip compliance
void setPrimarySlipCompliance(double slip);

/// Get secondary slip compliance
double getSecondarySlipCompliance() const;

/// Set secondary slip compliance
void setSecondarySlipCompliance(double slip);

/// Get contact object associated witht this constraint
const collision::Contact& getContact() const;

private:
/// Time step
double mTimeStep;
Expand All @@ -185,6 +208,12 @@ class ContactConstraint : public ConstraintBase
/// Primary Coefficient of Friction
double mSecondaryFrictionCoeff;

/// Primary Coefficient of Slip Compliance
double mSlipCompliance;
azeey marked this conversation as resolved.
Show resolved Hide resolved

/// Secondary Coefficient of Slip Compliance
double mSecondarySlipCompliance;

/// Coefficient of restitution
double mRestitutionCoeff;

Expand Down
6 changes: 6 additions & 0 deletions dart/dynamics/ShapeFrame.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,8 @@ DynamicsAspectProperties::DynamicsAspectProperties(
: mFrictionCoeff(frictionCoeff),
mRestitutionCoeff(restitutionCoeff),
mSecondaryFrictionCoeff(frictionCoeff),
mSlipCompliance(-1.0),
mSecondarySlipCompliance(-1.0),
mFirstFrictionDirection(Eigen::Vector3d::Zero()),
mFirstFrictionDirectionFrame(nullptr)
{
Expand All @@ -69,11 +71,15 @@ DynamicsAspectProperties::DynamicsAspectProperties(
const double primaryFrictionCoeff,
const double secondaryFrictionCoeff,
const double restitutionCoeff,
const double slipCompliance,
const double secondarySlipCompliance,
const Eigen::Vector3d& firstFrictionDirection,
const Frame* firstFrictionDirectionFrame)
: mFrictionCoeff(primaryFrictionCoeff),
mRestitutionCoeff(restitutionCoeff),
mSecondaryFrictionCoeff(secondaryFrictionCoeff),
mSlipCompliance(slipCompliance),
mSecondarySlipCompliance(secondarySlipCompliance),
mFirstFrictionDirection(firstFrictionDirection),
mFirstFrictionDirectionFrame(firstFrictionDirectionFrame)
{
Expand Down
12 changes: 12 additions & 0 deletions dart/dynamics/ShapeFrame.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,18 @@ class DynamicsAspect final : public common::AspectWithVersionedProperties<
// void setRestitutionCoeff(const double& value);
// const double& getRestitutionCoeff() const;

/// Slip compliance parameters act as constraint force mixing (cfm)
/// for the friction constraints.
/// They start with a default value of -1.0 and will be ignored
/// in favor of the global default value unless explicitly
/// set to a positive value.
DART_COMMON_SET_GET_ASPECT_PROPERTY(double, SlipCompliance)
// void setSlipCompliance(const double& value);
// const double& getSlipCompliance() const;
DART_COMMON_SET_GET_ASPECT_PROPERTY(double, SecondarySlipCompliance)
// void setSecondarySlipCompliance(const double& value);
// const double& getSecondarySlipCompliance() const;

/// Set the frame for interpreting the first friction direction vector.
/// The frame pointer defaults to nullptr, which is interpreted as this
/// ShapeFrame.
Expand Down
8 changes: 8 additions & 0 deletions dart/dynamics/detail/ShapeFrameAspect.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -97,6 +97,12 @@ struct DynamicsAspectProperties
/// Secondary coefficient of friction
double mSecondaryFrictionCoeff;

/// Primary slip compliance coefficient
double mSlipCompliance;
azeey marked this conversation as resolved.
Show resolved Hide resolved

/// Secondary slip compliance coefficient
double mSecondarySlipCompliance;

/// First friction direction unit vector
Eigen::Vector3d mFirstFrictionDirection;

Expand Down Expand Up @@ -128,6 +134,8 @@ struct DynamicsAspectProperties
const double primaryFrictionCoeff,
const double secondaryFrictionCoeff,
const double restitutionCoeff,
const double slipCompliance = -1.0,
azeey marked this conversation as resolved.
Show resolved Hide resolved
const double secondarySlipCompliance = -1.0,
const Eigen::Vector3d& firstFrictionDirection = Eigen::Vector3d::Zero(),
const Frame* firstFrictionDirectionFrame = nullptr);

Expand Down
7 changes: 7 additions & 0 deletions unittests/comprehensive/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,13 @@ if(TARGET dart-collision-bullet)
target_link_libraries(test_Raycast dart-collision-bullet)
endif()

if(TARGET dart-collision-ode)
# This test doesn't work with FCL because it converts simple shapes to meshes, which makes
# it difficult to come up with correct test expectations.
dart_add_test("comprehensive" test_ForceDependentSlip)
target_link_libraries(test_ForceDependentSlip dart-collision-ode)
endif()

if(TARGET dart-utils)

dart_add_test("comprehensive" test_Collision)
Expand Down
Loading