Gazebo | Ignition | Community
Ask Your Question
0

cfmDamping: documentation please

asked 2013-03-15 18:28:15 -0500

cga gravatar image

What is cfmDamping and why was it added? Does it replace

    dynamics damping="0.1" friction="0"

on all the atlas joints? Both kinds of damping seem to be applied to all body joints. Does it lead to a more accurate simulation of pure viscous damping with a fixed value? What is that viscous damping coefficient?

So everyone understands what I am talking about, here is the relevant code from gazebo/physics/ode/ODEJoint.cc
When not at joint limit:

      if (this->cfmDampingState[i] != ODEJoint::DAMPING_ACTIVE)
      {
        // add additional constraint row by fake hitting joint limit
        // then, set erp and cfm to simulate viscous joint damping
        this->SetAttribute("stop_erp", i, 0.0);
        this->SetAttribute("stop_cfm", i, 1.0 / this->dampingCoefficient);
        this->SetAttribute("hi_stop", i, 0.0);
        this->SetAttribute("lo_stop", i, 0.0);
        this->SetAttribute("hi_stop", i, 0.0);
        this->cfmDampingState[i] = ODEJoint::DAMPING_ACTIVE;
      }

The old form of damping seems still operational in gazebo/physics/Joint.cc

  double dampingForce = -this->dampingCoefficient * this->GetVelocity(0);
  this->SetForce(0, dampingForce);

We need to understand cfmDamping to get our models of your model to be correct.

Thanks, Chris

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
1

answered 2013-03-15 20:30:44 -0500

hsu gravatar image

The damping method is selected in SetDamping,

    if (this->useCFMDamping)
      this->applyDamping = physics::Joint::ConnectJointUpdate(
        boost::bind(&ODEJoint::CFMDamping, this));
    else
      this->applyDamping = physics::Joint::ConnectJointUpdate(
        boost::bind(&ODEJoint::ApplyDamping, this));
    this->dampingInitialized = true;

So only one of CFMDamping or ApplyDamping is called.

To answer your question regarding cfmDamping method, it is effectively moving the viscous damping force calculation into the constraint equation. So the two methods should yield the same behavior if LCP is solved to infinite precision with infinitely small time steps. The cfm damping approach has the benefits of solving for damping force implicitly, allowing infinitely large damping coefficients (converges to a fixed joint in the limit as damping coefficient goes to infinity).

The relationship between cfm, erp, spring stiffness (kp) and damping (kd) coefficients are layed out in the ODE manual. There's some more forum discussion here for reference.

edit flag offensive delete link more

Question Tools

Stats

Asked: 2013-03-15 18:28:15 -0500

Seen: 1,477 times

Last updated: Mar 15 '13