pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
ur5x4.py
1"""
2Load 4 times the UR5 model, plus a plate object on top of them, to feature a simple
3parallel robot.
4No optimization, this file is just an example of how to load the models.
5"""
6
7from pathlib import Path
8
9import numpy as np
10from pinocchio import SE3
11from pinocchio.robot_wrapper import RobotWrapper
12from pinocchio.utils import eye, rotate, se3ToXYZQUATtuple, urdf, zero
13
14PKG = Path("/opt/openrobots/share")
15URDF = PKG / "ur5_description/urdf/ur5_gripper.urdf"
16
17
18def loadRobot(M0, name):
19 """
20 This function load a UR5 robot n a new model, move the basis to placement <M0>
21 and add the corresponding visuals in gepetto viewer with name prefix given by string
22 <name>.
23 It returns the robot wrapper (model,data).
24 """
25 robot = RobotWrapper(urdf, [PKG])
26 robot.model.jointPlacements[1] = M0 * robot.model.jointPlacements[1]
27 robot.visual_model.geometryObjects[0].placement = (
28 M0 * robot.visual_model.geometryObjects[0].placement
29 )
30 robot.visual_data.oMg[0] = M0 * robot.visual_data.oMg[0]
31 robot.initDisplay(loadModel=True, viewerRootNodeName="world/" + name)
32 return robot
33
34
35robots = []
36# Load 4 Ur5 robots, placed at 0.3m from origin in the 4 directions x,y,-x,-y.
37Mt = SE3(eye(3), np.array([0.3, 0, 0])) # First robot is simply translated
38for i in range(4):
39 robots.append(loadRobot(SE3(rotate("z", np.pi / 2 * i), zero(3)) * Mt, f"robot{i}"))
40
41# Set up the robots configuration with end effector pointed upward.
42q0 = np.array([np.pi / 4, -np.pi / 4, -np.pi / 2, np.pi / 4, np.pi / 2, 0])
43for i in range(4):
44 robots[i].display(q0)
45
46# Add a new object featuring the parallel robot tool plate.
47gepettoViewer = robots[0].viewer.gui
48w, h, d = 0.25, 0.25, 0.005
49color = [red, green, blue, transparency] = [1, 1, 0.78, 1.0]
50gepettoViewer.addBox("world/toolplate", w, h, d, color)
51Mtool = SE3(rotate("z", 1.268), np.array([0, 0, 0.77]))
52gepettoViewer.applyConfiguration("world/toolplate", se3ToXYZQUATtuple(Mtool))
53gepettoViewer.refresh()
loadRobot(M0, name)
Definition ur5x4.py:18