1 from pathlib 
import Path
 
    7 pinocchio_model_dir = Path(__file__).parent.parent / 
"models" 
   10     (pinocchio_model_dir / 
"example-robot-data/robots") 
if len(argv) < 2 
else argv[1]
 
   12 mesh_dir = pinocchio_model_dir
 
   13 urdf_model_path = model_path / 
"ur_description/urdf/ur5_robot.urdf" 
   16 model, collision_model, visual_model = pinocchio.buildModelsFromUrdf(
 
   17     urdf_model_path, mesh_dir
 
   19 print(
"model name: " + model.name)
 
   22 data, collision_data, visual_data = pinocchio.createDatas(
 
   23     model, collision_model, visual_model
 
   38 print(
"\nJoint placements:")
 
   39 for name, oMi 
in zip(model.names, data.oMi):
 
   40     print(
"{:<24} : {: .2f} {: .2f} {: .2f}".format(name, *oMi.translation.T.flat))
 
   43 print(
"\nCollision object placements:")
 
   44 for k, oMg 
in enumerate(collision_data.oMg):
 
   45     print(
"{:d} : {: .2f} {: .2f} {: .2f}".format(k, *oMg.translation.T.flat))
 
   48 print(
"\nVisual object placements:")
 
   49 for k, oMg 
in enumerate(visual_data.oMg):
 
   50     print(
"{:d} : {: .2f} {: .2f} {: .2f}".format(k, *oMg.translation.T.flat))