Skip to content

Commit

Permalink
Include joint friction in ODE state-space representation
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Sep 23, 2022
1 parent 6465f81 commit 226df95
Showing 1 changed file with 15 additions and 9 deletions.
24 changes: 15 additions & 9 deletions src/jaxsim/simulation/ode.py
Original file line number Diff line number Diff line change
Expand Up @@ -105,22 +105,28 @@ def dx_dt(
terrain=terrain,
)

# ==============
# Joint friction
# ==============

kp_friction = physics_model._joint_friction_static.values()
kd_friction = physics_model._joint_friction_static.values()

# Compute the joint friction effects
tau_friction = -(
jnp.diag(kp_friction) @ jnp.sign(ode_state.physics_model.joint_positions)
+ jnp.diag(kd_friction) @ ode_state.physics_model.joint_velocities
)

# ========================
# Compute forward dynamics
# ========================

# Compute the total forces applied to the bodies
total_forces = ode_input.physics_model.f_ext + contact_forces_links

# Compute the mechanical joint torques (real torque sent to the joint) by
# subtracting the optional joint friction
# TODO: add support of coulomb/viscous parameters in parsers and PhysicsModel
kp_friction = jnp.array([0.0] * physics_model.dofs())
kd_friction = jnp.array([0.0] * physics_model.dofs())
tau = ode_input.physics_model.tau - (
jnp.diag(kp_friction) @ jnp.sign(ode_state.physics_model.joint_positions)
+ jnp.diag(kd_friction) @ ode_state.physics_model.joint_velocities
)
# Compute the joint torques to actuate
tau = ode_input.physics_model.tau + tau_friction

W_a_WB, qdd = algos.aba.aba(
model=physics_model,
Expand Down

0 comments on commit 226df95

Please sign in to comment.