5 import pinocchio
as pin
9 from os.path import dirname, join, abspath
15 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),
"models")
17 model_path = join(pinocchio_model_dir,
"example-robot-data/robots")
18 mesh_dir = pinocchio_model_dir
19 urdf_filename =
"romeo_small.urdf" 20 urdf_model_path = join(join(model_path,
"romeo_description/urdf"),urdf_filename)
22 model, collision_model, visual_model = pin.buildModelsFromUrdf(urdf_model_path, mesh_dir, pin.JointModelFreeFlyer())
25 for geom
in visual_model.geometryObjects:
30 viz = MeshcatVisualizer(model, collision_model, visual_model)
39 viz.initViewer(open=
True)
40 except ImportError
as err:
41 print(
"Error while initializing the viewer. It seems you should install Python meshcat")
48 viz.loadViewerModel(color = [0.0, 0.0, 0.0, 1.0])
52 0, 0, 0.840252, 0, 0, 0, 1,
53 0, 0, -0.3490658, 0.6981317, -0.3490658, 0,
54 0, 0, -0.3490658, 0.6981317, -0.3490658, 0,
56 1.5, 0.6, -0.5, -1.05, -0.4, -0.3, -0.2,
58 1.5, -0.6, 0.5, 1.05, -0.4, -0.3, -0.2,
63 red_robot_viz = MeshcatVisualizer(model, collision_model, visual_model)
64 red_robot_viz.initViewer(viz.viewer)
65 red_robot_viz.loadViewerModel(rootNodeName =
"red_robot", color = [1.0, 0.0, 0.0, 0.5])
68 red_robot_viz.display(q)