cfmDamping: documentation please
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