3 from pathlib
import Path
7 import pinocchio
as pin
11 pinocchio_model_dir = Path(__file__).parent.parent /
"models"
13 model_path = pinocchio_model_dir /
"example-robot-data/robots"
14 mesh_dir = pinocchio_model_dir
15 urdf_filename =
"ur5_robot.urdf"
16 urdf_model_path = model_path /
"ur_description/urdf" / urdf_filename
18 model1, collision_model1, visual_model1 = pin.buildModelsFromUrdf(
19 urdf_model_path, package_dirs=mesh_dir
24 model2.name =
"pendulum"
25 geom_model = pin.GeometryModel()
28 joint_placement = pin.SE3.Identity()
32 joint_name =
"joint_spherical"
33 joint_id = model2.addJoint(
34 parent_id, pin.JointModelSpherical(), joint_placement, joint_name
37 body_inertia = pin.Inertia.FromSphere(body_mass, body_radius)
38 body_placement = joint_placement.copy()
39 body_placement.translation[2] = 0.1
40 model2.appendBodyToJoint(joint_id, body_inertia, body_placement)
43 shape1 = fcl.Sphere(body_radius)
44 geom1_obj = pin.GeometryObject(geom1_name, joint_id, body_placement, shape1)
45 geom1_obj.meshColor = np.ones(4)
46 geom_model.addGeometryObject(geom1_obj)
49 shape2 = fcl.Cylinder(body_radius / 4.0, body_placement.translation[2])
50 shape2_placement = body_placement.copy()
51 shape2_placement.translation[2] /= 2.0
53 geom2_obj = pin.GeometryObject(geom2_name, joint_id, shape2_placement, shape2)
54 geom2_obj.meshColor = np.array([0.0, 0.0, 0.0, 1.0])
55 geom_model.addGeometryObject(geom2_obj)
57 visual_model2 = geom_model
60 frame_id_end_effector = model1.getFrameId(
"tool0")
61 model, visual_model = pin.appendModel(
66 frame_id_end_effector,
71 f
"Check the joints of the appended model:\n {model} \n "
72 "->Notice the spherical joint at the end."
76 viz = Visualizer(model, visual_model, visual_model)
77 viz.initViewer(open=
True)
78 except ImportError
as err:
80 "Error while initializing the viewer. "
81 "It seems you should install Python meshcat"
90 model.lowerPositionLimit.fill(-math.pi / 2)
91 model.upperPositionLimit.fill(+math.pi / 2)
92 q = pin.randomConfiguration(model)