6 from pathlib
import Path
9 import pinocchio
as pin
14 pinocchio_model_dir = Path(__file__).parent.parent /
"models"
16 model_path = pinocchio_model_dir /
"example-robot-data/robots"
17 mesh_dir = pinocchio_model_dir
20 urdf_filename =
"solo.urdf"
21 urdf_model_path = model_path /
"solo_description/robots" / urdf_filename
23 model, collision_model, visual_model = pin.buildModelsFromUrdf(
24 urdf_model_path, mesh_dir, pin.JointModelFreeFlyer()
36 viz.initViewer(open=
True)
37 except ImportError
as err:
39 "Error while initializing the viewer. "
40 "It seems you should install Python meshcat"
49 q0 = pin.neutral(model)
51 viz.displayVisuals(
True)
54 mesh = visual_model.geometryObjects[0].geometry
55 mesh.buildConvexRepresentation(
True)
59 if convex
is not None:
60 placement = pin.SE3.Identity()
61 placement.translation[0] = 2.0
62 geometry = pin.GeometryObject(
"convex", 0, placement, convex)
63 geometry.meshColor = np.ones(4)
65 geometry.overrideMaterial =
True
66 geometry.meshMaterial = pin.GeometryPhongMaterial()
67 geometry.meshMaterial.meshEmissionColor = np.array([1.0, 0.1, 0.1, 1.0])
68 geometry.meshMaterial.meshSpecularColor = np.array([0.1, 1.0, 0.1, 1.0])
69 geometry.meshMaterial.meshShininess = 0.8
70 visual_model.addGeometryObject(geometry)
77 viz2.initViewer(viz.viewer)
78 viz2.loadViewerModel(rootNodeName=
"pinocchio2")
85 [0.0, 0.0, 0.235, 0.0, 0.0, 0.0, 1.0, 0.8, -1.6, 0.8, -1.6, -0.8, 1.6, -0.8, 1.6]
88 v0 = np.random.randn(model.nv) * 2
90 pin.forwardKinematics(model, data, q1, v0)
91 frame_id = model.getFrameId(
"HR_FOOT")
93 viz.drawFrameVelocities(frame_id=frame_id)
95 model.gravity.linear[:] = 0.0
100 tau0 = np.zeros(model.nv)
104 for i
in range(nsteps):
107 a1 = pin.aba(model, data, q, v, tau0)
109 qnext = pin.integrate(model, q, dt * vnext)
113 viz.drawFrameVelocities(frame_id=frame_id)
119 fid2 = model.getFrameId(
"FL_FOOT")
123 viz.drawFrameVelocities(frame_id)
124 viz.drawFrameVelocities(fid2)
127 with viz.create_video_ctx(
"../leap.mp4"):
128 viz.play(qs, dt, callback=my_callback)