1 from pathlib
import Path
3 import pinocchio
as pin
5 pinocchio_model_dir = Path(__file__).parent.parent /
"models"
8 /
"example-robot-data/robots/anymal_b_simple_description/robots/anymal.urdf"
10 model = pin.buildModelFromUrdf(urdf_filename)
11 data = model.createData()
13 q0 = pin.neutral(model)
16 feet_names = [
"LH_FOOT",
"RH_FOOT",
"LF_FOOT",
"RF_FOOT"]
18 for foot_name
in feet_names:
19 frame_id = model.getFrameId(foot_name)
20 feet_frame_ids.append(frame_id)
23 for fid
in feet_frame_ids:
24 frame = model.frames[fid]
25 cmodel = pin.RigidConstraintModel(
26 pin.ContactType.CONTACT_3D,
29 pin.LOCAL_WORLD_ALIGNED,
31 contact_models.append(cmodel)
33 contact_data = [cmodel.createData()
for cmodel
in contact_models]
35 pin.initConstraintDynamics(model, data, contact_models)
36 pin.crba(model, data, q0)
38 data.contact_chol.compute(model, data, contact_models, contact_data)
40 delassus_matrix = data.contact_chol.getInverseOperationalSpaceInertiaMatrix()
41 delassus_matrix_inv = data.contact_chol.getOperationalSpaceInertiaMatrix()