Skip to content

Commit

Permalink
Include static and viscous friction parameters into PhysicsModel
Browse files Browse the repository at this point in the history
  • Loading branch information
diegoferigo committed Sep 23, 2022
1 parent 4e6a732 commit 6465f81
Showing 1 changed file with 14 additions and 0 deletions.
14 changes: 14 additions & 0 deletions src/jaxsim/physics/model/physics_model.py
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,9 @@ class PhysicsModel(JaxsimDataclass):
)
_link_inertias_dict: Dict[int, jtp.Matrix] = dataclasses.field(default_factory=dict)

_joint_friction_static: Dict[int, float] = dataclasses.field(default_factory=dict)
_joint_friction_viscous: Dict[int, float] = dataclasses.field(default_factory=dict)

def __post_init__(self):

if self.initial_state is None:
Expand Down Expand Up @@ -90,6 +93,15 @@ def build_from(
joint.index: joint.jtype for joint in model_description.joints
}

# Dicts from the joint index to the static and viscous friction.
# Note: the joint index is equal to its child link index.
joint_friction_static = {
joint.index: joint.friction_static for joint in model_description.joints
}
joint_friction_viscous = {
joint.index: joint.friction_viscous for joint in model_description.joints
}

# Transform between model's root and model's base link
# (this is just the pose of the base link in the SDF description)
base_link = model_description.links_dict[model_description.link_names()[0]]
Expand Down Expand Up @@ -146,6 +158,8 @@ def build_from(
_jtype_dict=joint_types_dict,
_tree_transforms_dict=tree_transforms_dict,
_link_inertias_dict=link_spatial_inertias_dict,
_joint_friction_static=joint_friction_static,
_joint_friction_viscous=joint_friction_viscous,
gravity=jnp.hstack([gravity.squeeze(), np.zeros(3)]),
is_floating_base=True,
gc=GroundContact.build_from(model_description=model_description),
Expand Down

0 comments on commit 6465f81

Please sign in to comment.