pendulum.py
Go to the documentation of this file.
1 """
2 Create a simulation environment for a N-pendulum.
3 Example of use:
4 
5 env = Pendulum(N)
6 env.reset()
7 
8 for i in range(1000):
9  env.step(zero(env.nu))
10  env.render()
11 
12 """
13 
14 import time
15 
16 import numpy as np
17 import pinocchio as pin
18 from display import Display
19 from numpy.linalg import inv
20 from pinocchio.utils import rand
21 
22 
23 class Visual:
24  """
25  Class representing one 3D mesh of the robot, to be attached to a joint. The class
26  contains:
27  * the name of the 3D objects inside Gepetto viewer.
28  * the ID of the joint in the kinematic tree to which the body is attached.
29  * the placement of the body with respect to the joint frame.
30  This class is only used in the list Robot.visuals (see below).
31  """
32 
33  def __init__(self, name, jointParent, placement):
34  self.name = name # Name in gepetto viewer
35  self.jointParent = jointParent # ID (int) of the joint
36  self.placement = placement # placement of the body wrt joint, i.e. bodyMjoint
37 
38  def place(self, display, oMjoint):
39  oMbody = oMjoint * self.placement
40  display.place(self.name, oMbody, False)
41 
42 
43 class Pendulum:
44  """
45  Define a class Robot with 7DOF (shoulder=3 + elbow=1 + wrist=3).
46  The configuration is nq=7. The velocity is the same.
47  The members of the class are:
48  * viewer: a display encapsulating a gepetto viewer client to create 3D objects and
49  place them.
50  * model: the kinematic tree of the robot.
51  * data: the temporary variables to be used by the kinematic algorithms.
52  * visuals: the list of all the 'visual' 3D objects to render the robot, each element
53  of the list being an object Visual (see above).
54 
55  See tp1.py for an example of use.
56  """
57 
58  def __init__(self, nbJoint=1):
59  """Create a Pinocchio model of a N-pendulum, with N the argument <nbJoint>."""
60  self.viewer = Display()
61  self.visuals = []
62  self.model = pin.Model()
63  self.createPendulum(nbJoint)
64  self.data = self.model.createData()
65 
66  self.q0 = np.zeros(self.model.nq)
67 
68  self.DT = 5e-2 # Step length
69  self.NDT = 2 # Number of Euler steps per integration (internal)
70  self.Kf = 0.10 # Friction coefficient
71  self.vmax = 8.0 # Max velocity (clipped if larger)
72  self.umax = 2.0 # Max torque (clipped if larger)
73  self.withSinCos = False # If true, state is [cos(q),sin(q),qdot], else [q,qdot]
74 
75  def createPendulum(self, nbJoint, rootId=0, prefix="", jointPlacement=None):
76  color = [red, green, blue, transparency] = [1, 1, 0.78, 1.0]
77  colorred = [1.0, 0.0, 0.0, 1.0]
78 
79  jointId = rootId
80  jointPlacement = (
81  jointPlacement if jointPlacement is not None else pin.SE3.Identity()
82  )
83  length = 1.0
84  mass = length
85  inertia = pin.Inertia(
86  mass,
87  np.array([0.0, 0.0, length / 2]),
88  mass / 5 * np.diagflat([1e-2, length**2, 1e-2]),
89  )
90 
91  for i in range(nbJoint):
92  istr = str(i)
93  name = prefix + "joint" + istr
94  jointName, _bodyName = [name + "_joint", name + "_body"]
95  jointId = self.model.addJoint(
96  jointId, pin.JointModelRY(), jointPlacement, jointName
97  )
98  self.model.appendBodyToJoint(jointId, inertia, pin.SE3.Identity())
99  try:
100  self.viewer.viewer.gui.addSphere(
101  "world/" + prefix + "sphere" + istr, 0.15, colorred
102  )
103  except: # noqa: E722
104  pass
105  self.visuals.append(
106  Visual("world/" + prefix + "sphere" + istr, jointId, pin.SE3.Identity())
107  )
108  try:
109  self.viewer.viewer.gui.addCapsule(
110  "world/" + prefix + "arm" + istr, 0.1, 0.8 * length, color
111  )
112  except: # noqa: E722
113  pass
114  self.visuals.append(
115  Visual(
116  "world/" + prefix + "arm" + istr,
117  jointId,
118  pin.SE3(np.eye(3), np.array([0.0, 0.0, length / 2])),
119  )
120  )
121  jointPlacement = pin.SE3(np.eye(3), np.array([0.0, 0.0, length]))
122 
123  self.model.addFrame(
124  pin.Frame("tip", jointId, 0, jointPlacement, pin.FrameType.OP_FRAME)
125  )
126 
127  def display(self, q):
128  pin.forwardKinematics(self.model, self.data, q)
129  for visual in self.visuals:
130  visual.place(self.viewer, self.data.oMi[visual.jointParent])
131  self.viewer.viewer.gui.refresh()
132 
133  @property
134  def nq(self):
135  return self.model.nq
136 
137  @property
138  def nv(self):
139  return self.model.nv
140 
141  @property
142  def nx(self):
143  return self.nq + self.nv
144 
145  @property
146  def nobs(self):
147  return self.nx + self.withSinCos
148 
149  @property
150  def nu(self):
151  return self.nv
152 
153  def reset(self, x0=None):
154  if x0 is None:
155  q0 = np.pi * (rand(self.nq) * 2 - 1)
156  v0 = rand(self.nv) * 2 - 1
157  x0 = np.vstack([q0, v0])
158  assert len(x0) == self.nx
159  self.x = x0.copy()
160  self.r = 0.0
161  return self.obs(self.x)
162 
163  def step(self, u):
164  assert len(u) == self.nu
165  _, self.r = self.dynamics(self.x, u)
166  return self.obs(self.x), self.r
167 
168  def obs(self, x):
169  if self.withSinCos:
170  return np.vstack(
171  [np.vstack([np.cos(qi), np.sin(qi)]) for qi in x[: self.nq]]
172  + [x[self.nq :]],
173  )
174  else:
175  return x.copy()
176 
177  def tip(self, q):
178  """Return the altitude of pendulum tip"""
179  pin.framesKinematics(self.model, self.data, q)
180  return self.data.oMf[1].translation[2, 0]
181 
182  def dynamics(self, x, u, display=False):
183  """
184  Dynamic function: x,u -> xnext=f(x,y).
185  Put the result in x (the initial value is destroyed).
186  Also compute the cost of making this step.
187  Return x for convenience along with the cost.
188  """
189 
190  def modulePi(th):
191  return (th + np.pi) % (2 * np.pi) - np.pi
192 
193  def sumsq(x):
194  return np.sum(np.square(x))
195 
196  cost = 0.0
197  q = modulePi(x[: self.nq])
198  v = x[self.nq :]
199  u = np.clip(np.reshape(np.array(u), [self.nu, 1]), -self.umax, self.umax)
200 
201  DT = self.DT / self.NDT
202  for i in range(self.NDT):
203  pin.computeAllTerms(self.model, self.data, q, v)
204  M = self.data.M
205  b = self.data.nle
206  # tau = u-self.Kf*v
207  a = inv(M) * (u - self.Kf * v - b)
208 
209  v += a * DT
210  q += v * DT
211  cost += (sumsq(q) + 1e-1 * sumsq(v) + 1e-3 * sumsq(u)) * DT
212 
213  if display:
214  self.display(q)
215  time.sleep(1e-4)
216 
217  x[: self.nq] = modulePi(q)
218  x[self.nq :] = np.clip(v, -self.vmax, self.vmax)
219 
220  return x, -cost
221 
222  def render(self):
223  q = self.x[: self.nq]
224  self.display(q)
225  time.sleep(self.DT / 10)
pendulum.Pendulum.q0
q0
Definition: pendulum.py:66
pendulum.Pendulum.__init__
def __init__(self, nbJoint=1)
Definition: pendulum.py:58
pendulum.Pendulum.dynamics
def dynamics(self, x, u, display=False)
Definition: pendulum.py:182
display.Display
Definition: display.py:8
pendulum.Pendulum.reset
def reset(self, x0=None)
Definition: pendulum.py:153
pendulum.Visual.name
name
Definition: pendulum.py:34
pendulum.Visual.__init__
def __init__(self, name, jointParent, placement)
Definition: pendulum.py:33
pendulum.Visual.placement
placement
Definition: pendulum.py:36
pendulum.Pendulum.createPendulum
def createPendulum(self, nbJoint, rootId=0, prefix="", jointPlacement=None)
Definition: pendulum.py:75
pendulum.Pendulum.nobs
def nobs(self)
Definition: pendulum.py:146
pendulum.Visual.jointParent
jointParent
Definition: pendulum.py:35
pendulum.Pendulum.render
def render(self)
Definition: pendulum.py:222
pendulum.Pendulum.nq
def nq(self)
Definition: pendulum.py:134
pendulum.Pendulum.Kf
Kf
Definition: pendulum.py:70
pendulum.Pendulum.viewer
viewer
Definition: pendulum.py:60
pendulum.Pendulum.NDT
NDT
Definition: pendulum.py:69
pendulum.Pendulum.x
x
Definition: pendulum.py:159
pendulum.Pendulum
Definition: pendulum.py:43
pendulum.Visual
Definition: pendulum.py:23
pinocchio.utils
Definition: bindings/python/pinocchio/utils.py:1
pendulum.Pendulum.visuals
visuals
Definition: pendulum.py:61
pinocchio::createData
ConstraintDataTpl< Scalar, Options, ConstraintCollectionTpl > createData(const ConstraintModelTpl< Scalar, Options, ConstraintCollectionTpl > &cmodel)
Definition: constraint-model-visitor.hpp:248
pendulum.Pendulum.umax
umax
Definition: pendulum.py:72
pendulum.Pendulum.nx
def nx(self)
Definition: pendulum.py:142
pendulum.Pendulum.nu
def nu(self)
Definition: pendulum.py:150
pendulum.Visual.place
def place(self, display, oMjoint)
Definition: pendulum.py:38
pendulum.Pendulum.DT
DT
Definition: pendulum.py:68
pendulum.Pendulum.model
model
Definition: pendulum.py:62
pendulum.Pendulum.tip
def tip(self, q)
Definition: pendulum.py:177
pendulum.Pendulum.display
def display(self, q)
Definition: pendulum.py:127
pendulum.Pendulum.obs
def obs(self, x)
Definition: pendulum.py:168
pendulum.Pendulum.nv
def nv(self)
Definition: pendulum.py:138
boost::fusion::append
result_of::push_front< V const, T >::type append(T const &t, V const &v)
Append the element T at the front of boost fusion vector V.
Definition: fusion.hpp:32
pendulum.Pendulum.withSinCos
withSinCos
Definition: pendulum.py:73
pendulum.Pendulum.data
data
Definition: pendulum.py:64
pendulum.Pendulum.r
r
Definition: pendulum.py:160
pinocchio.utils.rand
def rand(n)
Definition: bindings/python/pinocchio/utils.py:41
pendulum.Pendulum.step
def step(self, u)
Definition: pendulum.py:163
pendulum.Pendulum.vmax
vmax
Definition: pendulum.py:71


pinocchio
Author(s):
autogenerated on Sat Sep 28 2024 02:41:21