2 import pinocchio 
as pin
 
    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). 
   22         M0 = 
pin.SE3(
eye(3), np.array([0.0, 0.0, 0.6]))
 
   23         self.
model.jointPlacements[2] = M0 * self.
model.jointPlacements[2]
 
   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))
 
   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))
 
   42         RobotWrapper.initDisplay(self, loadModel=loadModel)
 
   43         if loadModel 
and not hasattr(self, 
"display"):
 
   44             RobotWrapper.initDisplay(self, loadModel=
False)
 
   49                 "world/mobilebasis", 0.25, 0.25, 0.25, [0.8, 0.2, 0.2, 1]
 
   51             self.
viewer.gui.addCylinder(
 
   52                 "world/mobilewheel1", 0.05, 0.45, [0.1, 0.0, 0.0, 1]
 
   54             self.
viewer.gui.addCylinder(
 
   55                 "world/mobilewheel2", 0.05, 0.45, [0.1, 0.0, 0.0, 1]
 
   58             self.
viewer.gui.setStaticTransform(
 
   59                 "world/mobilebasis", [0.0, 0.0, 0.35, 1.0, 0.0, 0.0, 0.0]
 
   61             self.
viewer.gui.setStaticTransform(
 
   62                 "world/mobilewheel1", [+0.15, 0.0, 0.05, 0.7, 0.7, 0.0, 0.0]
 
   64             self.
viewer.gui.setStaticTransform(
 
   65                 "world/mobilewheel2", [-0.15, 0.0, 0.05, 0.7, 0.7, 0.0, 0.0]
 
   68             self.
viewer.gui.addXYZaxis(
 
   69                 "world/framebasis", [1.0, 0.0, 0.0, 1.0], 0.03, 0.1
 
   71             self.
viewer.gui.addXYZaxis(
 
   72                 "world/frametool", [1.0, 0.0, 0.0, 1.0], 0.03, 0.1
 
   75             print(
"Error when adding 3d objects in the viewer ... ignore")
 
   78         RobotWrapper.display(self, q)
 
   80         self.
viewer.gui.applyConfiguration(
 
   81             "world/mobilebasis", pin.SE3ToXYZQUATtuple(M1)
 
   83         self.
viewer.gui.applyConfiguration(
 
   84             "world/mobilewheel1", pin.SE3ToXYZQUATtuple(M1)
 
   86         self.
viewer.gui.applyConfiguration(
 
   87             "world/mobilewheel2", pin.SE3ToXYZQUATtuple(M1)
 
   92         self.
viewer.gui.applyConfiguration(
 
   93             "world/framebasis", pin.SE3ToXYZQUATtuple(self.
data.oMf[-2])
 
   95         self.
viewer.gui.applyConfiguration(
 
   96             "world/frametool", pin.SE3ToXYZQUATtuple(self.
data.oMf[-1])