|
3 | 3 | hppfcl.HeightField.
|
4 | 4 | """
|
5 | 5 |
|
| 6 | +import time |
| 7 | +from pathlib import Path |
| 8 | + |
6 | 9 | import numpy as np
|
7 | 10 | import pinocchio as pin
|
8 |
| -from example_robot_data import load |
9 | 11 | from pinocchio.visualize import MeshcatVisualizer
|
10 | 12 |
|
11 |
| -robot = load("solo12") |
| 13 | +# Load the URDF model. |
| 14 | +# Conversion with str seems to be necessary when executing this file with ipython |
| 15 | +pinocchio_model_dir = Path(__file__).parent.parent / "models" |
| 16 | + |
| 17 | +model_path = pinocchio_model_dir / "example-robot-data/robots" |
| 18 | +mesh_dir = pinocchio_model_dir |
| 19 | +urdf_filename = "solo12.urdf" |
| 20 | +urdf_model_path = model_path / "solo_description/robots" / urdf_filename |
| 21 | + |
| 22 | +model, collision_model, visual_model = pin.buildModelsFromUrdf( |
| 23 | + urdf_model_path, mesh_dir, pin.JointModelFreeFlyer() |
| 24 | +) |
12 | 25 |
|
13 | 26 | q_ref = np.array(
|
14 | 27 | [
|
|
35 | 48 | )
|
36 | 49 |
|
37 | 50 |
|
38 |
| -model = robot.model |
39 |
| -vizer = MeshcatVisualizer(model, robot.collision_model, robot.visual_model) |
40 |
| -vizer.initViewer(loadModel=True) |
| 51 | +vizer = MeshcatVisualizer(model, collision_model, visual_model) |
| 52 | +vizer.initViewer(open=True) |
41 | 53 |
|
42 | 54 |
|
43 | 55 | def ground(xy):
|
@@ -66,11 +78,14 @@ def vizGround(viz, elevation_fn, space, name="ground", color=[1.0, 1.0, 0.6, 0.8
|
66 | 78 | obj = pin.GeometryObject("ground", 0, pl, heightField)
|
67 | 79 | obj.meshColor[:] = color
|
68 | 80 | viz.addGeometryObject(obj)
|
69 |
| - viz.viewer.open() |
70 | 81 |
|
71 | 82 |
|
| 83 | +# Load the robot in the viewer. |
| 84 | +vizer.loadViewerModel() |
| 85 | + |
72 | 86 | colorrgb = [128, 149, 255, 200]
|
73 | 87 | colorrgb = np.array(colorrgb) / 255.0
|
74 | 88 | vizGround(vizer, ground, 0.02, color=colorrgb)
|
75 | 89 |
|
76 | 90 | vizer.display(q_ref)
|
| 91 | +time.sleep(1.0) |
0 commit comments