Start a new topic
Answered

(Rolling) Friction Coefficient

I am using Vortex Essentials to create a (rigid body) simulation of a ball-on-plate scenario. Therefore, I want to manipulate the friction of the contact between the ball and the plate. The friction should be in the form of linear and angular movement friction.


My current solution, which uses kFrictionModelScaledBox, looks like this:


 

mymaterial->setFrictionModel(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, Vx::VxMaterialBase::kFrictionModelScaledBox);

mymaterial->setFrictionModel(Vx::VxMaterialBase::kFrictionAxisAngularSecondary, Vx::VxMaterialBase::kFrictionModelScaledBox);

mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisLinear, myvalue1);

mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, myvalue2);

mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularSecondary, myvalue2);


But after reading the documentation on "void Vx::VxMaterialBase::setFrictionCoefficient(axis, coeff)", I am confused. Should myvalue2 be scaled with the radius of the ball?


Or should I use Vx::VxRollingResistance? Could you explain what is the difference between (rolling) resistance and (rolling) friction in Vortex?


Which paramter/coefficient/friction model do I have to set when I want to implement friciton that is proportional to the (relative) velocity?


Best regards,


Best Answer

Hi Fabio,


Using scaled box friction will set the maximum allowed friction force (or torque, in case of the rolling or twist friction, defined through kFrictionAxisAngularPrimary and ...Secondary) to the provided friction coefficient times the normal force, i.e., the force applied along the contact normal. The contact normal can be visualized via the debug visualizations in the editor, either by pressing keyboard shortcut shift-c, or via the debug visualization menu accessible via right click in the 3D view. Note that you can also visualize the primary friction axis by turning on contact visualization (shift-c) and then switching through the various contact displays via alt-c. First time shift-c shows contact normal. Then pressing alt-c shows primary axis. There are also displays for contact force and torque.


The friction force or torque will act to obtain zero relative velocity along the friction axis for kFrictionAxisLinear..., or about the friction axis for kFrictionAxisAngular... . The solver will apply as much force as required to achieve this kinematic state, up to the maximum allowed friction force (see last paragraph).


However, there is a way to obtain viscous properties in the friction force and torque. This can be achieved via the slip parameter. The slip parameter is defined as the inverse of a damping coefficient and has therefore the effect of making the friction constraint behave like a damper. That is, the friction fore will be linearly proportional to the relative velocity along (linear case) or about (angular case) the friction axis.

Note that the maximum allowed friction fore is still capped according to the normal force and the friction coefficient (see explanation above). So, the friction constraint will act like a damper but with a force cap defined by the friction coefficient times the normal force.


Example: 

// use scaled box, i.e., coulomb friction, which will set maximum allowed friction torque applied about primary axis (the friction torque cap) to T_max = N * 
const double phi = 0.7;

mymaterial->setFrictionModel(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, Vx::VxMaterialBase::kFrictionModelScaledBox);
mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, phi);

// Give friction constraint viscous properties via slip parameter.
// Applied friction torque will be linearly proportional to relative angular velocity at contact point and about the primary axis.
// That is, together with friction torque cap from scaled box model (see above), friction torque will be T = min(T_max, (1/slip) * relativeAngularSpeed)

const double dampingCoeff = 10000;
const double slip = 1.0 / dampingCoeff;
mymaterial->setSlip(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, slip).

 

Let me know if you have further questions.


Cheers,

Daniel



Hi Fabio,


That's great. I am glad I could help.


Regarding the edit feature: I totally agree. Will pass the message on.


Cheers,

Daniel

Hi Daniel,

indeed, you were. So the topic is closed for me.

Just a side note: it would be nice, if the users were able to edit their comments in hindsight (e.g., polish the layout, or correct typos).

Best wishes,
Fabio

 


1 person likes this

Hi Fabio,


Your understanding regarding question 1 seems correct.

I am glad I could be of help.


Cheers,

Daniel

Hi Daniel,


thanks again for your well-written answer. Questions 2) - 5) are now closed for me.


I made that screenshot in question 1) from the function in the documentation which was build on (the fromer payed) version 6.8.1.


After some trials, I found out that one has to scale the coeff with the radius r, if one wants a rolling behavior comparable to the linear movement.


In my experiments a plate was tilted around one axis and I noted the angle at which the ball resting on the plate started rolling. Using static_friction_scale = 1 and a value for Vx::VxMaterialBase::kFrictionAxisLinear (s.t. the ball does not slide) the ball should start rolling, when the plate's angle is above arctan(static_rolling_friction_coeff), see angle of friction on Wikipedia. E.g., for static_rolling_friction_coeff (there is no such variable in Vortex. I just call it like that because this is what I am able to validate) of 0.1 the ball should start rolling at angle >= 5.711°.
Now for me the question was, if static_rolling_friction_coeff = coeff or if static_rolling_friction_coeff = coeff * r (where coeff is what we pass as an argument to Vx::VxMaterialBase::setFrictionCoefficient).

After my evalattion, I am sure that if one once to treat the friction coefficient for a rolling motion like the friction coefficient for a linear motion, it is necessary to scale it with the radius when passing to the Vx::VxMaterialBase::setFrictionCoefficient method. Since I only checked for a ball-on-plate scenario, I can not say if it is the curvature radius or the distance to the CoM. But one can have a look in the mentioned screenshot above.


Finally, if you don't disagree with my statement, I consider question 1) closed, too. But if I made a mistake, please correct me.


Best regards,
Fabio

 


1 person likes this

Hi Fabio,


You say:

"So, as I understood it, Coulomb friction for rotatory motion is achieved by

mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, value);

and linear, velocity-proportional damping for rotatory motion is achieved by
mymaterial->setSlip(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, slip);
 // slip = 1/dampingFactor"


That's right.

Note that the contact plane on which friction is calculated (orthogonal to the contact normal) is spanned by two orthogonal unit vectors, the primary and secondary friction axes. For setting parameters related to angular friction around these axes, use enum values kFrictionAxisAngularPrimary and kFrictionAxisAngularSecondary. 

For setting parameters related to linear (translational) friction along these axes, use enum values kFrictionAxisLinearPrimary and kFrictionAxisLinearSecondary

If you wish your linear or angular friction to act isotropically (on the tangent plane), you need to set the same parameters for both axes respectively.

This also answers your question 2).


Regarding your question 1):

I am not sure what the variable Crr refers to and in which API function it should be provided. Is it a friction coefficient or a friction force/torque?


Regarding your question 3):

For translational (or linear) friction, the coulomb friction coefficient (as defined in literature for the material pairing you want to simulate) should be via VxContactMaterial::setFrictionCoefficient for the enum values kFrictionAxisLinearPrimary and kFrictionAxisLinearSecondary. The contact material is obtained for the corresponding material pairing, e.g., steel/wood, from the universe's material table, via the rigid body response model (see VxUniverse::getRigidBodyResponseModel and VxRigidBodyResponseModel::getMaterialTable).


Regarding your question 4):


VxMaterialBase::setDamping(...) is used for specifying the damping coefficient of the spring-damper response in normal direction at the contact (the rigid collision force). Likewise, VxMaterialBase::setCompliance(...) sets the compliance (or inverse stiffness) of the spring-damper response in normal direction at the contact point. Compliance is defined as inverse stiffness (compliance=1/stiffness).


The function VxMaterialBase::setSlip(FrictionAxis axis, VxReal inSlip) is used to produce viscous friction forces in the tangent plane (orthogonal to the contact normal). This parameter has nothing to do with the damping coefficient for the normal-direction contact force response.


Regarding your question 5):


VxPart::setAngularVelocityDamping(VxReal damping) and VxPart::setLinearVelocityDamping(VxReal damping) define a world space damping force which is applied to the part (rigid body) at its center and is proportional to the part's mass and its linear or angular velocity, respectively. These parameters have nothing to do with friction forces. Setting these damping parameters to anything but zero is not required in the normal simulation case, unless you'd like to need to add artificial velocity damping for simulation for some special effect which is proportional to body velocity. I would recommend you to leave these values at zero.


Let me know if you have further question.


Cheers,

Daniel

Hi Daniel,

 

 

first of all, I want to thank you vary much for your long and helpful answer.

So, as I understood it, Coulomb friction for rotatory motion is achieved by
mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, value);
// 0 <= value <= 1

 

 

and linear, velocity-proportional damping for rotatory motion is achieved by
mymaterial->setSlip(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, slip);
// slip = 1/dampingFactor

 

 

 

But, I still have some questions.
1)
In the Vortex 6.8.1 documentation for the setFrictionCoefficient funciton it says

 

image

But in your code snippet, you set phi for a rotatory motion and did not scale it with the radius (of the ball in my scenario). Why?

 

 

 

2) In your code snippet, you did only set the primary axis. Would a rolling sphere or cylinder behave differently, if I also set a value the secondary axis?

 

 

 

3) If I want to have Coulomb friction for a translatory motion, what do I set as coeff?

 

 

 

4) Is the damping parameter in void Vx::VxMaterialBase::setDamping(VxReal param) the one which is equal to the inverse of the slip? If so, why is there the void Vx::VxMaterialBase::setSlip(FrictionAxis axis, VxReal inSlip) function?

 

 

5) Concerning damping, there are also the VXCORE_SYMBOL void Vx::VxPart::setAngularVelocityDamping(VxReal damping) and VXCORE_SYMBOL void Vx::VxPart::setLinearVelocityDamping(VxReal damping) function, which seem to be a constant and opposing torque/force. How is this type of friction motivated? It looks like Coulomb friction without the proportionality to the normal force. I noticed that these two functions operate on the VxPart and the damping mentioned before. What does this mean for modeling?

 

 

 

I know that this is a lot of questions, but I really can't get my head around when to use which damping function and am looking very much forward to your answers.

 

 

Best wishes,
Fabio

 

Answer

Hi Fabio,


Using scaled box friction will set the maximum allowed friction force (or torque, in case of the rolling or twist friction, defined through kFrictionAxisAngularPrimary and ...Secondary) to the provided friction coefficient times the normal force, i.e., the force applied along the contact normal. The contact normal can be visualized via the debug visualizations in the editor, either by pressing keyboard shortcut shift-c, or via the debug visualization menu accessible via right click in the 3D view. Note that you can also visualize the primary friction axis by turning on contact visualization (shift-c) and then switching through the various contact displays via alt-c. First time shift-c shows contact normal. Then pressing alt-c shows primary axis. There are also displays for contact force and torque.


The friction force or torque will act to obtain zero relative velocity along the friction axis for kFrictionAxisLinear..., or about the friction axis for kFrictionAxisAngular... . The solver will apply as much force as required to achieve this kinematic state, up to the maximum allowed friction force (see last paragraph).


However, there is a way to obtain viscous properties in the friction force and torque. This can be achieved via the slip parameter. The slip parameter is defined as the inverse of a damping coefficient and has therefore the effect of making the friction constraint behave like a damper. That is, the friction fore will be linearly proportional to the relative velocity along (linear case) or about (angular case) the friction axis.

Note that the maximum allowed friction fore is still capped according to the normal force and the friction coefficient (see explanation above). So, the friction constraint will act like a damper but with a force cap defined by the friction coefficient times the normal force.


Example: 

// use scaled box, i.e., coulomb friction, which will set maximum allowed friction torque applied about primary axis (the friction torque cap) to T_max = N * 
const double phi = 0.7;

mymaterial->setFrictionModel(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, Vx::VxMaterialBase::kFrictionModelScaledBox);
mymaterial->setFrictionCoefficient(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, phi);

// Give friction constraint viscous properties via slip parameter.
// Applied friction torque will be linearly proportional to relative angular velocity at contact point and about the primary axis.
// That is, together with friction torque cap from scaled box model (see above), friction torque will be T = min(T_max, (1/slip) * relativeAngularSpeed)

const double dampingCoeff = 10000;
const double slip = 1.0 / dampingCoeff;
mymaterial->setSlip(Vx::VxMaterialBase::kFrictionAxisAngularPrimary, slip).

 

Let me know if you have further questions.


Cheers,

Daniel


Login to post a comment