robot-wrapper-viewer.py
Go to the documentation of this file.
1 #
2 # In this short script, we show how to use RobotWrapper
3 # integrating different kinds of viewers
4 #
5 
6 import pinocchio as pin
7 from pinocchio.robot_wrapper import RobotWrapper
8 from pinocchio.visualize import (GepettoVisualizer, MeshcatVisualizer)
9 from sys import argv
10 import os
11 from os.path import dirname, join, abspath
12 
13 # If you want to visualize the robot in this example,
14 # you can choose which visualizer to employ
15 # by specifying an option from the command line:
16 # GepettoVisualizer: -g
17 # MeshcatVisualizer: -m
18 VISUALIZER = None
19 if len(argv)>1:
20  opt = argv[1]
21  if opt == '-g':
22  VISUALIZER = GepettoVisualizer
23  elif opt == '-m':
24  VISUALIZER = MeshcatVisualizer
25  else:
26  raise ValueError("Unrecognized option: " + opt)
27 
28 # Load the URDF model with RobotWrapper
29 # Conversion with str seems to be necessary when executing this file with ipython
30 pinocchio_model_dir = join(dirname(dirname(str(abspath(__file__)))),"models")
31 
32 model_path = join(pinocchio_model_dir,"example-robot-data/robots")
33 mesh_dir = pinocchio_model_dir
34 urdf_filename = "talos_reduced.urdf"
35 urdf_model_path = join(join(model_path,"talos_data/robots"),urdf_filename)
36 
37 robot = RobotWrapper.BuildFromURDF(urdf_model_path, mesh_dir, pin.JointModelFreeFlyer())
38 
39 # alias
40 model = robot.model
41 data = robot.data
42 
43 # do whatever, e.g. compute the center of mass position expressed in the world frame
44 q0 = robot.q0
45 com = robot.com(q0)
46 
47 # This last command is similar to:
48 com2 = pin.centerOfMass(model,data,q0)
49 
50 # Show model with a visualizer of your choice
51 if VISUALIZER:
52  robot.setVisualizer(VISUALIZER())
53  robot.initViewer()
54  robot.loadViewerModel("pinocchio")
55  robot.display(q0)


pinocchio
Author(s):
autogenerated on Tue Jun 1 2021 02:45:04