Open EricCousineau-TRI opened 1 year ago
In the FWIW category, using a sigmoid like hyperbolic tangent seems "better" than arctan, at least for making the continuous-time integrator "happy":
def arctanh(y):
u = -(y + 1) / (y - 1)
x = np.log(u) / 2
return x
def regularizer_tanh(s, *, m=0.95):
"""m: Desired value for r(1)"""
c = arctanh(m)
value = np.tanh(c * s)
return value
Still (slowly) doing basic sys id and very simple simulation experiments on compensation.
fwiw -- i just ran into this, too. Specifically I was hoping to have joint stiction (via the urdf/joint friction element) in SAP, and found the same message in the urdf parser.
From having tried out control with stiction + damping compensation on the plant, these terms do seem critical.
Is it possible to have these also as parameters in the plant? \cc @joemasterjohn
Supporting joint-level dry friction would be very useful for more accurate manipulator modelling
Hi, I'd like to follow up on this issue and ask if there's any workaround solution? I'm trying to simulate the friction by compensating the input torque to the multibody plant. However, when I do so both effort and joint velocity start to oscillate.
A snippet of my code is copied below:
VectorX<T> torque_output = torque_input;
for (std::size_t i = 0; i < num_joints_; ++i) {
auto joint_velocity = joint_state[num_joints_ + i];
if (std::abs(joint_velocity) < joint_velocity_threshold_) {
torque_output[i] +=
-frictions_[i] * joint_velocity / joint_velocity_threshold_;
} else {
torque_output[i] += frictions_[i] * (joint_velocity > 0 ? -1 : 1);
}
control->SetFromVector(torque_output);
}
The plot of the joint velocity, desired torque and torque after compensation:
Thanks for any help!
Is your feature request related to a problem? Please describe. Relates #6527
Per f2f w/ Ale, we most likely don't support joint-level dry friction, aside from damping (viscous friction). Seems confirmed by not seeing something relevant in current API, and per message here: https://github.com/RobotLocomotion/drake/blob/2467945ffa9b9afe3879bbbe1a975a40e5b57759/multibody/parsing/detail_urdf_parser.cc#L405-L407
Specs appear to support it:
//joint/dynamics/@friction
//joint/axis/dynamics/@friction
//body/joint/@frictionloss
attribute?Describe the solution you'd like Would be nice to at least simple dry friction in MultibodyPlant for both continuous-time and discrete-time plants / solvers.
Ideally, where viable, it would be nice to have Stribeck static / dynamic friction (only continuous-time?).
Describe alternatives you've considered As a workaround, I can implement my own simple dry stiction model as a separate applied generalized force that I will then feed that into the MbP. If want some level of accuracy, then I can use an implicit integrator.
Additional context This is for doing basic system-id, trying to estimate stiction at the joints.
\cc @AdityaBhat-TRI