pinocchio  3.7.0
A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
 
Loading...
Searching...
No Matches
mobilerobot.py
1import numpy as np
2import pinocchio as pin
3from pinocchio.robot_wrapper import RobotWrapper
4from pinocchio.utils import eye
5
6
7class MobileRobotWrapper(RobotWrapper):
8 """
9 The class models a mobile robot with UR5 arm, feature 3+6 DOF.
10 The configuration of the basis is represented by [X, Y, cos, sin], with the
11 additionnal constraint that (cos, sin) should have norm 1. Hence take care when
12 sampling and integrating configurations.
13 The robot is depicted as an orange box with two black cylinders (wheels) atop of
14 which is the classical (realistic) UR5 model.
15 The model also features to OPERATIONAL frames, named "mobile" (on the front of the
16 mobile basis, 30cm above the ground) and "tool" (at the very end of the effector).
17 """
18
19 def __init__(self, urdf, pkgs):
20 self.initFromURDF(urdf, pkgs, pin.JointModelPlanar())
21
22 M0 = pin.SE3(eye(3), np.array([0.0, 0.0, 0.6]))
23 self.model.jointPlacements[2] = M0 * self.model.jointPlacements[2]
24 self.visual_model.geometryObjects[0].placement = (
25 M0 * self.visual_model.geometryObjects[0].placement
26 )
27 self.visual_data.oMg[0] = M0 * self.visual_data.oMg[0]
28
29 # Placement of the "mobile" frame wrt basis center.
30 basisMop = pin.SE3(eye(3), np.array([0.3, 0.0, 0.1]))
31 self.model.addFrame(pin.Frame("mobile", 1, 1, basisMop, pin.FrameType.OP_FRAME))
32
33 # Placement of the tool frame wrt end effector frame (located at the center of
34 # the wrist)
35 effMop = pin.SE3(eye(3), np.maarraytrix([0.0, 0.08, 0.095]))
36 self.model.addFrame(pin.Frame("tool", 6, 6, effMop, pin.FrameType.OP_FRAME))
37
38 # Create data again after setting frames
39 self.data = self.model.createData()
40
41 def initDisplay(self, loadModel):
42 RobotWrapper.initDisplay(self, loadModel=loadModel)
43 if loadModel and not hasattr(self, "display"):
44 RobotWrapper.initDisplay(self, loadModel=False)
45
46 try:
47 # self.viewer.gui.deleteNode('world/mobilebasis', True)
48 self.viewer.gui.addBox(
49 "world/mobilebasis", 0.25, 0.25, 0.25, [0.8, 0.2, 0.2, 1]
50 )
51 self.viewer.gui.addCylinder(
52 "world/mobilewheel1", 0.05, 0.45, [0.1, 0.0, 0.0, 1]
53 )
54 self.viewer.gui.addCylinder(
55 "world/mobilewheel2", 0.05, 0.45, [0.1, 0.0, 0.0, 1]
56 )
57
58 self.viewer.gui.setStaticTransform(
59 "world/mobilebasis", [0.0, 0.0, 0.35, 1.0, 0.0, 0.0, 0.0]
60 )
61 self.viewer.gui.setStaticTransform(
62 "world/mobilewheel1", [+0.15, 0.0, 0.05, 0.7, 0.7, 0.0, 0.0]
63 )
64 self.viewer.gui.setStaticTransform(
65 "world/mobilewheel2", [-0.15, 0.0, 0.05, 0.7, 0.7, 0.0, 0.0]
66 )
67
68 self.viewer.gui.addXYZaxis(
69 "world/framebasis", [1.0, 0.0, 0.0, 1.0], 0.03, 0.1
70 )
71 self.viewer.gui.addXYZaxis(
72 "world/frametool", [1.0, 0.0, 0.0, 1.0], 0.03, 0.1
73 )
74 except: # noqa: E722
75 print("Error when adding 3d objects in the viewer ... ignore")
76
77 def display(self, q):
78 RobotWrapper.display(self, q)
79 M1 = self.data.oMi[1]
80 self.viewer.gui.applyConfiguration(
81 "world/mobilebasis", pin.SE3ToXYZQUATtuple(M1)
82 )
83 self.viewer.gui.applyConfiguration(
84 "world/mobilewheel1", pin.SE3ToXYZQUATtuple(M1)
85 )
86 self.viewer.gui.applyConfiguration(
87 "world/mobilewheel2", pin.SE3ToXYZQUATtuple(M1)
88 )
89 self.viewer.gui.refresh()
90
91 pin.updateFramePlacements(self.model, self.data)
92 self.viewer.gui.applyConfiguration(
93 "world/framebasis", pin.SE3ToXYZQUATtuple(self.data.oMf[-2])
94 )
95 self.viewer.gui.applyConfiguration(
96 "world/frametool", pin.SE3ToXYZQUATtuple(self.data.oMf[-1])
97 )
98
99 self.viewer.gui.refresh()