add yapf style and apply yapf to format all Python files

This recreates pull request #2192
This commit is contained in:
Erwin Coumans
2019-04-27 07:31:15 -07:00
parent c591735042
commit ef9570c315
347 changed files with 70304 additions and 22752 deletions

View File

@@ -7,31 +7,38 @@ import time
p = bc.BulletClient(connection_mode=pybullet.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
p.loadURDF("plane_transparent.urdf", useMaximalCoordinates=True)
p#.setPhysicsEngineParameter(numSolverIterations=10, fixedTimeStep=0.01)
p #.setPhysicsEngineParameter(numSolverIterations=10, fixedTimeStep=0.01)
p.configureDebugVisualizer(p.COV_ENABLE_PLANAR_REFLECTION, 1)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 0)
p.configureDebugVisualizer(p.COV_ENABLE_PLANAR_REFLECTION,1)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
y2z = p.getQuaternionFromEuler([0, 0, 1.57])
meshScale = [1, 1, 1]
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,
fileName="domino/domino.obj",
rgbaColor=[1, 1, 1, 1],
specularColor=[0.4, .4, 0],
visualFrameOrientation=y2z,
meshScale=meshScale)
y2z = p.getQuaternionFromEuler([0,0,1.57])
meshScale = [1,1,1]
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,fileName="domino/domino.obj", rgbaColor=[1,1,1,1], specularColor=[0.4,.4,0], visualFrameOrientation=y2z, meshScale=meshScale)
boxDimensions = [0.5 * 0.00635, 0.5 * 0.0254, 0.5 * 0.0508]
collisionShapeId = p.createCollisionShape(p.GEOM_BOX, halfExtents=boxDimensions)
boxDimensions = [0.5*0.00635, 0.5*0.0254, 0.5*0.0508]
collisionShapeId = p.createCollisionShape(p.GEOM_BOX,halfExtents=boxDimensions)
for j in range (12):
print("j=",j)
for i in range (35):
for j in range(12):
print("j=", j)
for i in range(35):
#p.loadURDF("domino/domino.urdf",[i*0.04,0, 0.06])
p.createMultiBody(baseMass=0.025,baseCollisionShapeIndex = collisionShapeId,baseVisualShapeIndex = visualShapeId, basePosition = [i*0.04,j*0.05, 0.06], useMaximalCoordinates=True)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,1)
p.createMultiBody(baseMass=0.025,
baseCollisionShapeIndex=collisionShapeId,
baseVisualShapeIndex=visualShapeId,
basePosition=[i * 0.04, j * 0.05, 0.06],
useMaximalCoordinates=True)
p.setGravity(0,0,-9.8)
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
p.setGravity(0, 0, -9.8)
p.setRealTimeSimulation(1)
while (1):
p.setGravity(0,0,-9.8)
p.setGravity(0, 0, -9.8)
#p.stepSimulation(1./100.)
time.sleep(1./240.)
time.sleep(1. / 240.)

View File

@@ -2,179 +2,582 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import gym
import numpy as np
import pybullet_envs
import time
def relu(x):
return np.maximum(x, 0)
return np.maximum(x, 0)
class SmallReactivePolicy:
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64.0)
assert weights_dense2_w.shape == (64.0, 32.0)
assert weights_final_w.shape == (32.0, action_space.shape[0])
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64.0)
assert weights_dense2_w.shape == (64.0, 32.0)
assert weights_final_w.shape == (32.0, action_space.shape[0])
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def main():
env = gym.make("InvertedDoublePendulumBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
env = gym.make("InvertedDoublePendulumBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
time.sleep(1. / 60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open == False:
return
if not done: continue
if restart_delay == 0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60 * 2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay > 0: continue
break
while 1:
time.sleep(1./60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open==False:
return
if not done: continue
if restart_delay==0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60*2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay > 0: continue
break
weights_dense1_w = np.array([
[ -0.5857, +0.1810, +0.2839, +0.1278, -0.4302, -0.3152, +0.5916, -0.0635, +0.6259, +0.2873, -0.0572, -0.3538, -0.8121, +0.2707, +0.1656, -0.2103, -0.1614, -0.2789, -0.5856, -0.4733, +0.1838, +0.1063, +0.7629, +0.0873, +0.1480, +0.1768, +0.6522, +0.1158, -0.0816, +0.6542, -0.8870, +0.1775, +0.1532, +0.2268, -0.0313, -0.0470, +0.5328, -0.0570, +0.4820, -0.3772, -0.7581, +0.2835, -0.3566, +0.9371, -0.0441, -0.1797, -0.2859, -0.0238, +0.0261, -0.0296, -0.1406, +0.2869, +0.1279, +0.6653, +0.5643, -0.3136, +0.7751, +0.2341, +0.1903, +0.8283, -0.0697, +0.1276, -0.0250, -0.0053],
[ +0.3741, +0.4844, -0.0638, -0.3205, +0.3137, +0.9636, +0.5329, +0.6882, +0.2983, -0.6675, -0.6372, +0.2065, -0.2645, -0.4789, +0.2326, -0.0691, -0.5905, -0.3354, +0.3428, +0.4253, +0.9111, -0.4751, -0.2124, +0.3920, +0.2897, -1.1101, +0.1894, -0.4025, -0.1125, -0.0627, +0.2347, -0.8787, +0.1019, +0.9128, +0.2544, -0.3933, +0.6485, -0.1936, -0.2402, +0.5012, -0.0918, +0.3160, -0.7860, +0.3439, -0.4268, -0.1788, -0.3930, +0.5128, +0.2338, +0.2571, +0.1343, +0.9850, -0.7074, +0.3532, +0.3048, -0.4542, +0.5539, -0.4409, -0.2003, -0.4837, -0.3554, -0.4447, -0.0817, -0.8497],
[ +0.0825, +0.5847, +0.4837, +0.5144, +0.4770, +0.0199, +0.4275, -0.4530, +0.8499, -0.2840, +0.3817, -0.5098, -0.2155, -0.1475, +0.1145, -0.1871, -0.0526, +0.3583, -0.3537, -0.7111, -0.6116, +0.3406, -0.6360, +0.7786, +0.6628, -0.0493, +0.3505, -0.0376, -0.6556, +1.0748, -0.5329, +0.6477, -0.7117, +0.3723, +0.6006, +0.0171, +0.0012, +0.4910, -0.5651, -0.6868, +0.2403, +0.0254, -0.4416, +0.7534, -0.0138, -1.1298, +0.5447, +0.0974, +0.1988, -0.2161, -0.3126, -0.5731, -0.1278, +0.2995, -0.1200, -0.7917, +0.5326, +0.4562, -0.0144, +0.5717, -0.4065, +0.1494, +0.7100, +0.2461],
[ -0.2861, +0.4314, -0.2982, -0.1401, -0.1033, +0.5287, -0.6620, -0.3975, +0.0038, +0.1991, -0.7079, -0.9000, +0.1659, +0.3623, -0.0752, -0.1907, -0.2335, -0.5143, +0.2324, -0.0487, +0.1583, -0.5989, +0.5957, +0.2150, -0.0335, +0.2154, +0.3279, -0.7976, +0.5320, -0.4438, +0.2170, -0.3841, -0.0039, -0.0847, -0.0028, -0.4278, -0.2393, -0.9239, +0.2880, -0.1437, -0.0941, -0.0796, -0.3906, -0.3224, +0.1038, -0.1929, -0.2713, -0.4157, -0.2178, +0.5729, -0.2065, +0.0059, +0.3879, +0.0590, +0.1759, +0.0677, -0.0170, -0.2252, +0.3301, -0.0599, +0.3791, -0.1455, +0.2200, -0.0499],
[ -0.4403, +0.7182, +0.7941, +0.1469, +1.5777, +0.3426, +0.0923, +0.2160, +1.1492, -0.5206, -0.2659, -0.1504, +0.2739, -1.3939, +0.8992, -1.1433, -0.3828, -0.2497, -0.2172, +0.2318, -0.3605, +0.6413, -1.9095, +1.4785, -0.1274, -0.7208, -0.0802, -0.8779, -1.6260, +0.9151, +0.8289, -0.0902, -0.3551, +0.6198, +1.7488, +0.0739, -1.2022, -0.3536, -1.5187, +0.1839, +1.4258, +0.4217, +0.1503, -0.0460, +0.2327, -0.4139, -0.3668, +0.2997, +0.6856, +0.6917, -0.3856, -0.3620, +0.1578, -0.8349, -1.0796, -0.0319, -1.1966, -0.8122, +0.5053, -0.5033, -0.9207, -0.1193, -0.7625, +0.1379],
[ -0.0321, -0.3206, -0.4516, +0.3420, +1.0964, +0.0311, +0.4654, -0.2367, +0.3347, -0.2798, -0.8169, -0.1555, +0.9397, -0.5597, +0.7113, -0.3642, -0.2840, -0.1323, -0.1000, +0.2283, +0.3612, -0.4784, +0.0504, +0.5310, -0.0887, +0.2926, +0.5069, -0.5645, -0.0976, -0.2594, +0.4425, +0.9223, -0.5637, -0.2336, -0.1316, -0.6564, -0.2780, -0.2409, -0.1637, +0.4506, +0.7018, -0.1299, +0.7172, +0.1207, +0.4375, +0.3836, +0.2781, -0.7792, -0.5317, +0.4510, +0.2423, -0.0588, -0.4254, -0.6381, -0.8205, +0.6417, +0.1904, -0.2618, +0.5900, -0.3899, -0.7851, -0.4769, -0.3688, -0.3510],
[ -0.8366, -0.3157, -0.1130, +0.2005, +0.3713, -0.4351, -0.1278, -0.5689, +0.3229, -0.5981, -0.4917, -0.4160, -0.5504, +0.2225, -0.1581, -0.6457, +0.1001, -1.0635, +0.2368, +0.2494, -0.4054, -0.1699, -0.1316, +0.2614, +0.3016, +0.4222, -0.1548, -0.0766, -0.5226, -0.3576, -0.2433, -0.5495, +0.0056, +0.0193, +0.2353, +0.3986, +0.3580, -0.7886, +0.3928, +0.1831, +0.4319, +0.2276, -0.3062, +0.0413, -0.4288, +0.1365, +0.3176, +0.3564, +0.5668, -0.4401, -0.9576, -0.1435, +0.0304, -0.5575, +0.0412, -0.1096, +0.2207, +0.1227, -0.0051, +0.5808, -0.1331, +0.1368, +0.4170, -0.8095],
[ -0.6368, -1.3221, -0.4492, -1.5414, +0.4004, -2.8780, -0.1748, -0.8166, +1.7066, +1.0714, -0.4755, +0.3020, +0.0422, +0.3466, +0.4472, -0.6209, -3.3768, -0.0806, +1.3624, -2.4155, +1.0886, +0.3412, +0.0891, +1.6821, -0.5361, +0.3952, +1.5120, +0.3910, +1.9500, -0.9065, -1.3452, +0.0904, -0.0389, +0.2817, -1.8375, +0.8131, -1.5287, +0.3115, +1.4069, -0.3424, +1.6101, +2.6775, +0.5516, +1.6500, -0.4138, -0.0170, +1.0008, -0.7865, +0.0551, +2.2068, -0.0108, +0.3207, -1.1884, +0.3792, -0.6435, +0.2858, -0.6881, +0.1554, -1.6926, -0.0975, -1.4120, -0.0827, -1.5186, +0.2526],
[ -0.2900, -0.2805, +0.9182, -0.8893, +0.7345, -0.9015, -0.2696, +0.2344, +0.3889, +0.6790, +0.3657, -0.1995, -0.6738, -0.4166, +0.1690, -0.3798, -0.9872, -0.2558, -0.4205, -0.6190, -0.0092, -0.2261, -0.2738, +0.2977, -0.7348, +0.4872, +0.4776, -0.1364, +0.5836, -0.2688, -0.4261, -0.3612, -0.3533, +0.4665, +0.0155, +1.0116, -0.7139, -0.3707, -0.4429, -0.0383, +0.6716, +0.5972, +0.3506, +0.3294, -1.3734, -0.5905, -0.1168, -0.2609, +0.3436, +0.8277, +0.4965, +0.3005, -0.2929, +0.1501, -0.2655, +0.3860, -0.3946, +0.8764, +0.7927, +0.0541, -1.0912, -0.2006, -0.6928, +0.4653]
# yapf: disable
weights_dense1_w = np.array(
[[
-0.5857, +0.1810, +0.2839, +0.1278, -0.4302, -0.3152, +0.5916, -0.0635,
+0.6259, +0.2873, -0.0572, -0.3538, -0.8121, +0.2707, +0.1656, -0.2103,
-0.1614, -0.2789, -0.5856, -0.4733, +0.1838, +0.1063, +0.7629, +0.0873,
+0.1480, +0.1768, +0.6522, +0.1158, -0.0816, +0.6542, -0.8870, +0.1775,
+0.1532, +0.2268, -0.0313, -0.0470, +0.5328, -0.0570, +0.4820, -0.3772,
-0.7581, +0.2835, -0.3566, +0.9371, -0.0441, -0.1797, -0.2859, -0.0238,
+0.0261, -0.0296, -0.1406, +0.2869, +0.1279, +0.6653, +0.5643, -0.3136,
+0.7751, +0.2341, +0.1903, +0.8283, -0.0697, +0.1276, -0.0250, -0.0053
],
[
+0.3741, +0.4844, -0.0638, -0.3205, +0.3137, +0.9636, +0.5329,
+0.6882, +0.2983, -0.6675, -0.6372, +0.2065, -0.2645, -0.4789,
+0.2326, -0.0691, -0.5905, -0.3354, +0.3428, +0.4253, +0.9111,
-0.4751, -0.2124, +0.3920, +0.2897, -1.1101, +0.1894, -0.4025,
-0.1125, -0.0627, +0.2347, -0.8787, +0.1019, +0.9128, +0.2544,
-0.3933, +0.6485, -0.1936, -0.2402, +0.5012, -0.0918, +0.3160,
-0.7860, +0.3439, -0.4268, -0.1788, -0.3930, +0.5128, +0.2338,
+0.2571, +0.1343, +0.9850, -0.7074, +0.3532, +0.3048, -0.4542,
+0.5539, -0.4409, -0.2003, -0.4837, -0.3554, -0.4447, -0.0817, -0.8497
],
[
+0.0825, +0.5847, +0.4837, +0.5144, +0.4770, +0.0199, +0.4275,
-0.4530, +0.8499, -0.2840, +0.3817, -0.5098, -0.2155, -0.1475,
+0.1145, -0.1871, -0.0526, +0.3583, -0.3537, -0.7111, -0.6116,
+0.3406, -0.6360, +0.7786, +0.6628, -0.0493, +0.3505, -0.0376,
-0.6556, +1.0748, -0.5329, +0.6477, -0.7117, +0.3723, +0.6006,
+0.0171, +0.0012, +0.4910, -0.5651, -0.6868, +0.2403, +0.0254,
-0.4416, +0.7534, -0.0138, -1.1298, +0.5447, +0.0974, +0.1988,
-0.2161, -0.3126, -0.5731, -0.1278, +0.2995, -0.1200, -0.7917,
+0.5326, +0.4562, -0.0144, +0.5717, -0.4065, +0.1494, +0.7100, +0.2461
],
[
-0.2861, +0.4314, -0.2982, -0.1401, -0.1033, +0.5287, -0.6620,
-0.3975, +0.0038, +0.1991, -0.7079, -0.9000, +0.1659, +0.3623,
-0.0752, -0.1907, -0.2335, -0.5143, +0.2324, -0.0487, +0.1583,
-0.5989, +0.5957, +0.2150, -0.0335, +0.2154, +0.3279, -0.7976,
+0.5320, -0.4438, +0.2170, -0.3841, -0.0039, -0.0847, -0.0028,
-0.4278, -0.2393, -0.9239, +0.2880, -0.1437, -0.0941, -0.0796,
-0.3906, -0.3224, +0.1038, -0.1929, -0.2713, -0.4157, -0.2178,
+0.5729, -0.2065, +0.0059, +0.3879, +0.0590, +0.1759, +0.0677,
-0.0170, -0.2252, +0.3301, -0.0599, +0.3791, -0.1455, +0.2200, -0.0499
],
[
-0.4403, +0.7182, +0.7941, +0.1469, +1.5777, +0.3426, +0.0923,
+0.2160, +1.1492, -0.5206, -0.2659, -0.1504, +0.2739, -1.3939,
+0.8992, -1.1433, -0.3828, -0.2497, -0.2172, +0.2318, -0.3605,
+0.6413, -1.9095, +1.4785, -0.1274, -0.7208, -0.0802, -0.8779,
-1.6260, +0.9151, +0.8289, -0.0902, -0.3551, +0.6198, +1.7488,
+0.0739, -1.2022, -0.3536, -1.5187, +0.1839, +1.4258, +0.4217,
+0.1503, -0.0460, +0.2327, -0.4139, -0.3668, +0.2997, +0.6856,
+0.6917, -0.3856, -0.3620, +0.1578, -0.8349, -1.0796, -0.0319,
-1.1966, -0.8122, +0.5053, -0.5033, -0.9207, -0.1193, -0.7625, +0.1379
],
[
-0.0321, -0.3206, -0.4516, +0.3420, +1.0964, +0.0311, +0.4654,
-0.2367, +0.3347, -0.2798, -0.8169, -0.1555, +0.9397, -0.5597,
+0.7113, -0.3642, -0.2840, -0.1323, -0.1000, +0.2283, +0.3612,
-0.4784, +0.0504, +0.5310, -0.0887, +0.2926, +0.5069, -0.5645,
-0.0976, -0.2594, +0.4425, +0.9223, -0.5637, -0.2336, -0.1316,
-0.6564, -0.2780, -0.2409, -0.1637, +0.4506, +0.7018, -0.1299,
+0.7172, +0.1207, +0.4375, +0.3836, +0.2781, -0.7792, -0.5317,
+0.4510, +0.2423, -0.0588, -0.4254, -0.6381, -0.8205, +0.6417,
+0.1904, -0.2618, +0.5900, -0.3899, -0.7851, -0.4769, -0.3688, -0.3510
],
[
-0.8366, -0.3157, -0.1130, +0.2005, +0.3713, -0.4351, -0.1278,
-0.5689, +0.3229, -0.5981, -0.4917, -0.4160, -0.5504, +0.2225,
-0.1581, -0.6457, +0.1001, -1.0635, +0.2368, +0.2494, -0.4054,
-0.1699, -0.1316, +0.2614, +0.3016, +0.4222, -0.1548, -0.0766,
-0.5226, -0.3576, -0.2433, -0.5495, +0.0056, +0.0193, +0.2353,
+0.3986, +0.3580, -0.7886, +0.3928, +0.1831, +0.4319, +0.2276,
-0.3062, +0.0413, -0.4288, +0.1365, +0.3176, +0.3564, +0.5668,
-0.4401, -0.9576, -0.1435, +0.0304, -0.5575, +0.0412, -0.1096,
+0.2207, +0.1227, -0.0051, +0.5808, -0.1331, +0.1368, +0.4170, -0.8095
],
[
-0.6368, -1.3221, -0.4492, -1.5414, +0.4004, -2.8780, -0.1748,
-0.8166, +1.7066, +1.0714, -0.4755, +0.3020, +0.0422, +0.3466,
+0.4472, -0.6209, -3.3768, -0.0806, +1.3624, -2.4155, +1.0886,
+0.3412, +0.0891, +1.6821, -0.5361, +0.3952, +1.5120, +0.3910,
+1.9500, -0.9065, -1.3452, +0.0904, -0.0389, +0.2817, -1.8375,
+0.8131, -1.5287, +0.3115, +1.4069, -0.3424, +1.6101, +2.6775,
+0.5516, +1.6500, -0.4138, -0.0170, +1.0008, -0.7865, +0.0551,
+2.2068, -0.0108, +0.3207, -1.1884, +0.3792, -0.6435, +0.2858,
-0.6881, +0.1554, -1.6926, -0.0975, -1.4120, -0.0827, -1.5186, +0.2526
],
[
-0.2900, -0.2805, +0.9182, -0.8893, +0.7345, -0.9015, -0.2696,
+0.2344, +0.3889, +0.6790, +0.3657, -0.1995, -0.6738, -0.4166,
+0.1690, -0.3798, -0.9872, -0.2558, -0.4205, -0.6190, -0.0092,
-0.2261, -0.2738, +0.2977, -0.7348, +0.4872, +0.4776, -0.1364,
+0.5836, -0.2688, -0.4261, -0.3612, -0.3533, +0.4665, +0.0155,
+1.0116, -0.7139, -0.3707, -0.4429, -0.0383, +0.6716, +0.5972,
+0.3506, +0.3294, -1.3734, -0.5905, -0.1168, -0.2609, +0.3436,
+0.8277, +0.4965, +0.3005, -0.2929, +0.1501, -0.2655, +0.3860,
-0.3946, +0.8764, +0.7927, +0.0541, -1.0912, -0.2006, -0.6928, +0.4653
]])
weights_dense1_b = np.array([
-0.1146, +0.2897, +0.0137, +0.0822, +0.0367, +0.0951, -0.0657, +0.0653,
-0.0729, -0.0501, -0.6380, -0.4403, +0.0660, +0.0693, -0.4353, -0.2766,
-0.1258, -0.6947, -0.1616, -0.0453, +0.1498, -0.2340, -0.0764, +0.2020,
+0.4812, +0.0908, -0.1883, -0.0753, -0.0373, -0.4172, -0.1071, +0.0861,
-0.1550, -0.0648, -0.1473, +0.1507, -0.0121, -0.5468, -0.1529, -0.3341,
+0.0239, -0.0463, -0.0044, -0.0541, +0.0384, +0.3028, +0.3378, +0.0965,
+0.0740, +0.1948, -0.1655, +0.1558, +0.1367, -0.1514, +0.0540, -0.0015,
-0.1256, +0.3402, -0.0273, -0.2239, -0.0073, -0.6246, +0.0755, -0.2002
])
weights_dense1_b = np.array([ -0.1146, +0.2897, +0.0137, +0.0822, +0.0367, +0.0951, -0.0657, +0.0653, -0.0729, -0.0501, -0.6380, -0.4403, +0.0660, +0.0693, -0.4353, -0.2766, -0.1258, -0.6947, -0.1616, -0.0453, +0.1498, -0.2340, -0.0764, +0.2020, +0.4812, +0.0908, -0.1883, -0.0753, -0.0373, -0.4172, -0.1071, +0.0861, -0.1550, -0.0648, -0.1473, +0.1507, -0.0121, -0.5468, -0.1529, -0.3341, +0.0239, -0.0463, -0.0044, -0.0541, +0.0384, +0.3028, +0.3378, +0.0965, +0.0740, +0.1948, -0.1655, +0.1558, +0.1367, -0.1514, +0.0540, -0.0015, -0.1256, +0.3402, -0.0273, -0.2239, -0.0073, -0.6246, +0.0755, -0.2002])
weights_dense2_w = np.array([
[ +0.5019, +0.3831, +0.6726, +0.3767, +0.2021, -0.1615, +0.3882, -0.0487, -0.2713, +0.1173, -0.2218, +0.0598, +0.0819, -0.1157, +0.5879, -0.3587, +0.1376, -0.2595, +0.0257, -0.1182, +0.0723, +0.5612, -0.4087, -0.4651, +0.0631, +0.1786, +0.1206, +0.4791, +0.5922, -0.4444, +0.3446, -0.0464],
[ -0.0485, +0.0739, -0.6915, +0.5446, -0.2461, +0.1557, +0.8993, -0.7537, +0.1149, +0.0575, -0.1714, -0.3796, +0.3508, -0.2315, +0.4389, -1.4456, -1.3490, -0.1598, -1.0354, -0.2320, -0.3765, +0.1070, -0.7107, +0.4150, +0.2711, -0.2915, -0.7957, +0.7753, -0.0425, -0.1352, +0.3018, -0.0069],
[ -0.4047, +1.0040, -0.4570, +0.3017, +0.1477, -0.0163, +0.4087, -0.6368, -0.0764, -0.0695, +0.0208, -0.2411, +0.1936, +0.0047, +0.0107, -0.8538, -0.5887, -0.0524, -1.4902, +0.2858, +0.4396, -0.3433, -0.6778, -0.7137, +0.4587, +0.3359, -0.7350, -1.0813, -0.1296, +0.1748, -0.3830, -0.2103],
[ +0.0503, -0.3342, -0.6057, +0.2217, +0.3164, -0.1881, -0.5867, -0.2471, -0.2527, -0.0444, +0.1874, -0.0960, +0.2039, -0.0488, +0.1741, -0.1623, -0.0758, -0.2354, -0.5986, -0.2129, -0.2470, +0.3317, -0.4795, -0.6380, +0.1494, +0.0115, -0.2746, -0.8428, -0.0118, -0.0604, +0.0886, -0.0408],
[ -0.1932, -1.3896, +0.3919, -0.4700, -0.9806, -0.1554, +0.3132, +0.4138, -0.4943, -0.1408, -0.0976, +0.1551, -0.0180, +0.0864, -0.0053, -0.2430, +0.4948, +0.2709, -0.3488, +0.2085, -0.2124, -0.3025, -0.0692, +0.3884, +0.5764, +0.5783, +0.4351, -0.2633, -0.9288, +0.2218, -0.9049, -0.2970],
[ -0.2841, -0.3393, -0.1062, -0.1415, +0.0257, +0.0816, -0.4833, -0.2775, +0.0308, -0.0344, +0.5451, +0.1588, -0.7454, -0.1444, +0.4189, -0.2001, -2.0586, -0.0616, -1.4463, +0.0076, -0.7703, +0.3279, -0.7009, +0.6046, -0.1615, -0.5188, -0.7503, +0.0615, +0.1815, -0.2512, +0.0321, -0.1834],
[ +0.3751, +0.2932, -0.6815, +0.3771, +0.0603, -0.2035, -0.2644, -1.0120, -0.0661, -0.0846, +0.1209, +0.0367, +0.0493, -0.2603, -0.1608, -0.7580, -0.8609, +0.1415, -0.7626, -1.0209, -0.7498, -0.0732, -0.8138, -0.2292, +0.5803, -0.2718, -1.4684, -0.1584, +0.2096, +0.1336, +0.3632, +0.0216],
[ -0.0625, -0.1233, -0.2715, +0.5541, +0.3121, +0.0265, +0.4501, -1.1024, -0.1160, -0.1005, -0.0844, -0.0516, +0.0916, +0.0901, +0.3710, -0.5753, -0.3728, -0.1103, -0.6285, -0.2179, +0.1570, +0.1168, -0.9312, +0.0135, -0.0376, -0.1693, -0.5358, -0.0028, +0.2105, -0.7373, +0.2776, +0.2326],
[ -0.5378, -0.3201, +0.3606, +0.1331, +0.0120, -0.2421, -0.0230, +0.4622, -0.3140, +0.0803, -0.6897, -0.4704, +0.2685, +0.0803, -0.7654, -0.1433, +0.0242, +0.0917, +0.2458, +0.0457, -0.2503, -0.1197, +0.1454, -0.1523, -0.4095, +0.1856, +0.0678, -1.0011, +0.0117, +0.1789, -0.4063, -0.0888],
[ -0.6352, -0.6358, -0.2066, +0.0758, -0.2973, -0.3014, -0.0556, -0.0912, -0.2729, -0.1492, -0.1928, -1.8768, +0.2183, +0.0801, +0.1288, -1.2493, +0.1115, +0.2797, -0.1458, +0.0062, -0.0402, -0.8945, -0.2231, -0.1154, +0.3635, -0.3021, +0.1402, -0.7347, +0.2772, +0.3182, -0.9708, +0.0376],
[ +0.6899, +0.3471, -0.5863, +0.1497, +0.1616, -0.0497, +0.3579, -0.6421, +0.4529, -0.1588, +0.9250, +0.2357, -0.0712, -0.1793, -0.0231, -0.4814, -0.7654, +0.0591, -0.6866, -0.1705, +0.2255, -0.0007, -0.3890, +0.6114, +0.0443, -0.6929, -0.7734, +0.2314, -0.0231, -0.6386, +0.1237, +0.0472],
[ -0.2496, -0.1687, +0.1234, +0.4152, +0.4207, -0.1398, +0.1287, +0.5903, +0.0530, -0.1181, +0.0803, -0.0641, -0.1198, -0.4702, -0.3669, +0.2340, -0.3778, +0.4341, +0.2411, -0.2171, -0.3051, -0.2397, +0.1756, +0.4040, +0.0682, +0.1575, +0.4137, +0.0887, -0.1998, +0.2221, -0.2474, -0.0559],
[ -2.2466, -1.2725, +0.5947, -0.3192, -0.2665, -0.0129, -0.7615, +0.1148, +0.2745, -0.0556, -1.3313, -0.7143, -0.5119, -0.0572, -0.1892, -0.3294, -0.0187, -0.7696, +1.0413, +0.4226, +0.1378, -1.3668, +0.9806, -0.1810, -0.2307, -0.4924, +0.7163, -1.2529, -0.3216, +0.1683, -0.6657, -0.1121],
[ +0.1227, +0.2433, -0.1292, -0.7152, -0.1342, -0.1116, -0.2695, +0.0243, -0.0770, -0.1713, +0.2837, +0.2076, -0.7322, -0.1657, -0.3407, -0.4378, +0.0679, -0.3777, +0.3025, -0.6780, -0.2326, +0.1463, +0.0535, -0.6373, -0.2027, -0.5404, -0.1598, +0.1511, -0.1776, +0.0854, +0.1753, -0.0342],
[ -0.1772, -0.2654, -0.4170, -0.3301, +0.2956, -0.4234, +0.0835, +0.2869, -0.2804, -0.2073, -0.3291, -0.5897, -0.4116, -0.0447, +0.1601, +0.1602, +0.1691, -0.2014, -0.0502, +0.1167, -1.0103, -0.4297, -0.2039, -0.0859, +0.2756, -0.1768, -0.2726, -0.0256, -0.0834, +0.0852, +0.0930, -0.0606],
[ -0.5390, -0.5441, +0.3202, -0.1018, +0.0059, +0.1799, -0.1917, +0.3674, +0.2576, -0.0707, -0.4401, -0.3990, +0.0565, +0.0751, -0.5959, +0.3866, +0.2763, -0.2564, +0.4937, +0.5076, +0.3941, -0.3593, +0.4346, +0.2561, -0.0762, -0.2873, +0.6820, -0.3032, -0.3268, +0.1319, -0.3643, +0.0292],
[ +0.1816, -0.0451, -0.9370, +0.1335, -0.1030, -0.0400, +0.0311, -1.3751, -0.1860, +0.1559, +0.5395, +0.3994, -0.1703, -0.1157, +0.6342, -0.4726, -0.6213, -0.2096, -0.7549, -0.9815, -0.3798, +0.5286, -0.8413, +0.2577, +0.2223, -1.2260, -1.3571, -0.0970, +0.3334, -0.2096, +0.3566, -0.1703],
[ +0.0635, +0.1541, -0.2206, +0.0924, +0.1302, +0.1947, -0.3868, -0.6834, -0.0603, -0.3752, +0.3103, -0.1699, -0.0833, -0.1190, -0.0310, -0.5480, -1.1421, -0.0020, -0.3611, -0.3800, -0.0638, +0.0811, -0.5886, +0.0690, +0.1925, +0.0710, -0.3142, +0.1837, +0.2125, -0.1217, +0.2185, +0.0458],
[ -0.3973, +0.0486, +0.2518, -0.3208, +0.1218, -0.5324, -0.3417, +0.0322, -0.0088, +0.0214, +0.2725, +0.0960, -0.2949, -0.1770, -0.1511, +0.0259, +0.1161, -0.8829, +0.2415, +0.0939, -0.7213, +0.2220, +0.1687, -0.1802, -0.0539, +0.1786, +0.6638, +0.3559, +0.2343, +0.3212, +0.4396, -0.1385],
[ -0.2384, -0.5346, -0.2323, -0.2277, +0.3503, -0.0308, -0.2004, -0.1096, -0.2587, -0.1143, +0.2579, +0.2382, -0.5883, -0.1277, +0.2257, -0.0244, -0.9605, -0.4244, -0.7321, +0.3017, -1.6256, -0.2074, -0.8327, +0.0607, -0.0751, -0.0153, -0.4485, +0.1758, +0.1821, +0.2625, +0.0108, -0.2395],
[ -0.5639, -0.3613, +0.1291, -0.2132, +0.4927, -0.0604, -0.8067, +0.0933, -0.1483, -0.0321, -0.6843, -0.3064, -0.5646, -0.2040, -0.0414, +0.6092, +0.4903, -0.9346, +0.3389, +0.2040, -0.0295, -0.2196, +0.4264, +0.0312, -1.1801, +0.3008, +0.7719, +0.2140, -0.0257, +0.5275, -0.0553, +0.0362],
[ -0.6039, -1.2848, +0.6301, -0.1285, +0.2338, -0.2585, -0.3217, +0.4326, +0.0441, -0.0356, -0.5720, -0.8739, -0.3924, +0.2499, -0.2620, +0.1396, -0.0701, -0.2239, +0.2612, +0.1646, +0.7769, -0.6382, +0.8720, -0.1956, -0.1779, -0.1608, -0.0358, -0.4453, -0.1154, +0.5532, -0.9282, +0.0031],
[ -0.1990, +0.3708, -0.0049, -0.3260, -0.0465, +0.0415, +0.1601, +0.0019, +0.0114, +0.0438, +0.0893, +0.3056, -0.6166, +0.1145, -0.6742, +0.0483, +0.0739, -0.1139, +0.5772, -1.5569, +0.4253, -0.0769, +0.4014, -0.6817, +0.0228, -0.0383, -0.0844, -0.1560, +0.1414, -0.3420, +0.3664, -0.2293],
[ -0.0917, -0.8692, +0.4704, +0.1796, -0.1346, -0.5246, +0.0622, +0.3420, -0.5879, -0.0445, -0.3444, -0.0490, +0.0956, -0.0753, -0.8856, +0.1275, +0.1592, +0.3569, +0.1774, +0.2723, +0.1125, -0.1718, +0.2451, -0.0132, +0.1584, -0.0197, +0.0700, -0.2156, +0.0094, +0.4639, -0.6721, -0.2180],
[ +0.0578, -0.1570, -0.1623, -0.1359, +0.1346, +0.1821, -0.0696, -0.0570, +0.0011, +0.1216, +0.1069, -0.0841, +0.1017, -0.1663, -0.6005, -0.4583, -0.2606, -0.0292, +0.0321, -0.5614, -0.4416, +0.0355, +0.2081, +0.3517, +0.0619, -1.0007, -0.0765, +0.1769, -0.1286, +0.5833, -0.1758, -0.1957],
[ -0.0013, +0.3157, +0.0395, -1.0792, -0.1198, -0.2945, -0.0090, +0.3281, -0.0618, -0.0806, +0.0768, +0.2802, -0.2311, -0.2302, +0.0506, +0.0552, +0.3727, +0.3610, +0.2029, -0.1743, +0.4557, -0.1761, -0.5039, -0.9115, +0.2842, +0.1317, -0.5961, -0.4214, -1.0727, +0.3308, +0.2380, -0.3348],
[ +0.2455, -0.1299, +0.3117, -1.0169, -0.3417, +0.0310, -0.4793, +0.5334, -0.4799, -0.3291, -0.1344, +0.3732, -0.1514, +0.1574, -0.1819, -0.0206, +0.5675, -0.6992, +0.4815, -0.1497, -0.3804, +0.1389, +0.5850, -0.2920, +0.2569, -0.3527, +0.3641, -0.2014, -0.1457, +0.2365, -0.2335, -0.2610],
[ -0.2252, +0.1225, +0.0953, -0.0193, +0.3955, -0.0800, +0.0090, -0.4155, +0.1851, +0.3392, -0.3260, -0.3907, +0.1320, +0.1266, +0.0579, +0.1819, -0.5793, -0.2230, +0.1351, -0.1519, -0.0527, -0.0036, +0.1243, +0.1387, -0.2874, -0.4997, -0.3251, +0.0435, -0.5244, +0.1051, -0.2081, +0.2126],
[ -0.6574, +0.6789, +0.1026, -0.5191, +0.1058, -0.6812, +0.1798, -0.1029, +0.0757, -0.0089, +0.1539, +0.4688, -0.1306, +0.0595, -0.8136, -0.4843, +0.3675, +0.1800, +0.2641, -0.0589, +0.0613, +0.2019, -0.0765, -0.1216, -0.4588, +0.0629, +0.1133, +0.7055, -2.8075, +0.3867, +0.4791, -0.1118],
[ +0.2771, +0.3461, -0.8556, -0.0316, +0.3640, -0.1380, -0.3765, -0.9258, -0.0693, -0.1283, +0.0576, -0.0792, +0.4468, -0.5001, +0.5939, -1.2226, -0.9252, -0.3980, -1.3444, -0.9488, -0.7199, +0.4289, -1.8749, -0.0867, +0.3905, -0.4535, -0.5607, -0.2247, -0.0359, -0.4125, +0.7124, -0.1963],
[ -0.2584, -0.5358, -0.0916, +0.0765, +0.0615, -0.1887, -0.2253, -0.7855, -0.0061, -0.1887, +0.5511, +0.3207, -0.2055, -0.1694, +0.4772, -1.0356, -0.9884, -0.2620, -0.1214, +0.9733, -0.9700, -0.3205, -0.7005, -0.2960, +0.1132, -0.0352, +0.3491, -0.2440, +0.1108, +0.1083, +0.3029, -0.0031],
[ -0.6217, +0.1238, +0.0245, -0.1769, -0.2487, +0.0526, -0.0090, +0.1370, +0.2666, -0.0743, -0.8230, -0.7723, -0.0929, -0.1532, +0.6103, -0.4931, -1.3329, -0.3735, +0.0217, -0.1539, -0.4946, -1.0838, -0.5840, +0.1618, +0.2584, +0.4200, +0.1171, -0.5601, +0.1604, +0.0864, +0.2287, -0.0057],
[ -0.2220, +0.4837, -0.0825, +0.0143, +0.2734, -0.0853, +0.1578, -0.0112, +0.1829, +0.0390, +0.2151, -0.1538, -0.1111, -0.0773, +0.3439, -0.2134, -0.2884, -0.3831, +0.2767, -0.3149, +0.1463, +0.3230, +0.2187, -0.2309, -0.1096, +0.3709, -0.0105, +0.3709, +0.3034, -0.7602, +0.5988, -0.0595],
[ -0.6073, +0.1780, +0.1682, +0.1604, +0.3662, -0.0385, -0.1495, +0.3012, -0.2065, -0.0163, -1.0465, -0.8268, -0.0190, +0.0964, -0.2755, +0.0965, -0.3466, -0.3758, -0.1113, +0.1462, +0.3280, -0.1600, +0.1023, +0.1998, -0.3642, +0.2736, +0.3782, -0.2681, +0.2334, +0.1721, +0.0385, +0.0348],
[ -0.0582, -0.5750, +0.1279, +0.3630, -0.2404, -0.1511, +0.2650, -0.0324, -0.2258, +0.0007, +0.3051, -0.1875, -0.5106, +0.0104, +0.1335, -0.5282, -0.2210, +0.2648, -0.7506, +0.4975, -1.7048, +0.2378, -0.1771, +0.2981, +0.1252, +0.1384, -0.3384, -0.0830, +0.0966, +0.3728, -0.1980, -0.1953],
[ -1.0735, -0.2780, +0.1428, -0.0624, -0.0311, -0.2687, -0.1623, +0.2996, +0.1782, -0.1403, -0.3761, -1.3413, -0.2020, -0.0492, -0.6636, -0.2737, +0.2228, +0.3109, +0.1596, +0.0172, +0.1325, -1.4936, -0.0615, -0.1547, -0.2285, +0.2648, -0.1008, -1.6756, -0.2352, +0.0998, -0.4550, +0.2028],
[ -0.3866, -0.0107, +0.1052, +0.1423, +0.1160, +0.1712, -0.6206, -0.3505, -0.3298, -0.0362, +0.6768, +0.2086, -0.4348, -0.3577, +0.0131, -0.1640, +0.0160, -0.3891, -0.0180, -0.1064, -0.2494, +0.0340, +0.2225, -0.1320, -0.3550, -0.3005, +0.0118, +0.2782, +0.4691, -1.3792, +0.1971, -0.0598],
[ +0.0215, +0.1885, -0.5360, -0.1283, +0.4689, +0.1426, -0.2809, -0.8197, +0.1951, -0.1620, +0.0627, +0.2864, -0.3069, -0.1170, +0.0545, -0.4527, -0.6646, -0.1546, -0.1794, -0.5350, -0.1060, -0.0198, -0.5782, -0.2201, +0.0361, -0.2497, -0.1527, -0.1489, +0.1034, +0.0925, +0.0368, -0.0352],
[ +0.2459, +0.3230, -0.0494, -0.5631, +0.0600, -0.3036, -0.5443, +0.1081, -0.2231, +0.0734, +0.0289, +0.4205, -0.6415, -0.1305, -0.0717, +0.2971, +0.0476, -1.3001, +0.5122, -0.0005, -0.3572, +0.0727, +0.1713, -0.4751, -0.3614, -0.0957, -0.0942, +0.0580, +0.2393, +0.0038, +0.1938, -0.1704],
[ +0.3352, -0.0882, -0.0349, -0.6093, +0.4262, -0.1350, -0.0687, -0.2459, -0.5564, -0.2956, +0.1619, -0.0813, -0.5128, -0.2209, +0.3870, -0.0804, +0.7676, -0.1745, -0.3860, -0.5517, -0.6899, -0.6400, +0.6095, -0.5337, +0.3452, -0.6608, +0.0662, +0.1741, +0.1653, -0.4191, +0.1051, -0.3116],
[ -0.0527, -1.3119, +0.3441, -0.0041, -0.5938, -0.4224, +0.3973, +0.4673, -0.0613, -0.0191, +0.1297, -0.2211, -0.0880, +0.0319, +0.0661, -0.2075, +0.4380, +0.3197, +0.0989, +0.2346, -0.0142, -1.2137, +0.1618, -0.3300, +0.4591, +0.4910, +0.3537, -0.5902, -0.0616, +0.2882, -0.0900, -0.0208],
[ -0.7068, -0.7952, +0.4496, +0.1237, -0.2000, -0.5966, +0.3920, +0.3458, +0.0036, -0.0666, -0.3061, -0.1172, +0.0446, +0.1768, -0.5318, +0.2083, +0.3371, +0.1497, +0.4244, +0.3980, +0.2023, -0.8931, +0.1860, -0.6889, -0.3250, +0.1250, +0.1510, -0.3405, -0.4040, +0.1598, -0.9933, +0.0233],
[ -1.2305, -0.3178, +0.0536, -0.0585, -0.7097, +0.3196, +0.2899, +0.8200, +0.0384, +0.1733, -1.1839, -2.2545, +0.0653, +0.1376, -0.1359, -0.1202, -0.0831, -0.5397, +0.1100, +0.1386, -0.1271, -0.6298, +0.1038, -0.1213, -0.1461, -0.4508, +0.5106, -0.8266, -0.6204, +0.3753, -0.4897, -0.0751],
[ -0.3676, -0.5547, +0.0897, -0.0230, -0.3045, -0.1885, -0.5990, +0.3622, -0.2240, -0.1205, -0.3056, +0.7085, +0.0053, -0.1213, -0.3023, +0.1433, -0.2090, -0.0412, +0.2561, +0.1313, -0.2803, +0.2543, +0.0571, -0.9791, -0.0167, -0.2928, -0.3020, -0.2271, +0.0507, -0.1310, -0.6347, -0.0889],
[ -0.2794, +0.0675, -1.0020, -0.2234, +0.3937, -0.2857, +0.1058, -1.0755, -0.0377, -0.2753, -0.0501, -0.0493, -0.2987, -0.2214, +0.2869, -1.0882, -1.2635, -1.2235, -0.5762, -0.4528, -0.1372, -0.0192, -1.3768, +0.2337, +0.2008, -0.2517, -0.3918, -0.6362, -0.1762, -0.9261, +0.1711, -0.0094],
[ -0.1099, -0.2142, -0.0006, -0.4617, -0.0286, +0.3482, -0.7728, -0.4384, +0.0050, -0.0151, +0.1974, +0.2815, -0.5295, -0.2581, +0.3404, -1.6254, -1.3208, -0.1648, -0.5207, +0.4104, -0.2795, +0.0613, -1.5642, -0.1178, -0.1354, +0.0375, +0.3323, +0.0540, +0.2038, -0.3223, +0.4603, -0.3780],
[ -0.3999, -0.3719, +0.1918, -0.4738, -0.0009, +0.0419, +0.1046, +0.2675, +0.1359, -0.2536, -0.3485, -0.3118, -0.3613, +0.0914, -0.4486, +0.2719, +0.2876, -0.0685, +0.4309, +0.1856, +0.4678, -0.3314, +0.0211, +0.2575, +0.5077, -0.1494, +0.5110, -0.6869, -1.4053, +0.3093, -0.2914, -0.1501],
[ +0.3543, +0.3915, +0.0536, +0.3995, +0.2165, -0.1133, -0.1209, +0.0824, -0.0723, -0.0774, -0.4248, -0.0243, -0.1089, -0.1408, +0.2072, -0.1309, -1.5186, -0.4079, -0.0530, -0.3525, +0.6782, +0.1991, -0.0292, +0.1339, -0.1074, +0.2312, +0.1969, +0.4662, +0.5312, -0.3306, +0.0622, +0.1057],
[ -1.1778, +0.2978, +0.0443, +0.1657, +0.1317, -0.1250, -0.0459, +0.0777, +0.1359, -0.0055, +0.2364, -2.3659, +0.2214, -0.1489, -0.3051, -0.5094, +0.1495, +0.3328, +0.1264, -0.0217, +0.2321, -0.6466, -0.1813, +0.5276, +0.1975, +0.3752, +0.1469, -0.8019, +0.2427, +0.1543, +0.2140, -0.1592],
[ -0.7753, -1.3502, +0.3157, +0.1847, +0.0661, -0.5501, +0.3482, +0.6112, +0.0207, +0.0534, -0.2106, -1.0144, -0.0836, -0.0275, -1.0761, +0.2131, +0.3135, +0.3134, +0.1974, +0.0182, +0.1975, -1.1221, +0.2958, -0.2610, +0.0865, +0.3592, +0.4317, -0.3505, -0.4557, +0.3033, -0.5797, -0.2988],
[ +0.4103, -0.0643, +0.0803, +0.2177, +0.1028, -0.2668, +0.0084, -0.2340, -0.2571, +0.0334, +0.3451, -0.0055, +0.0216, -0.1460, +0.5293, -0.2615, -0.3035, +0.1736, -0.4206, -0.2186, +0.1343, +0.6001, -0.0499, -0.2777, -0.0160, -0.4303, -0.2795, +0.1932, +0.4219, -0.0800, +0.1819, -0.1007],
[ -0.7074, -0.0546, +0.4495, +0.1427, +0.3306, +0.0811, -0.5433, -0.0609, -0.2128, -0.1059, -1.0477, -0.4679, -0.1780, -0.1373, -0.3672, +0.0724, -0.0554, -0.5400, +0.0457, -0.0469, -0.0367, -0.4609, +0.1668, -0.0266, -0.9007, +0.2975, +0.5204, -0.0453, -0.1314, -0.0980, +0.1424, -0.1877],
[ +0.0657, +0.1230, -0.2558, +0.3103, -0.0795, -0.1243, +0.1956, +0.0262, -0.2626, -0.0554, +0.3760, +0.3076, -0.4633, +0.0790, +0.2363, -0.3311, +0.1235, -0.1727, -0.2468, +0.0188, -0.1121, -0.2807, -0.5865, -0.4197, +0.1949, -0.4970, -1.0413, -0.1698, +0.1798, +0.2004, -0.0514, +0.0254],
[ -0.1566, -1.1156, +0.4431, -0.1503, -0.5682, +0.1822, -0.1201, +0.5151, -0.1386, -0.1764, +0.2063, -0.8582, +0.3750, -0.1405, +0.0852, +0.2641, -0.1951, -0.0575, -0.4181, +0.2273, +0.1332, -0.2797, +0.5406, -0.0869, +0.2453, +0.0648, +0.2252, -0.0628, -0.6882, -0.0514, -0.4663, -0.0954],
[ -0.4780, +0.5844, +0.1782, -0.0831, +0.1547, -0.0595, -0.5646, -0.0488, -0.1774, -0.0098, +0.1833, +0.3520, -0.3359, -0.1492, +0.1139, -0.1223, -0.5312, -0.5361, +0.1689, -0.2020, +0.1069, +0.2327, +0.2887, +0.0526, -0.5916, -0.2435, -0.2342, +0.3422, +0.4399, -1.1880, +0.1293, -0.1021],
[ -1.2784, -1.8266, +0.0630, -0.3332, -0.5833, -0.3733, +0.3265, +0.1977, +0.0716, -0.2575, +0.0403, -0.1961, +0.1541, -0.2311, -0.1734, -0.1785, +0.0168, +0.1134, +0.0407, -0.1661, +0.5985, -1.9681, +0.1342, +0.3432, +0.3934, +0.0663, +0.3141, -2.0177, -1.7071, +0.2942, -1.0684, -0.0737],
[ +0.1763, +0.2191, +0.2609, +0.0723, +0.1038, -0.2516, -0.9086, +0.1536, +0.0153, +0.1061, +0.1675, +0.3839, -0.5326, +0.2007, -0.4943, -0.1048, +0.1614, -0.4703, +0.3453, -0.7441, -0.6187, +0.4247, +0.1721, -0.1776, -0.0919, -0.8387, +0.0798, -0.0598, +0.2711, -0.0508, +0.1761, +0.0029],
[ -0.2003, +0.2194, -0.6280, +0.1593, +0.1648, -0.1007, +0.3162, -0.3881, -0.1584, -0.0148, +0.7057, +0.0085, +0.3488, +0.0977, +0.4018, -0.8195, -0.1944, +0.4359, -0.6605, -0.1929, +0.2237, +0.1087, -0.4213, -0.7149, +0.3972, -0.1313, -0.2815, -0.7234, -0.0561, -0.5364, +0.0178, +0.0349],
[ +0.0567, +0.1687, +0.0007, +0.2939, -1.3854, +0.0168, +0.1909, +0.4919, -0.4547, +0.0562, -0.1188, +0.1653, -0.0265, -0.0541, -0.1117, -0.3240, +0.2545, +0.6516, +0.0124, -0.1258, -0.0656, -0.3524, +0.0174, +0.3926, +0.1125, +0.2834, -0.1961, -0.3603, +0.1783, -0.0224, -0.6900, -0.1688],
[ +0.0672, +0.6339, -0.3839, +0.0077, +0.8224, -0.3197, -0.0589, -0.1318, +0.0222, -0.1530, +0.1237, +0.4014, -0.1952, -0.1130, +0.4214, -0.2741, +0.2291, +0.0757, +0.0563, -0.0967, +0.4210, +0.5133, +0.0412, -0.9212, +0.1377, -0.4068, -0.3652, +0.4283, +0.6182, -0.6187, +0.1997, +0.1240],
[ -0.0067, +0.3307, -0.7751, -0.2084, +0.4740, -0.0264, -0.0768, -0.9519, -0.0632, -0.0753, +0.3293, +0.5260, -0.6023, +0.0060, +0.2799, -0.2904, -0.8262, -0.6644, -0.3900, -0.1461, +0.4965, +0.3996, -0.7569, +0.0612, +0.5168, -0.5160, -0.4875, +0.3759, +0.0295, +0.1027, +0.6096, -0.0115],
[ -0.0110, +0.4652, -0.1486, -0.6029, +0.2581, -0.3184, -0.3759, +0.3213, -0.2748, -0.0630, +0.0953, +0.2101, -1.2738, -0.1353, +0.2710, -0.2276, +0.2586, -0.2347, -0.3320, +0.0487, -0.2318, -0.1002, +0.1236, +0.2660, -0.1172, +0.1437, -0.0850, +0.1659, -0.2152, -0.0764, +0.2838, -0.1325],
[ +0.0152, -0.0906, -0.1897, -0.3521, -0.1836, -0.1694, -0.4150, -0.1695, +0.0509, -0.0716, +0.3118, +0.2422, -0.5058, -0.0637, -0.1038, -0.2828, -0.0528, -0.2051, +0.2062, -0.2105, -0.7317, +0.1881, -0.2992, -0.0883, +0.0115, -1.5295, -0.1671, +0.0411, +0.0648, -0.0119, -0.2941, +0.0273],
[ +0.5028, +0.1780, -0.4643, -0.0373, +0.3067, -0.1974, +0.2643, -0.2365, -0.2083, +0.0472, +0.4830, +0.0630, +0.2155, -0.0916, +0.6290, -0.4427, -0.6266, +0.3576, -0.3541, -0.2034, +0.3733, +0.8247, -0.5837, -0.4372, +0.2696, -0.4042, -0.3436, +0.0355, -0.2288, -0.6382, +0.7358, -0.1229]
[
+0.5019, +0.3831, +0.6726, +0.3767, +0.2021, -0.1615, +0.3882, -0.0487,
-0.2713, +0.1173, -0.2218, +0.0598, +0.0819, -0.1157, +0.5879, -0.3587,
+0.1376, -0.2595, +0.0257, -0.1182, +0.0723, +0.5612, -0.4087, -0.4651,
+0.0631, +0.1786, +0.1206, +0.4791, +0.5922, -0.4444, +0.3446, -0.0464
],
[
-0.0485, +0.0739, -0.6915, +0.5446, -0.2461, +0.1557, +0.8993, -0.7537,
+0.1149, +0.0575, -0.1714, -0.3796, +0.3508, -0.2315, +0.4389, -1.4456,
-1.3490, -0.1598, -1.0354, -0.2320, -0.3765, +0.1070, -0.7107, +0.4150,
+0.2711, -0.2915, -0.7957, +0.7753, -0.0425, -0.1352, +0.3018, -0.0069
],
[
-0.4047, +1.0040, -0.4570, +0.3017, +0.1477, -0.0163, +0.4087, -0.6368,
-0.0764, -0.0695, +0.0208, -0.2411, +0.1936, +0.0047, +0.0107, -0.8538,
-0.5887, -0.0524, -1.4902, +0.2858, +0.4396, -0.3433, -0.6778, -0.7137,
+0.4587, +0.3359, -0.7350, -1.0813, -0.1296, +0.1748, -0.3830, -0.2103
],
[
+0.0503, -0.3342, -0.6057, +0.2217, +0.3164, -0.1881, -0.5867, -0.2471,
-0.2527, -0.0444, +0.1874, -0.0960, +0.2039, -0.0488, +0.1741, -0.1623,
-0.0758, -0.2354, -0.5986, -0.2129, -0.2470, +0.3317, -0.4795, -0.6380,
+0.1494, +0.0115, -0.2746, -0.8428, -0.0118, -0.0604, +0.0886, -0.0408
],
[
-0.1932, -1.3896, +0.3919, -0.4700, -0.9806, -0.1554, +0.3132, +0.4138,
-0.4943, -0.1408, -0.0976, +0.1551, -0.0180, +0.0864, -0.0053, -0.2430,
+0.4948, +0.2709, -0.3488, +0.2085, -0.2124, -0.3025, -0.0692, +0.3884,
+0.5764, +0.5783, +0.4351, -0.2633, -0.9288, +0.2218, -0.9049, -0.2970
],
[
-0.2841, -0.3393, -0.1062, -0.1415, +0.0257, +0.0816, -0.4833, -0.2775,
+0.0308, -0.0344, +0.5451, +0.1588, -0.7454, -0.1444, +0.4189, -0.2001,
-2.0586, -0.0616, -1.4463, +0.0076, -0.7703, +0.3279, -0.7009, +0.6046,
-0.1615, -0.5188, -0.7503, +0.0615, +0.1815, -0.2512, +0.0321, -0.1834
],
[
+0.3751, +0.2932, -0.6815, +0.3771, +0.0603, -0.2035, -0.2644, -1.0120,
-0.0661, -0.0846, +0.1209, +0.0367, +0.0493, -0.2603, -0.1608, -0.7580,
-0.8609, +0.1415, -0.7626, -1.0209, -0.7498, -0.0732, -0.8138, -0.2292,
+0.5803, -0.2718, -1.4684, -0.1584, +0.2096, +0.1336, +0.3632, +0.0216
],
[
-0.0625, -0.1233, -0.2715, +0.5541, +0.3121, +0.0265, +0.4501, -1.1024,
-0.1160, -0.1005, -0.0844, -0.0516, +0.0916, +0.0901, +0.3710, -0.5753,
-0.3728, -0.1103, -0.6285, -0.2179, +0.1570, +0.1168, -0.9312, +0.0135,
-0.0376, -0.1693, -0.5358, -0.0028, +0.2105, -0.7373, +0.2776, +0.2326
],
[
-0.5378, -0.3201, +0.3606, +0.1331, +0.0120, -0.2421, -0.0230, +0.4622,
-0.3140, +0.0803, -0.6897, -0.4704, +0.2685, +0.0803, -0.7654, -0.1433,
+0.0242, +0.0917, +0.2458, +0.0457, -0.2503, -0.1197, +0.1454, -0.1523,
-0.4095, +0.1856, +0.0678, -1.0011, +0.0117, +0.1789, -0.4063, -0.0888
],
[
-0.6352, -0.6358, -0.2066, +0.0758, -0.2973, -0.3014, -0.0556, -0.0912,
-0.2729, -0.1492, -0.1928, -1.8768, +0.2183, +0.0801, +0.1288, -1.2493,
+0.1115, +0.2797, -0.1458, +0.0062, -0.0402, -0.8945, -0.2231, -0.1154,
+0.3635, -0.3021, +0.1402, -0.7347, +0.2772, +0.3182, -0.9708, +0.0376
],
[
+0.6899, +0.3471, -0.5863, +0.1497, +0.1616, -0.0497, +0.3579, -0.6421,
+0.4529, -0.1588, +0.9250, +0.2357, -0.0712, -0.1793, -0.0231, -0.4814,
-0.7654, +0.0591, -0.6866, -0.1705, +0.2255, -0.0007, -0.3890, +0.6114,
+0.0443, -0.6929, -0.7734, +0.2314, -0.0231, -0.6386, +0.1237, +0.0472
],
[
-0.2496, -0.1687, +0.1234, +0.4152, +0.4207, -0.1398, +0.1287, +0.5903,
+0.0530, -0.1181, +0.0803, -0.0641, -0.1198, -0.4702, -0.3669, +0.2340,
-0.3778, +0.4341, +0.2411, -0.2171, -0.3051, -0.2397, +0.1756, +0.4040,
+0.0682, +0.1575, +0.4137, +0.0887, -0.1998, +0.2221, -0.2474, -0.0559
],
[
-2.2466, -1.2725, +0.5947, -0.3192, -0.2665, -0.0129, -0.7615, +0.1148,
+0.2745, -0.0556, -1.3313, -0.7143, -0.5119, -0.0572, -0.1892, -0.3294,
-0.0187, -0.7696, +1.0413, +0.4226, +0.1378, -1.3668, +0.9806, -0.1810,
-0.2307, -0.4924, +0.7163, -1.2529, -0.3216, +0.1683, -0.6657, -0.1121
],
[
+0.1227, +0.2433, -0.1292, -0.7152, -0.1342, -0.1116, -0.2695, +0.0243,
-0.0770, -0.1713, +0.2837, +0.2076, -0.7322, -0.1657, -0.3407, -0.4378,
+0.0679, -0.3777, +0.3025, -0.6780, -0.2326, +0.1463, +0.0535, -0.6373,
-0.2027, -0.5404, -0.1598, +0.1511, -0.1776, +0.0854, +0.1753, -0.0342
],
[
-0.1772, -0.2654, -0.4170, -0.3301, +0.2956, -0.4234, +0.0835, +0.2869,
-0.2804, -0.2073, -0.3291, -0.5897, -0.4116, -0.0447, +0.1601, +0.1602,
+0.1691, -0.2014, -0.0502, +0.1167, -1.0103, -0.4297, -0.2039, -0.0859,
+0.2756, -0.1768, -0.2726, -0.0256, -0.0834, +0.0852, +0.0930, -0.0606
],
[
-0.5390, -0.5441, +0.3202, -0.1018, +0.0059, +0.1799, -0.1917, +0.3674,
+0.2576, -0.0707, -0.4401, -0.3990, +0.0565, +0.0751, -0.5959, +0.3866,
+0.2763, -0.2564, +0.4937, +0.5076, +0.3941, -0.3593, +0.4346, +0.2561,
-0.0762, -0.2873, +0.6820, -0.3032, -0.3268, +0.1319, -0.3643, +0.0292
],
[
+0.1816, -0.0451, -0.9370, +0.1335, -0.1030, -0.0400, +0.0311, -1.3751,
-0.1860, +0.1559, +0.5395, +0.3994, -0.1703, -0.1157, +0.6342, -0.4726,
-0.6213, -0.2096, -0.7549, -0.9815, -0.3798, +0.5286, -0.8413, +0.2577,
+0.2223, -1.2260, -1.3571, -0.0970, +0.3334, -0.2096, +0.3566, -0.1703
],
[
+0.0635, +0.1541, -0.2206, +0.0924, +0.1302, +0.1947, -0.3868, -0.6834,
-0.0603, -0.3752, +0.3103, -0.1699, -0.0833, -0.1190, -0.0310, -0.5480,
-1.1421, -0.0020, -0.3611, -0.3800, -0.0638, +0.0811, -0.5886, +0.0690,
+0.1925, +0.0710, -0.3142, +0.1837, +0.2125, -0.1217, +0.2185, +0.0458
],
[
-0.3973, +0.0486, +0.2518, -0.3208, +0.1218, -0.5324, -0.3417, +0.0322,
-0.0088, +0.0214, +0.2725, +0.0960, -0.2949, -0.1770, -0.1511, +0.0259,
+0.1161, -0.8829, +0.2415, +0.0939, -0.7213, +0.2220, +0.1687, -0.1802,
-0.0539, +0.1786, +0.6638, +0.3559, +0.2343, +0.3212, +0.4396, -0.1385
],
[
-0.2384, -0.5346, -0.2323, -0.2277, +0.3503, -0.0308, -0.2004, -0.1096,
-0.2587, -0.1143, +0.2579, +0.2382, -0.5883, -0.1277, +0.2257, -0.0244,
-0.9605, -0.4244, -0.7321, +0.3017, -1.6256, -0.2074, -0.8327, +0.0607,
-0.0751, -0.0153, -0.4485, +0.1758, +0.1821, +0.2625, +0.0108, -0.2395
],
[
-0.5639, -0.3613, +0.1291, -0.2132, +0.4927, -0.0604, -0.8067, +0.0933,
-0.1483, -0.0321, -0.6843, -0.3064, -0.5646, -0.2040, -0.0414, +0.6092,
+0.4903, -0.9346, +0.3389, +0.2040, -0.0295, -0.2196, +0.4264, +0.0312,
-1.1801, +0.3008, +0.7719, +0.2140, -0.0257, +0.5275, -0.0553, +0.0362
],
[
-0.6039, -1.2848, +0.6301, -0.1285, +0.2338, -0.2585, -0.3217, +0.4326,
+0.0441, -0.0356, -0.5720, -0.8739, -0.3924, +0.2499, -0.2620, +0.1396,
-0.0701, -0.2239, +0.2612, +0.1646, +0.7769, -0.6382, +0.8720, -0.1956,
-0.1779, -0.1608, -0.0358, -0.4453, -0.1154, +0.5532, -0.9282, +0.0031
],
[
-0.1990, +0.3708, -0.0049, -0.3260, -0.0465, +0.0415, +0.1601, +0.0019,
+0.0114, +0.0438, +0.0893, +0.3056, -0.6166, +0.1145, -0.6742, +0.0483,
+0.0739, -0.1139, +0.5772, -1.5569, +0.4253, -0.0769, +0.4014, -0.6817,
+0.0228, -0.0383, -0.0844, -0.1560, +0.1414, -0.3420, +0.3664, -0.2293
],
[
-0.0917, -0.8692, +0.4704, +0.1796, -0.1346, -0.5246, +0.0622, +0.3420,
-0.5879, -0.0445, -0.3444, -0.0490, +0.0956, -0.0753, -0.8856, +0.1275,
+0.1592, +0.3569, +0.1774, +0.2723, +0.1125, -0.1718, +0.2451, -0.0132,
+0.1584, -0.0197, +0.0700, -0.2156, +0.0094, +0.4639, -0.6721, -0.2180
],
[
+0.0578, -0.1570, -0.1623, -0.1359, +0.1346, +0.1821, -0.0696, -0.0570,
+0.0011, +0.1216, +0.1069, -0.0841, +0.1017, -0.1663, -0.6005, -0.4583,
-0.2606, -0.0292, +0.0321, -0.5614, -0.4416, +0.0355, +0.2081, +0.3517,
+0.0619, -1.0007, -0.0765, +0.1769, -0.1286, +0.5833, -0.1758, -0.1957
],
[
-0.0013, +0.3157, +0.0395, -1.0792, -0.1198, -0.2945, -0.0090, +0.3281,
-0.0618, -0.0806, +0.0768, +0.2802, -0.2311, -0.2302, +0.0506, +0.0552,
+0.3727, +0.3610, +0.2029, -0.1743, +0.4557, -0.1761, -0.5039, -0.9115,
+0.2842, +0.1317, -0.5961, -0.4214, -1.0727, +0.3308, +0.2380, -0.3348
],
[
+0.2455, -0.1299, +0.3117, -1.0169, -0.3417, +0.0310, -0.4793, +0.5334,
-0.4799, -0.3291, -0.1344, +0.3732, -0.1514, +0.1574, -0.1819, -0.0206,
+0.5675, -0.6992, +0.4815, -0.1497, -0.3804, +0.1389, +0.5850, -0.2920,
+0.2569, -0.3527, +0.3641, -0.2014, -0.1457, +0.2365, -0.2335, -0.2610
],
[
-0.2252, +0.1225, +0.0953, -0.0193, +0.3955, -0.0800, +0.0090, -0.4155,
+0.1851, +0.3392, -0.3260, -0.3907, +0.1320, +0.1266, +0.0579, +0.1819,
-0.5793, -0.2230, +0.1351, -0.1519, -0.0527, -0.0036, +0.1243, +0.1387,
-0.2874, -0.4997, -0.3251, +0.0435, -0.5244, +0.1051, -0.2081, +0.2126
],
[
-0.6574, +0.6789, +0.1026, -0.5191, +0.1058, -0.6812, +0.1798, -0.1029,
+0.0757, -0.0089, +0.1539, +0.4688, -0.1306, +0.0595, -0.8136, -0.4843,
+0.3675, +0.1800, +0.2641, -0.0589, +0.0613, +0.2019, -0.0765, -0.1216,
-0.4588, +0.0629, +0.1133, +0.7055, -2.8075, +0.3867, +0.4791, -0.1118
],
[
+0.2771, +0.3461, -0.8556, -0.0316, +0.3640, -0.1380, -0.3765, -0.9258,
-0.0693, -0.1283, +0.0576, -0.0792, +0.4468, -0.5001, +0.5939, -1.2226,
-0.9252, -0.3980, -1.3444, -0.9488, -0.7199, +0.4289, -1.8749, -0.0867,
+0.3905, -0.4535, -0.5607, -0.2247, -0.0359, -0.4125, +0.7124, -0.1963
],
[
-0.2584, -0.5358, -0.0916, +0.0765, +0.0615, -0.1887, -0.2253, -0.7855,
-0.0061, -0.1887, +0.5511, +0.3207, -0.2055, -0.1694, +0.4772, -1.0356,
-0.9884, -0.2620, -0.1214, +0.9733, -0.9700, -0.3205, -0.7005, -0.2960,
+0.1132, -0.0352, +0.3491, -0.2440, +0.1108, +0.1083, +0.3029, -0.0031
],
[
-0.6217, +0.1238, +0.0245, -0.1769, -0.2487, +0.0526, -0.0090, +0.1370,
+0.2666, -0.0743, -0.8230, -0.7723, -0.0929, -0.1532, +0.6103, -0.4931,
-1.3329, -0.3735, +0.0217, -0.1539, -0.4946, -1.0838, -0.5840, +0.1618,
+0.2584, +0.4200, +0.1171, -0.5601, +0.1604, +0.0864, +0.2287, -0.0057
],
[
-0.2220, +0.4837, -0.0825, +0.0143, +0.2734, -0.0853, +0.1578, -0.0112,
+0.1829, +0.0390, +0.2151, -0.1538, -0.1111, -0.0773, +0.3439, -0.2134,
-0.2884, -0.3831, +0.2767, -0.3149, +0.1463, +0.3230, +0.2187, -0.2309,
-0.1096, +0.3709, -0.0105, +0.3709, +0.3034, -0.7602, +0.5988, -0.0595
],
[
-0.6073, +0.1780, +0.1682, +0.1604, +0.3662, -0.0385, -0.1495, +0.3012,
-0.2065, -0.0163, -1.0465, -0.8268, -0.0190, +0.0964, -0.2755, +0.0965,
-0.3466, -0.3758, -0.1113, +0.1462, +0.3280, -0.1600, +0.1023, +0.1998,
-0.3642, +0.2736, +0.3782, -0.2681, +0.2334, +0.1721, +0.0385, +0.0348
],
[
-0.0582, -0.5750, +0.1279, +0.3630, -0.2404, -0.1511, +0.2650, -0.0324,
-0.2258, +0.0007, +0.3051, -0.1875, -0.5106, +0.0104, +0.1335, -0.5282,
-0.2210, +0.2648, -0.7506, +0.4975, -1.7048, +0.2378, -0.1771, +0.2981,
+0.1252, +0.1384, -0.3384, -0.0830, +0.0966, +0.3728, -0.1980, -0.1953
],
[
-1.0735, -0.2780, +0.1428, -0.0624, -0.0311, -0.2687, -0.1623, +0.2996,
+0.1782, -0.1403, -0.3761, -1.3413, -0.2020, -0.0492, -0.6636, -0.2737,
+0.2228, +0.3109, +0.1596, +0.0172, +0.1325, -1.4936, -0.0615, -0.1547,
-0.2285, +0.2648, -0.1008, -1.6756, -0.2352, +0.0998, -0.4550, +0.2028
],
[
-0.3866, -0.0107, +0.1052, +0.1423, +0.1160, +0.1712, -0.6206, -0.3505,
-0.3298, -0.0362, +0.6768, +0.2086, -0.4348, -0.3577, +0.0131, -0.1640,
+0.0160, -0.3891, -0.0180, -0.1064, -0.2494, +0.0340, +0.2225, -0.1320,
-0.3550, -0.3005, +0.0118, +0.2782, +0.4691, -1.3792, +0.1971, -0.0598
],
[
+0.0215, +0.1885, -0.5360, -0.1283, +0.4689, +0.1426, -0.2809, -0.8197,
+0.1951, -0.1620, +0.0627, +0.2864, -0.3069, -0.1170, +0.0545, -0.4527,
-0.6646, -0.1546, -0.1794, -0.5350, -0.1060, -0.0198, -0.5782, -0.2201,
+0.0361, -0.2497, -0.1527, -0.1489, +0.1034, +0.0925, +0.0368, -0.0352
],
[
+0.2459, +0.3230, -0.0494, -0.5631, +0.0600, -0.3036, -0.5443, +0.1081,
-0.2231, +0.0734, +0.0289, +0.4205, -0.6415, -0.1305, -0.0717, +0.2971,
+0.0476, -1.3001, +0.5122, -0.0005, -0.3572, +0.0727, +0.1713, -0.4751,
-0.3614, -0.0957, -0.0942, +0.0580, +0.2393, +0.0038, +0.1938, -0.1704
],
[
+0.3352, -0.0882, -0.0349, -0.6093, +0.4262, -0.1350, -0.0687, -0.2459,
-0.5564, -0.2956, +0.1619, -0.0813, -0.5128, -0.2209, +0.3870, -0.0804,
+0.7676, -0.1745, -0.3860, -0.5517, -0.6899, -0.6400, +0.6095, -0.5337,
+0.3452, -0.6608, +0.0662, +0.1741, +0.1653, -0.4191, +0.1051, -0.3116
],
[
-0.0527, -1.3119, +0.3441, -0.0041, -0.5938, -0.4224, +0.3973, +0.4673,
-0.0613, -0.0191, +0.1297, -0.2211, -0.0880, +0.0319, +0.0661, -0.2075,
+0.4380, +0.3197, +0.0989, +0.2346, -0.0142, -1.2137, +0.1618, -0.3300,
+0.4591, +0.4910, +0.3537, -0.5902, -0.0616, +0.2882, -0.0900, -0.0208
],
[
-0.7068, -0.7952, +0.4496, +0.1237, -0.2000, -0.5966, +0.3920, +0.3458,
+0.0036, -0.0666, -0.3061, -0.1172, +0.0446, +0.1768, -0.5318, +0.2083,
+0.3371, +0.1497, +0.4244, +0.3980, +0.2023, -0.8931, +0.1860, -0.6889,
-0.3250, +0.1250, +0.1510, -0.3405, -0.4040, +0.1598, -0.9933, +0.0233
],
[
-1.2305, -0.3178, +0.0536, -0.0585, -0.7097, +0.3196, +0.2899, +0.8200,
+0.0384, +0.1733, -1.1839, -2.2545, +0.0653, +0.1376, -0.1359, -0.1202,
-0.0831, -0.5397, +0.1100, +0.1386, -0.1271, -0.6298, +0.1038, -0.1213,
-0.1461, -0.4508, +0.5106, -0.8266, -0.6204, +0.3753, -0.4897, -0.0751
],
[
-0.3676, -0.5547, +0.0897, -0.0230, -0.3045, -0.1885, -0.5990, +0.3622,
-0.2240, -0.1205, -0.3056, +0.7085, +0.0053, -0.1213, -0.3023, +0.1433,
-0.2090, -0.0412, +0.2561, +0.1313, -0.2803, +0.2543, +0.0571, -0.9791,
-0.0167, -0.2928, -0.3020, -0.2271, +0.0507, -0.1310, -0.6347, -0.0889
],
[
-0.2794, +0.0675, -1.0020, -0.2234, +0.3937, -0.2857, +0.1058, -1.0755,
-0.0377, -0.2753, -0.0501, -0.0493, -0.2987, -0.2214, +0.2869, -1.0882,
-1.2635, -1.2235, -0.5762, -0.4528, -0.1372, -0.0192, -1.3768, +0.2337,
+0.2008, -0.2517, -0.3918, -0.6362, -0.1762, -0.9261, +0.1711, -0.0094
],
[
-0.1099, -0.2142, -0.0006, -0.4617, -0.0286, +0.3482, -0.7728, -0.4384,
+0.0050, -0.0151, +0.1974, +0.2815, -0.5295, -0.2581, +0.3404, -1.6254,
-1.3208, -0.1648, -0.5207, +0.4104, -0.2795, +0.0613, -1.5642, -0.1178,
-0.1354, +0.0375, +0.3323, +0.0540, +0.2038, -0.3223, +0.4603, -0.3780
],
[
-0.3999, -0.3719, +0.1918, -0.4738, -0.0009, +0.0419, +0.1046, +0.2675,
+0.1359, -0.2536, -0.3485, -0.3118, -0.3613, +0.0914, -0.4486, +0.2719,
+0.2876, -0.0685, +0.4309, +0.1856, +0.4678, -0.3314, +0.0211, +0.2575,
+0.5077, -0.1494, +0.5110, -0.6869, -1.4053, +0.3093, -0.2914, -0.1501
],
[
+0.3543, +0.3915, +0.0536, +0.3995, +0.2165, -0.1133, -0.1209, +0.0824,
-0.0723, -0.0774, -0.4248, -0.0243, -0.1089, -0.1408, +0.2072, -0.1309,
-1.5186, -0.4079, -0.0530, -0.3525, +0.6782, +0.1991, -0.0292, +0.1339,
-0.1074, +0.2312, +0.1969, +0.4662, +0.5312, -0.3306, +0.0622, +0.1057
],
[
-1.1778, +0.2978, +0.0443, +0.1657, +0.1317, -0.1250, -0.0459, +0.0777,
+0.1359, -0.0055, +0.2364, -2.3659, +0.2214, -0.1489, -0.3051, -0.5094,
+0.1495, +0.3328, +0.1264, -0.0217, +0.2321, -0.6466, -0.1813, +0.5276,
+0.1975, +0.3752, +0.1469, -0.8019, +0.2427, +0.1543, +0.2140, -0.1592
],
[
-0.7753, -1.3502, +0.3157, +0.1847, +0.0661, -0.5501, +0.3482, +0.6112,
+0.0207, +0.0534, -0.2106, -1.0144, -0.0836, -0.0275, -1.0761, +0.2131,
+0.3135, +0.3134, +0.1974, +0.0182, +0.1975, -1.1221, +0.2958, -0.2610,
+0.0865, +0.3592, +0.4317, -0.3505, -0.4557, +0.3033, -0.5797, -0.2988
],
[
+0.4103, -0.0643, +0.0803, +0.2177, +0.1028, -0.2668, +0.0084, -0.2340,
-0.2571, +0.0334, +0.3451, -0.0055, +0.0216, -0.1460, +0.5293, -0.2615,
-0.3035, +0.1736, -0.4206, -0.2186, +0.1343, +0.6001, -0.0499, -0.2777,
-0.0160, -0.4303, -0.2795, +0.1932, +0.4219, -0.0800, +0.1819, -0.1007
],
[
-0.7074, -0.0546, +0.4495, +0.1427, +0.3306, +0.0811, -0.5433, -0.0609,
-0.2128, -0.1059, -1.0477, -0.4679, -0.1780, -0.1373, -0.3672, +0.0724,
-0.0554, -0.5400, +0.0457, -0.0469, -0.0367, -0.4609, +0.1668, -0.0266,
-0.9007, +0.2975, +0.5204, -0.0453, -0.1314, -0.0980, +0.1424, -0.1877
],
[
+0.0657, +0.1230, -0.2558, +0.3103, -0.0795, -0.1243, +0.1956, +0.0262,
-0.2626, -0.0554, +0.3760, +0.3076, -0.4633, +0.0790, +0.2363, -0.3311,
+0.1235, -0.1727, -0.2468, +0.0188, -0.1121, -0.2807, -0.5865, -0.4197,
+0.1949, -0.4970, -1.0413, -0.1698, +0.1798, +0.2004, -0.0514, +0.0254
],
[
-0.1566, -1.1156, +0.4431, -0.1503, -0.5682, +0.1822, -0.1201, +0.5151,
-0.1386, -0.1764, +0.2063, -0.8582, +0.3750, -0.1405, +0.0852, +0.2641,
-0.1951, -0.0575, -0.4181, +0.2273, +0.1332, -0.2797, +0.5406, -0.0869,
+0.2453, +0.0648, +0.2252, -0.0628, -0.6882, -0.0514, -0.4663, -0.0954
],
[
-0.4780, +0.5844, +0.1782, -0.0831, +0.1547, -0.0595, -0.5646, -0.0488,
-0.1774, -0.0098, +0.1833, +0.3520, -0.3359, -0.1492, +0.1139, -0.1223,
-0.5312, -0.5361, +0.1689, -0.2020, +0.1069, +0.2327, +0.2887, +0.0526,
-0.5916, -0.2435, -0.2342, +0.3422, +0.4399, -1.1880, +0.1293, -0.1021
],
[
-1.2784, -1.8266, +0.0630, -0.3332, -0.5833, -0.3733, +0.3265, +0.1977,
+0.0716, -0.2575, +0.0403, -0.1961, +0.1541, -0.2311, -0.1734, -0.1785,
+0.0168, +0.1134, +0.0407, -0.1661, +0.5985, -1.9681, +0.1342, +0.3432,
+0.3934, +0.0663, +0.3141, -2.0177, -1.7071, +0.2942, -1.0684, -0.0737
],
[
+0.1763, +0.2191, +0.2609, +0.0723, +0.1038, -0.2516, -0.9086, +0.1536,
+0.0153, +0.1061, +0.1675, +0.3839, -0.5326, +0.2007, -0.4943, -0.1048,
+0.1614, -0.4703, +0.3453, -0.7441, -0.6187, +0.4247, +0.1721, -0.1776,
-0.0919, -0.8387, +0.0798, -0.0598, +0.2711, -0.0508, +0.1761, +0.0029
],
[
-0.2003, +0.2194, -0.6280, +0.1593, +0.1648, -0.1007, +0.3162, -0.3881,
-0.1584, -0.0148, +0.7057, +0.0085, +0.3488, +0.0977, +0.4018, -0.8195,
-0.1944, +0.4359, -0.6605, -0.1929, +0.2237, +0.1087, -0.4213, -0.7149,
+0.3972, -0.1313, -0.2815, -0.7234, -0.0561, -0.5364, +0.0178, +0.0349
],
[
+0.0567, +0.1687, +0.0007, +0.2939, -1.3854, +0.0168, +0.1909, +0.4919,
-0.4547, +0.0562, -0.1188, +0.1653, -0.0265, -0.0541, -0.1117, -0.3240,
+0.2545, +0.6516, +0.0124, -0.1258, -0.0656, -0.3524, +0.0174, +0.3926,
+0.1125, +0.2834, -0.1961, -0.3603, +0.1783, -0.0224, -0.6900, -0.1688
],
[
+0.0672, +0.6339, -0.3839, +0.0077, +0.8224, -0.3197, -0.0589, -0.1318,
+0.0222, -0.1530, +0.1237, +0.4014, -0.1952, -0.1130, +0.4214, -0.2741,
+0.2291, +0.0757, +0.0563, -0.0967, +0.4210, +0.5133, +0.0412, -0.9212,
+0.1377, -0.4068, -0.3652, +0.4283, +0.6182, -0.6187, +0.1997, +0.1240
],
[
-0.0067, +0.3307, -0.7751, -0.2084, +0.4740, -0.0264, -0.0768, -0.9519,
-0.0632, -0.0753, +0.3293, +0.5260, -0.6023, +0.0060, +0.2799, -0.2904,
-0.8262, -0.6644, -0.3900, -0.1461, +0.4965, +0.3996, -0.7569, +0.0612,
+0.5168, -0.5160, -0.4875, +0.3759, +0.0295, +0.1027, +0.6096, -0.0115
],
[
-0.0110, +0.4652, -0.1486, -0.6029, +0.2581, -0.3184, -0.3759, +0.3213,
-0.2748, -0.0630, +0.0953, +0.2101, -1.2738, -0.1353, +0.2710, -0.2276,
+0.2586, -0.2347, -0.3320, +0.0487, -0.2318, -0.1002, +0.1236, +0.2660,
-0.1172, +0.1437, -0.0850, +0.1659, -0.2152, -0.0764, +0.2838, -0.1325
],
[
+0.0152, -0.0906, -0.1897, -0.3521, -0.1836, -0.1694, -0.4150, -0.1695,
+0.0509, -0.0716, +0.3118, +0.2422, -0.5058, -0.0637, -0.1038, -0.2828,
-0.0528, -0.2051, +0.2062, -0.2105, -0.7317, +0.1881, -0.2992, -0.0883,
+0.0115, -1.5295, -0.1671, +0.0411, +0.0648, -0.0119, -0.2941, +0.0273
],
[
+0.5028, +0.1780, -0.4643, -0.0373, +0.3067, -0.1974, +0.2643, -0.2365,
-0.2083, +0.0472, +0.4830, +0.0630, +0.2155, -0.0916, +0.6290, -0.4427,
-0.6266, +0.3576, -0.3541, -0.2034, +0.3733, +0.8247, -0.5837, -0.4372,
+0.2696, -0.4042, -0.3436, +0.0355, -0.2288, -0.6382, +0.7358, -0.1229
]
])
weights_dense2_b = np.array([ -0.0730, +0.0456, +0.0877, -0.2607, +0.0029, -0.2705, -0.1420, +0.2403, -0.2135, -0.0646, +0.1378, +0.1105, -0.4639, -0.0583, -0.0872, -0.1473, +0.1460, -0.0234, +0.0740, -0.0745, -0.1283, +0.0316, +0.0361, -0.0726, -0.0304, +0.0417, -0.0313, +0.0935, +0.0815, +0.0814, +0.0818, -0.1111])
weights_final_w = np.array([
[ +1.0397],
[ +0.7049],
[ -0.2128],
[ +0.2172],
[ +0.3027],
[ -0.1991],
[ +0.3398],
[ -0.5932],
[ -0.1439],
[ -0.0236],
[ +0.5679],
[ +0.8571],
[ +0.1934],
[ -0.1652],
[ +0.6933],
[ -0.5510],
[ -1.0587],
[ +0.6996],
[ -0.5009],
[ -0.4000],
[ -0.6958],
[ +0.7716],
[ -0.5342],
[ -0.5095],
[ +0.3040],
[ -1.1986],
[ -0.4900],
[ +0.7726],
[ +0.5871],
[ -0.2533],
[ +0.2633],
[ -0.0004]
weights_dense2_b = np.array([
-0.0730, +0.0456, +0.0877, -0.2607, +0.0029, -0.2705, -0.1420, +0.2403,
-0.2135, -0.0646, +0.1378, +0.1105, -0.4639, -0.0583, -0.0872, -0.1473,
+0.1460, -0.0234, +0.0740, -0.0745, -0.1283, +0.0316, +0.0361, -0.0726,
-0.0304, +0.0417, -0.0313, +0.0935, +0.0815, +0.0814, +0.0818, -0.1111
])
weights_final_b = np.array([ +0.0190])
weights_final_w = np.array([[+1.0397], [+0.7049], [-0.2128], [+0.2172],
[+0.3027], [-0.1991], [+0.3398], [-0.5932],
[-0.1439], [-0.0236], [+0.5679], [+0.8571],
[+0.1934], [-0.1652], [+0.6933], [-0.5510],
[-1.0587], [+0.6996], [-0.5009], [-0.4000],
[-0.6958], [+0.7716], [-0.5342], [-0.5095],
[+0.3040], [-1.1986], [-0.4900], [+0.7726],
[+0.5871], [-0.2533], [+0.2633], [-0.0004]])
if __name__=="__main__":
main()
weights_final_b = np.array([+0.0190])
# yapf: enable
if __name__ == "__main__":
main()

View File

@@ -2,174 +2,537 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import gym
import numpy as np
import pybullet_envs
import time
def relu(x):
return np.maximum(x, 0)
return np.maximum(x, 0)
class SmallReactivePolicy:
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64)
assert weights_dense2_w.shape == (64, 32)
assert weights_final_w.shape == (32, action_space.shape[0])
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64)
assert weights_dense2_w.shape == (64, 32)
assert weights_final_w.shape == (32, action_space.shape[0])
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def main():
print("create env")
env = gym.make("InvertedPendulumBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
print("create env")
env = gym.make("InvertedPendulumBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
print("frame")
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
print("frame")
while 1:
time.sleep(1./60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open==False:
return
if not done: continue
if restart_delay==0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60*2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay==0: break
time.sleep(1. / 60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open == False:
return
if not done: continue
if restart_delay == 0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60 * 2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay == 0: break
weights_dense1_w = np.array([
[ +0.8621, +0.3260, +0.0986, -0.1225, +0.2038, -0.8051, -0.7498, +0.1905, -0.3418, +0.5002, -0.1093, +0.0285, +0.3480, -0.1596, -0.1781, +0.3643, -0.4283, -0.3715, -0.1571, +0.3531, +0.0934, -0.2215, -0.3085, +0.9581, +0.2485, -0.6232, -0.3175, +0.9771, +0.3651, -0.8850, -0.4212, -0.0301, +0.0432, +0.3390, +0.7537, +0.1649, -0.0128, -0.1374, +0.3793, +1.0430, +0.8043, -0.9001, +0.4334, -0.1243, +1.2373, +0.1890, +0.3333, -0.0520, +0.1654, +0.2521, -0.0168, +0.8439, -0.6960, +0.1884, +0.0991, +0.5242, -0.6837, +0.6844, -0.2593, -0.3298, +0.2212, +0.0281, +0.2608, +0.6527],
[ -0.9350, -0.2122, +0.0162, +0.5306, -0.2914, -0.8573, +0.2552, +0.7069, +0.7862, -0.0315, -1.0844, +0.2707, +0.5102, -1.1359, +0.3066, +0.0357, +0.1833, -0.1946, +0.0948, +0.6685, -0.6101, +0.4774, -0.3017, +0.3823, -0.2835, -0.6760, +1.2963, +0.4466, -0.7132, -0.9109, -0.0589, -0.8726, +0.6972, -0.2256, -0.0286, +0.4646, -0.5113, -0.1692, +0.7638, +0.2274, -0.5734, +0.7430, +0.9680, +0.7809, -0.2457, -0.4952, +0.0197, -0.6428, +0.2367, -0.5887, -0.5167, +0.2299, -0.5853, -0.4101, +0.9042, +0.0913, +0.5774, +0.2756, +0.2436, -0.6068, -0.2232, -0.1415, -0.5094, -0.1012],
[ +0.0983, -0.3266, +0.2611, +0.0664, +0.6222, +0.0773, -0.2516, -0.4416, -0.3770, +0.0535, +0.3391, -0.7475, +0.5874, -0.0405, -0.2058, -0.5957, +0.2659, -0.8477, -0.5814, -0.0494, -0.1678, +0.2650, -0.4039, +0.1414, -0.6635, +0.0447, +0.2932, +0.1167, +0.1195, +0.0669, -0.4223, +0.1196, +0.0553, -0.7123, -0.4011, +0.3557, -0.4503, +0.7047, -0.4471, +0.0807, +0.3926, -0.1427, +0.4355, -0.3678, +0.3453, +0.1597, -0.3076, +0.4689, +0.3128, -0.7050, +0.6505, +0.3427, +0.1981, +0.1190, +0.2554, +0.8283, +0.1647, -0.4257, +0.1481, +0.4361, -0.5497, -0.6114, -0.0138, +0.0932],
[ +0.1866, +0.6408, -1.8201, +1.0946, +0.7742, -0.7651, +0.1082, +0.6842, +0.3794, +0.3547, -0.8172, -0.0921, -0.6736, +1.0251, -0.9618, -0.6869, +1.8465, +0.2425, +0.7910, +1.0009, -0.8031, +1.6697, -0.8962, +0.1873, +0.4960, -0.6812, +0.6860, +1.1932, -0.7019, +0.4028, +0.4841, +0.6497, +1.6490, -0.5464, +0.7060, +1.8087, -0.6118, -0.7955, -0.3797, -1.2048, +1.2356, -0.6141, +1.2502, +0.5641, -0.1019, -1.7516, -0.1134, -0.6719, +1.5014, -0.2718, -0.5933, +0.1714, -1.3590, -0.3656, +1.0083, -0.8511, -0.5597, -0.4446, -1.7158, -0.0851, +0.3089, +0.0967, -1.0121, +0.3048],
[ +0.3329, +0.5382, +0.1585, +0.8205, +0.5510, +0.2796, -0.7120, +0.3434, +0.2931, +1.2275, +0.4191, -0.6828, -0.5091, +0.8408, -0.3101, -0.5183, +0.2651, +0.2073, -0.1383, +0.6539, -0.2167, +0.7798, -0.5690, +0.3750, +0.4358, +0.6537, -0.2202, -0.0563, +0.6605, +0.4599, -0.5327, +0.6610, +0.8387, +0.1887, -0.2593, +0.7904, -0.3567, +0.4121, +0.4378, -0.2935, +0.1291, +0.0021, -0.3416, -0.5920, -0.2895, -0.4610, +0.7380, -0.6322, +0.6738, -0.1378, -0.3304, -0.2894, -0.3582, -0.8311, +0.2660, -0.2079, -0.1765, -0.6825, -0.1754, -0.4455, +0.7202, -0.8177, -0.9900, -0.7425]
# yapf: disable
weights_dense1_w = np.array(
[[
+0.8621, +0.3260, +0.0986, -0.1225, +0.2038, -0.8051, -0.7498, +0.1905,
-0.3418, +0.5002, -0.1093, +0.0285, +0.3480, -0.1596, -0.1781, +0.3643,
-0.4283, -0.3715, -0.1571, +0.3531, +0.0934, -0.2215, -0.3085, +0.9581,
+0.2485, -0.6232, -0.3175, +0.9771, +0.3651, -0.8850, -0.4212, -0.0301,
+0.0432, +0.3390, +0.7537, +0.1649, -0.0128, -0.1374, +0.3793, +1.0430,
+0.8043, -0.9001, +0.4334, -0.1243, +1.2373, +0.1890, +0.3333, -0.0520,
+0.1654, +0.2521, -0.0168, +0.8439, -0.6960, +0.1884, +0.0991, +0.5242,
-0.6837, +0.6844, -0.2593, -0.3298, +0.2212, +0.0281, +0.2608, +0.6527
],
[
-0.9350, -0.2122, +0.0162, +0.5306, -0.2914, -0.8573, +0.2552,
+0.7069, +0.7862, -0.0315, -1.0844, +0.2707, +0.5102, -1.1359,
+0.3066, +0.0357, +0.1833, -0.1946, +0.0948, +0.6685, -0.6101,
+0.4774, -0.3017, +0.3823, -0.2835, -0.6760, +1.2963, +0.4466,
-0.7132, -0.9109, -0.0589, -0.8726, +0.6972, -0.2256, -0.0286,
+0.4646, -0.5113, -0.1692, +0.7638, +0.2274, -0.5734, +0.7430,
+0.9680, +0.7809, -0.2457, -0.4952, +0.0197, -0.6428, +0.2367,
-0.5887, -0.5167, +0.2299, -0.5853, -0.4101, +0.9042, +0.0913,
+0.5774, +0.2756, +0.2436, -0.6068, -0.2232, -0.1415, -0.5094, -0.1012
],
[
+0.0983, -0.3266, +0.2611, +0.0664, +0.6222, +0.0773, -0.2516,
-0.4416, -0.3770, +0.0535, +0.3391, -0.7475, +0.5874, -0.0405,
-0.2058, -0.5957, +0.2659, -0.8477, -0.5814, -0.0494, -0.1678,
+0.2650, -0.4039, +0.1414, -0.6635, +0.0447, +0.2932, +0.1167,
+0.1195, +0.0669, -0.4223, +0.1196, +0.0553, -0.7123, -0.4011,
+0.3557, -0.4503, +0.7047, -0.4471, +0.0807, +0.3926, -0.1427,
+0.4355, -0.3678, +0.3453, +0.1597, -0.3076, +0.4689, +0.3128,
-0.7050, +0.6505, +0.3427, +0.1981, +0.1190, +0.2554, +0.8283,
+0.1647, -0.4257, +0.1481, +0.4361, -0.5497, -0.6114, -0.0138, +0.0932
],
[
+0.1866, +0.6408, -1.8201, +1.0946, +0.7742, -0.7651, +0.1082,
+0.6842, +0.3794, +0.3547, -0.8172, -0.0921, -0.6736, +1.0251,
-0.9618, -0.6869, +1.8465, +0.2425, +0.7910, +1.0009, -0.8031,
+1.6697, -0.8962, +0.1873, +0.4960, -0.6812, +0.6860, +1.1932,
-0.7019, +0.4028, +0.4841, +0.6497, +1.6490, -0.5464, +0.7060,
+1.8087, -0.6118, -0.7955, -0.3797, -1.2048, +1.2356, -0.6141,
+1.2502, +0.5641, -0.1019, -1.7516, -0.1134, -0.6719, +1.5014,
-0.2718, -0.5933, +0.1714, -1.3590, -0.3656, +1.0083, -0.8511,
-0.5597, -0.4446, -1.7158, -0.0851, +0.3089, +0.0967, -1.0121, +0.3048
],
[
+0.3329, +0.5382, +0.1585, +0.8205, +0.5510, +0.2796, -0.7120,
+0.3434, +0.2931, +1.2275, +0.4191, -0.6828, -0.5091, +0.8408,
-0.3101, -0.5183, +0.2651, +0.2073, -0.1383, +0.6539, -0.2167,
+0.7798, -0.5690, +0.3750, +0.4358, +0.6537, -0.2202, -0.0563,
+0.6605, +0.4599, -0.5327, +0.6610, +0.8387, +0.1887, -0.2593,
+0.7904, -0.3567, +0.4121, +0.4378, -0.2935, +0.1291, +0.0021,
-0.3416, -0.5920, -0.2895, -0.4610, +0.7380, -0.6322, +0.6738,
-0.1378, -0.3304, -0.2894, -0.3582, -0.8311, +0.2660, -0.2079,
-0.1765, -0.6825, -0.1754, -0.4455, +0.7202, -0.8177, -0.9900, -0.7425
]])
weights_dense1_b = np.array([
+0.0009, -0.2179, -0.0299, +0.2069, -0.0099, +0.0907, +0.0271, +0.1957,
+0.0185, +0.1671, -0.0699, -0.0332, -0.0244, +0.0022, +0.1877, -0.0801,
+0.0235, -0.0097, -0.0088, +0.1961, -0.1055, +0.0605, -0.0913, +0.0884,
-0.0638, +0.0229, -0.1101, +0.1966, -0.0042, +0.0221, -0.0966, +0.1554,
+0.1623, -0.0454, +0.1068, +0.0114, +0.0544, +0.0201, +0.0257, +0.0637,
+0.0761, +0.2120, +0.0225, +0.2023, -0.0931, +0.0585, -0.2253, -0.0302,
+0.0682, +0.0000, -0.1215, -0.1105, +0.1376, +0.0583, -0.1706, -0.0262,
-0.0897, +0.0728, +0.0787, +0.0912, -0.0964, -0.0959, -0.0195, +0.0232
])
weights_dense1_b = np.array([ +0.0009, -0.2179, -0.0299, +0.2069, -0.0099, +0.0907, +0.0271, +0.1957, +0.0185, +0.1671, -0.0699, -0.0332, -0.0244, +0.0022, +0.1877, -0.0801, +0.0235, -0.0097, -0.0088, +0.1961, -0.1055, +0.0605, -0.0913, +0.0884, -0.0638, +0.0229, -0.1101, +0.1966, -0.0042, +0.0221, -0.0966, +0.1554, +0.1623, -0.0454, +0.1068, +0.0114, +0.0544, +0.0201, +0.0257, +0.0637, +0.0761, +0.2120, +0.0225, +0.2023, -0.0931, +0.0585, -0.2253, -0.0302, +0.0682, +0.0000, -0.1215, -0.1105, +0.1376, +0.0583, -0.1706, -0.0262, -0.0897, +0.0728, +0.0787, +0.0912, -0.0964, -0.0959, -0.0195, +0.0232])
weights_dense2_w = np.array([
[ +0.0089, +0.2241, -0.0391, +0.1459, -0.0854, -0.0878, +0.2829, -0.1620, -0.1694, -0.5211, +0.0155, -0.1298, -0.0629, +0.1074, +0.0150, -0.3583, +0.0427, +0.1813, +0.2140, -0.4230, +0.1577, +0.1223, -0.0096, +0.0183, -0.1038, -0.5612, -0.0614, -0.0820, -0.0057, -0.2471, +0.0355, -0.1525],
[ +0.1555, -0.2934, +0.2690, -0.3218, +0.0101, -0.1188, -0.1798, -0.1405, +0.2701, -0.0972, +0.2338, -0.0122, -0.2254, -0.3225, -0.0268, -0.0829, +0.4085, +0.0691, -0.1448, -0.0429, -0.2750, -0.2479, +0.0396, +0.0427, +0.0205, -0.1462, -0.1481, +0.1365, -0.0903, +0.0094, +0.3665, +0.1163],
[ +0.0119, -0.3100, +0.1201, -0.2257, +0.1246, -0.1335, -0.3369, -0.0408, +0.3145, +0.2030, +0.1506, +0.0899, -0.1192, -0.2429, +0.0356, +0.0634, -0.0706, +0.1119, -0.0402, +0.1011, +0.1281, +0.4318, -0.4644, +0.0039, +0.0932, -0.0521, -0.1528, +0.1946, -0.0921, -0.0646, -0.0241, +0.1598],
[ -0.1007, +0.3939, -0.2066, +0.0752, -0.1709, -0.0286, +0.0196, +0.1853, -0.3619, -0.0449, +0.0334, -0.2673, +0.0640, +0.3055, -0.1184, -0.4550, +0.0951, -0.2168, +0.1502, -0.4816, +0.1392, -0.3708, -0.0849, -0.4331, -0.0800, -0.0967, +0.1334, -0.3169, -0.0004, -0.3002, -0.0841, -0.1763],
[ -0.0492, +0.0308, +0.0824, +0.0568, -0.0038, +0.3196, +0.5089, +0.0391, -0.1373, -0.1579, +0.0219, -0.2990, -0.0113, -0.2136, -0.0240, +0.1241, -0.1723, -0.0064, -0.0213, -0.2213, -0.0996, -0.0333, -0.4110, -0.2074, +0.0427, +0.0323, -0.0920, -0.1846, -0.1037, -0.0381, -0.0763, +0.0875],
[ +0.0965, -0.1536, -0.0270, -0.0834, +0.0270, +0.0908, -0.0257, -0.1284, +0.1994, +0.2317, +0.0193, +0.0493, -0.0723, -0.2748, +0.0248, -0.0021, -0.0483, +0.0610, -0.0056, -0.0575, +0.0930, +0.0749, -0.2599, +0.0223, +0.0050, -0.0569, -0.6755, +0.2190, +0.0009, +0.1493, -0.1822, +0.0763],
[ -0.0435, +0.3829, -0.2358, +0.3554, -0.1800, +0.0008, -0.0282, -0.0139, -0.2745, -0.2293, -0.4456, +0.1709, +0.0687, -0.0696, -0.0877, -0.0978, -0.0620, -0.4380, +0.2052, -0.1479, +0.0971, -0.0031, +0.0783, -0.0749, -0.2695, -0.0151, -0.0066, +0.0592, -0.0088, -0.0507, -0.0167, -0.2891],
[ -0.1797, -0.1446, -0.0609, -0.2840, +0.1933, +0.0366, -0.3077, -0.0018, -0.1564, +0.0283, +0.1447, +0.2110, -0.0047, -0.2123, +0.0041, +0.0171, +0.2826, +0.1549, -0.1211, +0.1360, +0.1473, +0.1541, -0.1583, +0.0955, -0.1047, +0.0530, +0.0667, +0.1454, -0.0860, +0.0602, +0.1970, +0.0716],
[ +0.0119, +0.1858, -0.1746, +0.0911, -0.0948, -0.0898, -0.0680, -0.2266, -0.1098, +0.0161, +0.0265, +0.1100, -0.3467, -0.0128, -0.2249, +0.0344, +0.1421, -0.1222, -0.0196, -0.1188, +0.0428, -0.2318, +0.0998, +0.1017, +0.0298, -0.1391, +0.1229, +0.1193, +0.0565, +0.1296, +0.0939, -0.0234],
[ +0.1817, +0.2432, -0.2712, +0.0668, -0.1836, +0.0232, -0.0793, +0.0161, -0.1585, -0.3731, -0.0243, -0.1066, +0.0928, -0.0499, -0.0692, -0.3354, +0.0754, +0.0468, -0.2522, -0.7501, +0.0235, -0.5134, -0.3031, -0.1907, -0.2166, -0.1713, -0.0422, +0.0831, +0.0664, -0.0462, +0.1627, -0.4927],
[ -0.0342, +0.2310, +0.2736, -0.0703, +0.1941, -0.0428, -0.0868, -0.2146, +0.1371, +0.0117, +0.0218, +0.0133, -0.0416, +0.1012, +0.1689, +0.3113, +0.0199, +0.1176, +0.0256, +0.0907, +0.0622, +0.3312, -0.0225, -0.0187, +0.2089, +0.1381, -0.2949, +0.1525, -0.0514, -0.1416, -0.0381, -0.0133],
[ -0.0885, +0.3841, -0.3811, +0.1388, -0.1801, -0.0434, +0.1371, -0.0393, +0.2549, -0.4207, -0.2308, +0.0187, -0.0975, +0.2137, -0.0840, -0.0491, +0.0424, +0.0060, +0.1007, +0.0315, +0.3005, +0.0501, +0.0516, -0.0521, -0.0100, +0.0984, +0.3092, +0.0031, -0.0380, +0.2344, +0.0808, -0.0694],
[ -0.0631, +0.0290, +0.1733, -0.0555, +0.1311, -0.0812, +0.1056, -0.1663, -0.1272, +0.2717, +0.0247, +0.0730, -0.3714, +0.0042, -0.0490, +0.0222, -0.0429, -0.1618, +0.1476, +0.1699, -0.1660, +0.1571, -0.0225, +0.1582, +0.1622, -0.0721, -0.1198, +0.1388, -0.1661, +0.0103, -0.1386, +0.0883],
[ +0.0306, +0.1041, -0.2540, +0.0423, +0.1098, -0.0204, +0.1478, +0.1917, +0.1102, +0.0045, -0.0263, +0.0818, -0.0245, -0.0047, -0.2407, -0.6658, +0.0834, +0.0400, +0.1785, -0.5141, +0.3379, -0.5638, -0.0012, -0.2549, -0.4172, -0.2134, -0.3793, -0.0736, -0.3442, +0.1044, -0.0489, -0.2967],
[ -0.0446, -0.1153, -0.0839, +0.0948, +0.3570, -0.0520, -0.1016, -0.0265, +0.4342, +0.2325, +0.1763, -0.2663, -0.0676, -0.0759, +0.0654, +0.2983, +0.1185, -0.0233, -0.5232, +0.1075, -0.3284, +0.2703, +0.2164, +0.0092, +0.2988, +0.1956, +0.0582, +0.3342, +0.0949, -0.1936, -0.0465, +0.4223],
[ +0.0737, -0.0069, -0.1301, +0.3047, -0.2603, +0.0369, -0.2049, +0.0378, -0.1846, -0.3474, -0.1353, +0.0965, +0.0956, -0.0692, -0.0440, -0.1767, -0.1616, -0.2183, +0.1853, -0.0618, +0.1210, -0.2178, +0.1066, -0.3849, -0.2628, +0.1444, +0.2814, -0.2963, +0.0673, +0.0983, +0.0442, +0.0020],
[ -0.0978, +0.2645, -0.3750, +0.2824, -0.3906, -0.0070, +0.1920, +0.0911, -0.0510, -0.1050, -0.2411, -0.2135, +0.0784, +0.3348, -0.0396, -0.4209, -0.0686, -0.2212, +0.3039, -0.4649, -0.0692, -0.5387, +0.0479, -0.4205, -0.2557, -0.1031, +0.1378, -0.3875, -0.1900, -0.0253, +0.1212, -0.4374],
[ -0.1067, +0.1545, +0.2016, -0.0620, -0.1419, -0.0661, -0.1224, -0.0560, +0.1045, -0.2062, -0.2551, +0.2440, -0.1116, +0.1544, -0.2324, +0.0999, -0.1832, -0.1226, -0.1774, +0.0629, -0.1170, -0.1375, +0.0839, +0.2029, +0.0551, +0.0359, +0.0967, +0.2290, -0.0312, -0.1228, +0.2831, +0.1785],
[ -0.1420, +0.1163, +0.0488, -0.0011, -0.1311, -0.1558, -0.0766, -0.0088, +0.1877, -0.1547, +0.1304, +0.0347, +0.1132, +0.2750, -0.0574, +0.0080, -0.2256, -0.0951, +0.1987, +0.2256, +0.0270, -0.0155, +0.0636, +0.0372, +0.2483, -0.1469, -0.2010, -0.0994, -0.1731, +0.0224, +0.0085, -0.1891],
[ +0.1037, +0.0015, -0.1525, -0.0444, -0.3130, -0.0318, +0.2370, -0.1492, -0.4707, -0.0023, +0.0884, +0.1722, -0.0421, +0.0858, -0.1036, -0.5701, +0.1249, -0.2643, -0.0203, -0.1380, +0.0973, -0.2060, +0.1806, +0.3054, -0.6548, -0.3282, -0.2969, -0.3984, -0.0448, -0.1802, +0.3282, -0.1891],
[ -0.1116, +0.3646, -0.0542, +0.3672, -0.4207, +0.2700, +0.3827, -0.0599, -0.3415, -0.2832, -0.0345, +0.1987, +0.0669, +0.1301, -0.3806, -0.2981, -0.1917, -0.2028, +0.1687, -0.2010, +0.3607, -0.0199, +0.2971, +0.0390, +0.0895, -0.3088, +0.0169, -0.1333, +0.0738, +0.2161, -0.1207, -0.3352],
[ -0.0134, +0.3853, -0.2106, +0.1996, -0.2277, -0.0971, +0.0917, -0.2901, -0.2493, +0.0295, -0.1438, -0.1902, -0.0074, +0.2240, -0.0277, -0.4374, +0.0749, -0.1779, +0.2687, -0.4093, -0.0042, -0.5023, -0.1169, -0.3157, +0.0061, +0.0270, +0.0204, -0.4626, -0.1717, -0.2126, +0.1335, -0.5028],
[ -0.0813, +0.1958, -0.4203, +0.3027, -0.3896, -0.1201, -0.0383, -0.1807, -0.4834, -0.3672, -0.3664, +0.2401, -0.0114, -0.0852, -0.2220, -0.1953, +0.0773, -0.0048, +0.1560, -0.1524, +0.0772, -0.2740, +0.1346, -0.3171, -0.0648, +0.1633, +0.2050, -0.1560, +0.0270, +0.3009, -0.2798, -0.0756],
[ -0.1754, +0.1428, +0.2527, -0.2624, -0.1126, -0.0014, +0.1030, -0.2716, -0.2678, -0.0268, +0.0982, -0.0385, -0.0628, -0.0768, -0.2531, +0.2935, -0.0661, +0.0778, -0.1184, +0.0070, -0.1331, -0.1174, -0.1338, -0.1601, -0.0357, -0.1964, -0.0550, -0.1151, +0.2369, +0.1578, -0.0826, -0.1985],
[ -0.1724, -0.0328, +0.0090, -0.0564, +0.0876, -0.0607, +0.0060, -0.2330, +0.1137, -0.0771, -0.0774, +0.0727, -0.2037, +0.1521, +0.0666, +0.0258, -0.2189, -0.1417, +0.0276, -0.0387, -0.0747, -0.0214, -0.0793, -0.0520, +0.0918, -0.1276, -0.0877, +0.0309, -0.0630, -0.0149, -0.0197, -0.1755],
[ +0.1471, -0.1542, +0.1202, -0.2846, +0.1209, -0.0383, -0.2689, -0.0442, -0.1086, +0.3428, +0.0120, +0.0473, +0.0320, -0.2629, -0.0904, -0.3732, -0.2179, +0.2540, -0.1725, -0.4163, -0.0333, +0.0934, -0.3123, -0.1123, -0.2196, +0.1580, -0.6386, +0.0650, -0.0473, +0.0521, +0.0061, -0.2745],
[ +0.0064, -0.1054, -0.2054, -0.1706, +0.1626, +0.0895, +0.0571, -0.2639, +0.0269, +0.1943, +0.0687, -0.1510, -0.1987, +0.0784, -0.1774, -0.0242, +0.0519, -0.3330, +0.0364, +0.1868, -0.3204, +0.1106, +0.0456, -0.1627, -0.2792, +0.0017, +0.2943, +0.0481, -0.1523, -0.1656, -0.0222, -0.0239],
[ +0.0853, +0.2513, -0.1716, +0.0164, -0.1375, -0.0870, +0.2430, +0.2161, -0.4489, -0.3427, +0.0341, -0.0022, -0.1488, +0.2685, -0.2290, -0.2439, +0.1216, -0.1475, -0.0332, -0.1282, -0.1603, -0.1076, -0.1279, -0.1439, -0.2784, -0.4271, +0.1286, -0.1134, -0.1994, -0.1031, -0.0210, -0.2327],
[ +0.1303, -0.0463, +0.1797, -0.0939, +0.2427, -0.0791, -0.0735, -0.2248, +0.1545, -0.1325, -0.1812, -0.0896, +0.0695, +0.0225, -0.1880, +0.1619, -0.0468, +0.0904, +0.1570, -0.0206, +0.1266, -0.0148, +0.0305, +0.2494, +0.1687, -0.0774, -0.2693, +0.0449, +0.0040, -0.1319, +0.1513, -0.0410],
[ +0.0545, +0.0586, -0.0087, -0.1021, -0.1756, -0.0722, +0.0678, +0.0310, -0.1490, -0.2823, +0.1335, -0.0038, +0.0660, +0.0696, -0.2747, -0.3360, +0.1061, +0.3080, +0.1201, -0.3870, +0.2960, -0.4409, -0.0295, +0.0854, -0.0908, +0.1224, -0.4637, -0.4016, +0.0420, +0.0505, +0.0364, -0.2983],
[ -0.1218, +0.2787, -0.1838, -0.0315, -0.1590, -0.2840, +0.2845, +0.0601, -0.1741, -0.2363, -0.3620, -0.1355, +0.0943, +0.1343, -0.0346, -0.1135, +0.0327, -0.2982, +0.1805, -0.1483, +0.1698, -0.1056, -0.0257, +0.0580, -0.1921, +0.0863, +0.1439, -0.1360, +0.0468, +0.2411, -0.1872, +0.0329],
[ +0.0068, +0.1272, +0.0108, +0.0178, +0.2308, +0.0207, -0.0050, +0.0127, +0.1008, -0.2972, -0.2233, -0.1369, +0.0797, +0.0023, -0.0782, -0.4778, +0.1916, +0.1325, +0.0110, -0.2083, +0.2786, -0.2724, -0.1214, +0.0510, -0.1068, -0.1982, -0.4602, -0.1082, -0.1563, -0.0689, -0.0913, +0.0983],
[ +0.1631, +0.1356, -0.1882, +0.2125, -0.4817, -0.1368, +0.1216, -0.1032, -0.4494, -0.2093, -0.0110, +0.0402, -0.0097, +0.1575, -0.2447, -0.8683, +0.1860, -0.4305, +0.1405, -0.3244, +0.1927, -0.5331, +0.0910, -0.1750, -0.2639, -0.3461, -0.0655, -0.4643, -0.0272, +0.0600, +0.1538, -0.3951],
[ +0.0750, +0.0031, -0.1113, +0.0419, -0.0726, +0.1712, +0.1273, -0.0844, +0.0187, -0.1579, +0.0365, +0.1953, +0.0259, +0.1069, +0.1584, +0.0159, +0.1700, -0.0276, +0.0061, -0.1753, -0.0827, -0.0493, +0.0756, -0.1169, +0.0177, -0.2200, -0.0495, -0.0934, +0.1999, -0.0962, -0.0035, +0.1083],
[ -0.0754, -0.1933, +0.1219, -0.3622, -0.2560, +0.0829, -0.3323, +0.0923, -0.1712, +0.0494, +0.1063, +0.3118, +0.0088, -0.3756, -0.0977, +0.0160, -0.0817, +0.1595, -0.3452, +0.2652, +0.2646, +0.2833, -0.3530, +0.0805, -0.1736, +0.0675, -0.1320, -0.3568, +0.1824, -0.0068, +0.0391, -0.3348],
[ +0.0661, +0.1602, -0.0509, +0.0562, -0.1738, +0.0114, -0.0268, -0.0354, -0.2069, -0.0250, -0.1061, -0.1695, -0.0719, +0.2797, -0.2477, -0.2539, +0.1287, -0.2037, +0.2556, -0.1008, +0.1943, -0.1660, +0.2728, -0.2338, -0.0806, -0.2346, +0.0449, -0.4673, -0.0362, -0.1172, +0.1695, -0.2252],
[ +0.0348, -0.2188, +0.0041, -0.1818, +0.3175, -0.0947, -0.2779, -0.0764, +0.2407, -0.1541, +0.2586, -0.1852, -0.1379, -0.3336, +0.1402, -0.0446, +0.0584, +0.0994, -0.3633, +0.0636, -0.0156, -0.0767, -0.2649, +0.0149, +0.2484, +0.2916, +0.1928, -0.0036, +0.0696, -0.0935, +0.2752, +0.0187],
[ -0.2666, +0.0507, -0.1783, +0.2308, +0.3974, -0.0719, +0.0276, -0.0048, +0.1177, +0.0816, -0.2346, -0.2762, +0.1167, +0.0719, -0.1303, -0.0892, +0.0177, +0.0072, +0.0965, +0.2305, +0.0988, +0.1532, -0.1653, +0.0692, -0.0419, -0.1874, -0.0896, +0.0014, +0.0375, -0.0905, -0.3757, +0.3573],
[ +0.4116, -0.2717, +0.2356, -0.1943, +0.0575, +0.0379, -0.0606, -0.0819, +0.1179, +0.2377, -0.1506, +0.1710, +0.0912, -0.2922, +0.0898, +0.1814, +0.1221, +0.1917, -0.3906, +0.1684, +0.1638, +0.2434, -0.1656, +0.1352, +0.0744, -0.0942, -0.2128, +0.0767, +0.0628, +0.1426, +0.3458, -0.0437],
[ -0.1387, -0.5340, +0.2895, -0.5476, +0.5888, +0.1435, -0.4898, +0.0061, +0.6167, +0.1024, +0.1127, +0.2197, +0.0206, -0.4723, +0.1195, +0.6172, +0.0276, +0.3961, -0.5498, +0.4008, -0.2163, +0.3337, -0.2608, +0.1666, +0.3415, +0.0077, -0.1649, +0.2619, -0.1937, -0.1043, +0.1770, +0.4285],
[ -0.0167, +0.0725, +0.1501, +0.0806, -0.0904, -0.2287, +0.1906, -0.0706, -0.0861, -0.1585, -0.1175, -0.0603, -0.0193, +0.4876, -0.1954, -0.0463, -0.1083, +0.1297, -0.0301, +0.0312, +0.0755, +0.0648, -0.4867, -0.0645, +0.0074, +0.0624, -0.1972, -0.1996, -0.1207, -0.1015, +0.0720, +0.0260],
[ +0.0007, -0.1637, +0.1202, -0.1045, +0.2969, +0.1975, -0.1374, +0.1684, +0.0790, +0.2108, -0.0220, +0.0773, +0.0046, +0.0205, -0.1746, +0.3445, +0.0773, +0.0005, +0.0251, +0.3337, -0.3365, +0.3956, -0.2011, +0.2489, +0.1875, +0.0282, -0.4611, +0.2249, +0.0182, -0.1252, -0.1899, +0.1563],
[ -0.0142, +0.0174, +0.1562, +0.0763, +0.1314, -0.0686, +0.3657, -0.0132, -0.0737, +0.0247, +0.0431, -0.2967, +0.0002, +0.2221, +0.1011, +0.1039, -0.0503, -0.3926, +0.1014, -0.1349, -0.1005, +0.1254, +0.0250, -0.1482, -0.2554, +0.1027, +0.1661, -0.1071, -0.0521, -0.0568, +0.1508, +0.0668],
[ -0.1106, +0.1260, -0.3472, +0.2769, +0.0344, -0.0668, +0.2888, +0.1583, -0.2782, -0.1161, -0.2939, +0.1309, -0.0010, +0.4387, +0.1623, -0.2627, -0.1011, -0.3530, +0.0604, -0.2499, +0.2736, -0.2715, +0.2004, -0.5407, -0.4915, -0.1778, +0.1274, -0.1071, -0.0170, -0.1190, -0.1540, -0.0364],
[ -0.1767, +0.2753, +0.2479, -0.0753, -0.2057, -0.2379, -0.0411, -0.0945, -0.1757, +0.1752, +0.1322, +0.0548, -0.0980, +0.1753, -0.0510, +0.2050, -0.0246, +0.5660, -0.2124, +0.1708, -0.1779, +0.2125, -0.0143, +0.1992, +0.1330, -0.2561, -0.1304, +0.2212, -0.2898, +0.0983, -0.1803, +0.1087],
[ -0.0503, -0.3082, +0.1056, -0.1658, +0.3225, +0.0727, -0.4463, -0.0153, +0.0195, +0.0962, -0.0483, -0.0484, +0.2464, -0.5537, +0.1422, +0.1233, -0.1036, +0.0864, -0.2107, +0.1319, +0.2002, +0.3051, -0.2054, +0.3069, +0.2754, +0.1618, -0.0593, -0.0373, +0.2155, -0.1157, -0.1199, +0.2342],
[ -0.1789, -0.1216, +0.0442, -0.1111, +0.1411, -0.0572, -0.4238, +0.0134, -0.1511, +0.0625, -0.0139, -0.2257, -0.1143, -0.2315, +0.3597, -0.1227, +0.0240, +0.2061, -0.0474, +0.0561, -0.2806, -0.0939, -0.0608, +0.1852, -0.0210, -0.3526, +0.0992, -0.3513, -0.0787, +0.1074, -0.0475, -0.1759],
[ -0.0510, +0.0215, +0.1585, -0.0757, +0.0357, -0.0553, -0.1151, -0.1353, +0.1000, -0.2570, -0.0664, -0.1762, +0.0430, -0.0365, +0.0198, +0.1154, -0.5763, +0.0393, -0.0443, +0.0504, +0.0482, +0.1528, +0.1955, -0.0493, +0.2712, -0.0688, -0.1406, +0.1479, +0.0204, +0.0838, -0.2282, +0.2307],
[ -0.1682, -0.0467, -0.0758, +0.3832, -0.1471, +0.0612, +0.3901, +0.1065, +0.2009, -0.3104, -0.2998, -0.3175, -0.0722, +0.1549, -0.2472, -0.1729, +0.0841, -0.1691, +0.1407, -0.1969, -0.0491, +0.0103, +0.1179, -0.1327, -0.1275, +0.0368, +0.0953, -0.1660, -0.0245, -0.3851, +0.1340, -0.1417],
[ +0.0114, -0.0822, -0.2575, -0.0169, +0.1292, +0.0791, -0.0803, +0.0061, -0.0445, -0.2228, +0.0215, +0.1863, +0.2645, -0.0295, +0.0756, -0.2138, -0.1607, +0.0527, +0.0592, -0.1770, -0.0982, -0.1096, +0.0925, -0.0325, +0.0047, +0.1512, +0.0663, -0.1348, +0.0084, -0.1352, +0.0189, +0.1428],
[ +0.0052, +0.1124, +0.1083, +0.1163, +0.0787, +0.0839, +0.0839, +0.0506, +0.0537, +0.1066, +0.1034, -0.1299, -0.1434, +0.0188, +0.1823, +0.1403, -0.4525, +0.0949, -0.0981, +0.0722, -0.1085, -0.2382, +0.1028, +0.0664, +0.1976, +0.1073, -0.2736, +0.2433, -0.3520, -0.0386, -0.2319, -0.0724],
[ -0.3279, -0.1491, -0.1409, +0.2056, -0.1464, +0.0543, +0.1842, +0.1104, -0.2819, +0.0769, -0.1159, +0.0228, -0.0988, +0.0026, -0.1204, -0.0780, -0.2018, +0.1755, +0.1574, +0.0222, +0.1662, -0.2193, -0.0718, +0.0010, -0.0123, -0.0120, +0.2587, +0.0358, -0.1435, +0.0017, -0.2620, +0.0965],
[ -0.1144, -0.1048, +0.2211, -0.0726, -0.1721, -0.2475, -0.3226, +0.0120, +0.0908, +0.0375, -0.0974, +0.0490, -0.1180, -0.3155, -0.2565, -0.0092, -0.4400, +0.2027, -0.1459, +0.1043, +0.0771, +0.0825, -0.1541, -0.0713, -0.0437, -0.0249, -0.1757, -0.1115, +0.0457, +0.1141, -0.2567, +0.0405],
[ +0.0587, +0.1083, +0.0729, +0.2131, -0.1586, +0.2208, -0.1576, -0.0811, -0.0467, +0.2201, -0.1082, -0.2077, +0.0030, -0.1222, +0.2023, +0.1155, -0.1616, +0.0105, +0.1167, -0.1257, +0.4859, +0.1337, -0.0169, -0.0163, +0.2076, +0.0367, -0.0050, -0.2590, -0.0800, -0.2192, +0.0938, +0.1126],
[ -0.3834, -0.0180, -0.2714, +0.0303, +0.0784, -0.1242, +0.1105, +0.0237, -0.0085, +0.2615, +0.0189, -0.3734, +0.0088, +0.1211, -0.0838, +0.0067, +0.1956, +0.1577, +0.2132, -0.0044, -0.2748, +0.1417, +0.0201, +0.1002, +0.0311, -0.0052, -0.1695, -0.0750, +0.2200, -0.2848, +0.0438, -0.0442],
[ -0.1496, +0.1258, +0.1903, -0.0337, -0.1470, -0.0530, +0.0519, -0.0037, +0.0342, +0.0404, -0.0950, -0.0840, +0.1083, -0.0488, +0.0427, +0.1454, +0.0851, -0.0203, -0.2354, +0.1562, +0.1899, +0.3145, +0.0013, +0.1608, +0.0126, +0.2080, -0.1409, -0.0746, +0.0580, -0.1045, -0.1753, +0.1225],
[ -0.0349, +0.1354, -0.1052, -0.1189, +0.0288, -0.0257, +0.0813, -0.1559, +0.1267, +0.0664, +0.2004, +0.1232, +0.2557, -0.1729, -0.0666, +0.1644, +0.1043, -0.2672, +0.0537, +0.0566, -0.1738, +0.0036, +0.1406, -0.0574, -0.0556, +0.3336, -0.0328, -0.1624, +0.0132, -0.0627, -0.1523, +0.0552],
[ -0.3105, +0.2681, -0.5462, +0.2785, -0.2453, -0.2965, +0.1436, +0.0786, -0.3242, -0.3518, +0.1025, +0.2219, -0.1324, +0.1681, +0.0701, -0.0938, +0.1574, -0.5157, +0.3574, -0.1100, +0.2647, -0.1698, +0.2684, -0.3876, -0.6240, -0.1013, +0.2920, -0.3569, -0.0008, +0.0974, +0.1444, -0.3349],
[ +0.0848, -0.1191, +0.2283, +0.0922, +0.2880, -0.1747, -0.4457, +0.1013, +0.2494, +0.1487, +0.1013, -0.0403, -0.0236, -0.1965, -0.0655, +0.0818, +0.0493, -0.0605, -0.1889, +0.1772, -0.2826, +0.2783, -0.1653, +0.3505, +0.4192, -0.1048, -0.1459, +0.0779, -0.0154, -0.1573, -0.1254, -0.1118],
[ -0.1817, +0.0719, +0.1352, +0.3208, +0.2142, -0.1149, +0.0020, +0.1617, +0.1055, +0.0395, -0.1802, -0.0631, -0.3172, +0.1971, +0.0197, +0.1271, -0.2375, -0.1849, -0.0134, +0.1223, +0.2566, +0.0311, -0.2746, +0.0278, +0.1233, +0.0167, -0.0363, +0.2146, -0.0466, +0.0732, -0.1490, +0.1040],
[ +0.1008, -0.1501, +0.0264, -0.4661, -0.0553, +0.0431, -0.3076, -0.0461, +0.1393, -0.1225, +0.2811, -0.0363, -0.0403, -0.3370, -0.0865, -0.1179, +0.1106, +0.2035, -0.2432, -0.0859, +0.0600, -0.0890, -0.0749, +0.0483, +0.0615, -0.0239, -0.4674, +0.0199, +0.0669, +0.1410, +0.1846, +0.2626],
[ +0.0663, +0.1486, -0.3928, +0.3257, -0.0316, +0.1377, +0.0418, +0.1921, -0.1616, -0.2265, -0.0917, +0.1582, -0.0537, +0.0295, -0.2264, -0.1921, -0.0225, +0.0928, +0.0747, -0.5268, -0.0068, -0.3328, +0.0437, -0.2361, -0.1408, -0.1234, +0.2216, -0.1372, -0.0499, +0.1940, +0.0098, -0.2953],
[ +0.0290, -0.1583, -0.0172, -0.1748, -0.0042, -0.0725, -0.2227, -0.1366, -0.1771, +0.1987, +0.3142, +0.1889, +0.0195, -0.5461, +0.0921, +0.1407, -0.1656, +0.1985, +0.0113, +0.2613, +0.2925, +0.1166, -0.1286, +0.1031, -0.2228, -0.0605, -0.2151, +0.2477, +0.1602, -0.0109, +0.0207, +0.1257],
[ +0.0630, -0.1688, +0.1662, -0.2327, +0.2832, +0.1350, -0.1658, +0.0504, -0.0502, +0.1736, +0.1002, -0.0051, -0.0311, -0.0628, +0.0039, +0.5085, -0.2191, +0.5105, -0.0927, +0.2833, -0.2828, +0.1078, +0.0406, -0.0392, -0.2372, +0.1508, +0.0556, +0.0313, +0.1296, +0.1315, -0.1143, +0.1632]
[
+0.0089, +0.2241, -0.0391, +0.1459, -0.0854, -0.0878, +0.2829, -0.1620,
-0.1694, -0.5211, +0.0155, -0.1298, -0.0629, +0.1074, +0.0150, -0.3583,
+0.0427, +0.1813, +0.2140, -0.4230, +0.1577, +0.1223, -0.0096, +0.0183,
-0.1038, -0.5612, -0.0614, -0.0820, -0.0057, -0.2471, +0.0355, -0.1525
],
[
+0.1555, -0.2934, +0.2690, -0.3218, +0.0101, -0.1188, -0.1798, -0.1405,
+0.2701, -0.0972, +0.2338, -0.0122, -0.2254, -0.3225, -0.0268, -0.0829,
+0.4085, +0.0691, -0.1448, -0.0429, -0.2750, -0.2479, +0.0396, +0.0427,
+0.0205, -0.1462, -0.1481, +0.1365, -0.0903, +0.0094, +0.3665, +0.1163
],
[
+0.0119, -0.3100, +0.1201, -0.2257, +0.1246, -0.1335, -0.3369, -0.0408,
+0.3145, +0.2030, +0.1506, +0.0899, -0.1192, -0.2429, +0.0356, +0.0634,
-0.0706, +0.1119, -0.0402, +0.1011, +0.1281, +0.4318, -0.4644, +0.0039,
+0.0932, -0.0521, -0.1528, +0.1946, -0.0921, -0.0646, -0.0241, +0.1598
],
[
-0.1007, +0.3939, -0.2066, +0.0752, -0.1709, -0.0286, +0.0196, +0.1853,
-0.3619, -0.0449, +0.0334, -0.2673, +0.0640, +0.3055, -0.1184, -0.4550,
+0.0951, -0.2168, +0.1502, -0.4816, +0.1392, -0.3708, -0.0849, -0.4331,
-0.0800, -0.0967, +0.1334, -0.3169, -0.0004, -0.3002, -0.0841, -0.1763
],
[
-0.0492, +0.0308, +0.0824, +0.0568, -0.0038, +0.3196, +0.5089, +0.0391,
-0.1373, -0.1579, +0.0219, -0.2990, -0.0113, -0.2136, -0.0240, +0.1241,
-0.1723, -0.0064, -0.0213, -0.2213, -0.0996, -0.0333, -0.4110, -0.2074,
+0.0427, +0.0323, -0.0920, -0.1846, -0.1037, -0.0381, -0.0763, +0.0875
],
[
+0.0965, -0.1536, -0.0270, -0.0834, +0.0270, +0.0908, -0.0257, -0.1284,
+0.1994, +0.2317, +0.0193, +0.0493, -0.0723, -0.2748, +0.0248, -0.0021,
-0.0483, +0.0610, -0.0056, -0.0575, +0.0930, +0.0749, -0.2599, +0.0223,
+0.0050, -0.0569, -0.6755, +0.2190, +0.0009, +0.1493, -0.1822, +0.0763
],
[
-0.0435, +0.3829, -0.2358, +0.3554, -0.1800, +0.0008, -0.0282, -0.0139,
-0.2745, -0.2293, -0.4456, +0.1709, +0.0687, -0.0696, -0.0877, -0.0978,
-0.0620, -0.4380, +0.2052, -0.1479, +0.0971, -0.0031, +0.0783, -0.0749,
-0.2695, -0.0151, -0.0066, +0.0592, -0.0088, -0.0507, -0.0167, -0.2891
],
[
-0.1797, -0.1446, -0.0609, -0.2840, +0.1933, +0.0366, -0.3077, -0.0018,
-0.1564, +0.0283, +0.1447, +0.2110, -0.0047, -0.2123, +0.0041, +0.0171,
+0.2826, +0.1549, -0.1211, +0.1360, +0.1473, +0.1541, -0.1583, +0.0955,
-0.1047, +0.0530, +0.0667, +0.1454, -0.0860, +0.0602, +0.1970, +0.0716
],
[
+0.0119, +0.1858, -0.1746, +0.0911, -0.0948, -0.0898, -0.0680, -0.2266,
-0.1098, +0.0161, +0.0265, +0.1100, -0.3467, -0.0128, -0.2249, +0.0344,
+0.1421, -0.1222, -0.0196, -0.1188, +0.0428, -0.2318, +0.0998, +0.1017,
+0.0298, -0.1391, +0.1229, +0.1193, +0.0565, +0.1296, +0.0939, -0.0234
],
[
+0.1817, +0.2432, -0.2712, +0.0668, -0.1836, +0.0232, -0.0793, +0.0161,
-0.1585, -0.3731, -0.0243, -0.1066, +0.0928, -0.0499, -0.0692, -0.3354,
+0.0754, +0.0468, -0.2522, -0.7501, +0.0235, -0.5134, -0.3031, -0.1907,
-0.2166, -0.1713, -0.0422, +0.0831, +0.0664, -0.0462, +0.1627, -0.4927
],
[
-0.0342, +0.2310, +0.2736, -0.0703, +0.1941, -0.0428, -0.0868, -0.2146,
+0.1371, +0.0117, +0.0218, +0.0133, -0.0416, +0.1012, +0.1689, +0.3113,
+0.0199, +0.1176, +0.0256, +0.0907, +0.0622, +0.3312, -0.0225, -0.0187,
+0.2089, +0.1381, -0.2949, +0.1525, -0.0514, -0.1416, -0.0381, -0.0133
],
[
-0.0885, +0.3841, -0.3811, +0.1388, -0.1801, -0.0434, +0.1371, -0.0393,
+0.2549, -0.4207, -0.2308, +0.0187, -0.0975, +0.2137, -0.0840, -0.0491,
+0.0424, +0.0060, +0.1007, +0.0315, +0.3005, +0.0501, +0.0516, -0.0521,
-0.0100, +0.0984, +0.3092, +0.0031, -0.0380, +0.2344, +0.0808, -0.0694
],
[
-0.0631, +0.0290, +0.1733, -0.0555, +0.1311, -0.0812, +0.1056, -0.1663,
-0.1272, +0.2717, +0.0247, +0.0730, -0.3714, +0.0042, -0.0490, +0.0222,
-0.0429, -0.1618, +0.1476, +0.1699, -0.1660, +0.1571, -0.0225, +0.1582,
+0.1622, -0.0721, -0.1198, +0.1388, -0.1661, +0.0103, -0.1386, +0.0883
],
[
+0.0306, +0.1041, -0.2540, +0.0423, +0.1098, -0.0204, +0.1478, +0.1917,
+0.1102, +0.0045, -0.0263, +0.0818, -0.0245, -0.0047, -0.2407, -0.6658,
+0.0834, +0.0400, +0.1785, -0.5141, +0.3379, -0.5638, -0.0012, -0.2549,
-0.4172, -0.2134, -0.3793, -0.0736, -0.3442, +0.1044, -0.0489, -0.2967
],
[
-0.0446, -0.1153, -0.0839, +0.0948, +0.3570, -0.0520, -0.1016, -0.0265,
+0.4342, +0.2325, +0.1763, -0.2663, -0.0676, -0.0759, +0.0654, +0.2983,
+0.1185, -0.0233, -0.5232, +0.1075, -0.3284, +0.2703, +0.2164, +0.0092,
+0.2988, +0.1956, +0.0582, +0.3342, +0.0949, -0.1936, -0.0465, +0.4223
],
[
+0.0737, -0.0069, -0.1301, +0.3047, -0.2603, +0.0369, -0.2049, +0.0378,
-0.1846, -0.3474, -0.1353, +0.0965, +0.0956, -0.0692, -0.0440, -0.1767,
-0.1616, -0.2183, +0.1853, -0.0618, +0.1210, -0.2178, +0.1066, -0.3849,
-0.2628, +0.1444, +0.2814, -0.2963, +0.0673, +0.0983, +0.0442, +0.0020
],
[
-0.0978, +0.2645, -0.3750, +0.2824, -0.3906, -0.0070, +0.1920, +0.0911,
-0.0510, -0.1050, -0.2411, -0.2135, +0.0784, +0.3348, -0.0396, -0.4209,
-0.0686, -0.2212, +0.3039, -0.4649, -0.0692, -0.5387, +0.0479, -0.4205,
-0.2557, -0.1031, +0.1378, -0.3875, -0.1900, -0.0253, +0.1212, -0.4374
],
[
-0.1067, +0.1545, +0.2016, -0.0620, -0.1419, -0.0661, -0.1224, -0.0560,
+0.1045, -0.2062, -0.2551, +0.2440, -0.1116, +0.1544, -0.2324, +0.0999,
-0.1832, -0.1226, -0.1774, +0.0629, -0.1170, -0.1375, +0.0839, +0.2029,
+0.0551, +0.0359, +0.0967, +0.2290, -0.0312, -0.1228, +0.2831, +0.1785
],
[
-0.1420, +0.1163, +0.0488, -0.0011, -0.1311, -0.1558, -0.0766, -0.0088,
+0.1877, -0.1547, +0.1304, +0.0347, +0.1132, +0.2750, -0.0574, +0.0080,
-0.2256, -0.0951, +0.1987, +0.2256, +0.0270, -0.0155, +0.0636, +0.0372,
+0.2483, -0.1469, -0.2010, -0.0994, -0.1731, +0.0224, +0.0085, -0.1891
],
[
+0.1037, +0.0015, -0.1525, -0.0444, -0.3130, -0.0318, +0.2370, -0.1492,
-0.4707, -0.0023, +0.0884, +0.1722, -0.0421, +0.0858, -0.1036, -0.5701,
+0.1249, -0.2643, -0.0203, -0.1380, +0.0973, -0.2060, +0.1806, +0.3054,
-0.6548, -0.3282, -0.2969, -0.3984, -0.0448, -0.1802, +0.3282, -0.1891
],
[
-0.1116, +0.3646, -0.0542, +0.3672, -0.4207, +0.2700, +0.3827, -0.0599,
-0.3415, -0.2832, -0.0345, +0.1987, +0.0669, +0.1301, -0.3806, -0.2981,
-0.1917, -0.2028, +0.1687, -0.2010, +0.3607, -0.0199, +0.2971, +0.0390,
+0.0895, -0.3088, +0.0169, -0.1333, +0.0738, +0.2161, -0.1207, -0.3352
],
[
-0.0134, +0.3853, -0.2106, +0.1996, -0.2277, -0.0971, +0.0917, -0.2901,
-0.2493, +0.0295, -0.1438, -0.1902, -0.0074, +0.2240, -0.0277, -0.4374,
+0.0749, -0.1779, +0.2687, -0.4093, -0.0042, -0.5023, -0.1169, -0.3157,
+0.0061, +0.0270, +0.0204, -0.4626, -0.1717, -0.2126, +0.1335, -0.5028
],
[
-0.0813, +0.1958, -0.4203, +0.3027, -0.3896, -0.1201, -0.0383, -0.1807,
-0.4834, -0.3672, -0.3664, +0.2401, -0.0114, -0.0852, -0.2220, -0.1953,
+0.0773, -0.0048, +0.1560, -0.1524, +0.0772, -0.2740, +0.1346, -0.3171,
-0.0648, +0.1633, +0.2050, -0.1560, +0.0270, +0.3009, -0.2798, -0.0756
],
[
-0.1754, +0.1428, +0.2527, -0.2624, -0.1126, -0.0014, +0.1030, -0.2716,
-0.2678, -0.0268, +0.0982, -0.0385, -0.0628, -0.0768, -0.2531, +0.2935,
-0.0661, +0.0778, -0.1184, +0.0070, -0.1331, -0.1174, -0.1338, -0.1601,
-0.0357, -0.1964, -0.0550, -0.1151, +0.2369, +0.1578, -0.0826, -0.1985
],
[
-0.1724, -0.0328, +0.0090, -0.0564, +0.0876, -0.0607, +0.0060, -0.2330,
+0.1137, -0.0771, -0.0774, +0.0727, -0.2037, +0.1521, +0.0666, +0.0258,
-0.2189, -0.1417, +0.0276, -0.0387, -0.0747, -0.0214, -0.0793, -0.0520,
+0.0918, -0.1276, -0.0877, +0.0309, -0.0630, -0.0149, -0.0197, -0.1755
],
[
+0.1471, -0.1542, +0.1202, -0.2846, +0.1209, -0.0383, -0.2689, -0.0442,
-0.1086, +0.3428, +0.0120, +0.0473, +0.0320, -0.2629, -0.0904, -0.3732,
-0.2179, +0.2540, -0.1725, -0.4163, -0.0333, +0.0934, -0.3123, -0.1123,
-0.2196, +0.1580, -0.6386, +0.0650, -0.0473, +0.0521, +0.0061, -0.2745
],
[
+0.0064, -0.1054, -0.2054, -0.1706, +0.1626, +0.0895, +0.0571, -0.2639,
+0.0269, +0.1943, +0.0687, -0.1510, -0.1987, +0.0784, -0.1774, -0.0242,
+0.0519, -0.3330, +0.0364, +0.1868, -0.3204, +0.1106, +0.0456, -0.1627,
-0.2792, +0.0017, +0.2943, +0.0481, -0.1523, -0.1656, -0.0222, -0.0239
],
[
+0.0853, +0.2513, -0.1716, +0.0164, -0.1375, -0.0870, +0.2430, +0.2161,
-0.4489, -0.3427, +0.0341, -0.0022, -0.1488, +0.2685, -0.2290, -0.2439,
+0.1216, -0.1475, -0.0332, -0.1282, -0.1603, -0.1076, -0.1279, -0.1439,
-0.2784, -0.4271, +0.1286, -0.1134, -0.1994, -0.1031, -0.0210, -0.2327
],
[
+0.1303, -0.0463, +0.1797, -0.0939, +0.2427, -0.0791, -0.0735, -0.2248,
+0.1545, -0.1325, -0.1812, -0.0896, +0.0695, +0.0225, -0.1880, +0.1619,
-0.0468, +0.0904, +0.1570, -0.0206, +0.1266, -0.0148, +0.0305, +0.2494,
+0.1687, -0.0774, -0.2693, +0.0449, +0.0040, -0.1319, +0.1513, -0.0410
],
[
+0.0545, +0.0586, -0.0087, -0.1021, -0.1756, -0.0722, +0.0678, +0.0310,
-0.1490, -0.2823, +0.1335, -0.0038, +0.0660, +0.0696, -0.2747, -0.3360,
+0.1061, +0.3080, +0.1201, -0.3870, +0.2960, -0.4409, -0.0295, +0.0854,
-0.0908, +0.1224, -0.4637, -0.4016, +0.0420, +0.0505, +0.0364, -0.2983
],
[
-0.1218, +0.2787, -0.1838, -0.0315, -0.1590, -0.2840, +0.2845, +0.0601,
-0.1741, -0.2363, -0.3620, -0.1355, +0.0943, +0.1343, -0.0346, -0.1135,
+0.0327, -0.2982, +0.1805, -0.1483, +0.1698, -0.1056, -0.0257, +0.0580,
-0.1921, +0.0863, +0.1439, -0.1360, +0.0468, +0.2411, -0.1872, +0.0329
],
[
+0.0068, +0.1272, +0.0108, +0.0178, +0.2308, +0.0207, -0.0050, +0.0127,
+0.1008, -0.2972, -0.2233, -0.1369, +0.0797, +0.0023, -0.0782, -0.4778,
+0.1916, +0.1325, +0.0110, -0.2083, +0.2786, -0.2724, -0.1214, +0.0510,
-0.1068, -0.1982, -0.4602, -0.1082, -0.1563, -0.0689, -0.0913, +0.0983
],
[
+0.1631, +0.1356, -0.1882, +0.2125, -0.4817, -0.1368, +0.1216, -0.1032,
-0.4494, -0.2093, -0.0110, +0.0402, -0.0097, +0.1575, -0.2447, -0.8683,
+0.1860, -0.4305, +0.1405, -0.3244, +0.1927, -0.5331, +0.0910, -0.1750,
-0.2639, -0.3461, -0.0655, -0.4643, -0.0272, +0.0600, +0.1538, -0.3951
],
[
+0.0750, +0.0031, -0.1113, +0.0419, -0.0726, +0.1712, +0.1273, -0.0844,
+0.0187, -0.1579, +0.0365, +0.1953, +0.0259, +0.1069, +0.1584, +0.0159,
+0.1700, -0.0276, +0.0061, -0.1753, -0.0827, -0.0493, +0.0756, -0.1169,
+0.0177, -0.2200, -0.0495, -0.0934, +0.1999, -0.0962, -0.0035, +0.1083
],
[
-0.0754, -0.1933, +0.1219, -0.3622, -0.2560, +0.0829, -0.3323, +0.0923,
-0.1712, +0.0494, +0.1063, +0.3118, +0.0088, -0.3756, -0.0977, +0.0160,
-0.0817, +0.1595, -0.3452, +0.2652, +0.2646, +0.2833, -0.3530, +0.0805,
-0.1736, +0.0675, -0.1320, -0.3568, +0.1824, -0.0068, +0.0391, -0.3348
],
[
+0.0661, +0.1602, -0.0509, +0.0562, -0.1738, +0.0114, -0.0268, -0.0354,
-0.2069, -0.0250, -0.1061, -0.1695, -0.0719, +0.2797, -0.2477, -0.2539,
+0.1287, -0.2037, +0.2556, -0.1008, +0.1943, -0.1660, +0.2728, -0.2338,
-0.0806, -0.2346, +0.0449, -0.4673, -0.0362, -0.1172, +0.1695, -0.2252
],
[
+0.0348, -0.2188, +0.0041, -0.1818, +0.3175, -0.0947, -0.2779, -0.0764,
+0.2407, -0.1541, +0.2586, -0.1852, -0.1379, -0.3336, +0.1402, -0.0446,
+0.0584, +0.0994, -0.3633, +0.0636, -0.0156, -0.0767, -0.2649, +0.0149,
+0.2484, +0.2916, +0.1928, -0.0036, +0.0696, -0.0935, +0.2752, +0.0187
],
[
-0.2666, +0.0507, -0.1783, +0.2308, +0.3974, -0.0719, +0.0276, -0.0048,
+0.1177, +0.0816, -0.2346, -0.2762, +0.1167, +0.0719, -0.1303, -0.0892,
+0.0177, +0.0072, +0.0965, +0.2305, +0.0988, +0.1532, -0.1653, +0.0692,
-0.0419, -0.1874, -0.0896, +0.0014, +0.0375, -0.0905, -0.3757, +0.3573
],
[
+0.4116, -0.2717, +0.2356, -0.1943, +0.0575, +0.0379, -0.0606, -0.0819,
+0.1179, +0.2377, -0.1506, +0.1710, +0.0912, -0.2922, +0.0898, +0.1814,
+0.1221, +0.1917, -0.3906, +0.1684, +0.1638, +0.2434, -0.1656, +0.1352,
+0.0744, -0.0942, -0.2128, +0.0767, +0.0628, +0.1426, +0.3458, -0.0437
],
[
-0.1387, -0.5340, +0.2895, -0.5476, +0.5888, +0.1435, -0.4898, +0.0061,
+0.6167, +0.1024, +0.1127, +0.2197, +0.0206, -0.4723, +0.1195, +0.6172,
+0.0276, +0.3961, -0.5498, +0.4008, -0.2163, +0.3337, -0.2608, +0.1666,
+0.3415, +0.0077, -0.1649, +0.2619, -0.1937, -0.1043, +0.1770, +0.4285
],
[
-0.0167, +0.0725, +0.1501, +0.0806, -0.0904, -0.2287, +0.1906, -0.0706,
-0.0861, -0.1585, -0.1175, -0.0603, -0.0193, +0.4876, -0.1954, -0.0463,
-0.1083, +0.1297, -0.0301, +0.0312, +0.0755, +0.0648, -0.4867, -0.0645,
+0.0074, +0.0624, -0.1972, -0.1996, -0.1207, -0.1015, +0.0720, +0.0260
],
[
+0.0007, -0.1637, +0.1202, -0.1045, +0.2969, +0.1975, -0.1374, +0.1684,
+0.0790, +0.2108, -0.0220, +0.0773, +0.0046, +0.0205, -0.1746, +0.3445,
+0.0773, +0.0005, +0.0251, +0.3337, -0.3365, +0.3956, -0.2011, +0.2489,
+0.1875, +0.0282, -0.4611, +0.2249, +0.0182, -0.1252, -0.1899, +0.1563
],
[
-0.0142, +0.0174, +0.1562, +0.0763, +0.1314, -0.0686, +0.3657, -0.0132,
-0.0737, +0.0247, +0.0431, -0.2967, +0.0002, +0.2221, +0.1011, +0.1039,
-0.0503, -0.3926, +0.1014, -0.1349, -0.1005, +0.1254, +0.0250, -0.1482,
-0.2554, +0.1027, +0.1661, -0.1071, -0.0521, -0.0568, +0.1508, +0.0668
],
[
-0.1106, +0.1260, -0.3472, +0.2769, +0.0344, -0.0668, +0.2888, +0.1583,
-0.2782, -0.1161, -0.2939, +0.1309, -0.0010, +0.4387, +0.1623, -0.2627,
-0.1011, -0.3530, +0.0604, -0.2499, +0.2736, -0.2715, +0.2004, -0.5407,
-0.4915, -0.1778, +0.1274, -0.1071, -0.0170, -0.1190, -0.1540, -0.0364
],
[
-0.1767, +0.2753, +0.2479, -0.0753, -0.2057, -0.2379, -0.0411, -0.0945,
-0.1757, +0.1752, +0.1322, +0.0548, -0.0980, +0.1753, -0.0510, +0.2050,
-0.0246, +0.5660, -0.2124, +0.1708, -0.1779, +0.2125, -0.0143, +0.1992,
+0.1330, -0.2561, -0.1304, +0.2212, -0.2898, +0.0983, -0.1803, +0.1087
],
[
-0.0503, -0.3082, +0.1056, -0.1658, +0.3225, +0.0727, -0.4463, -0.0153,
+0.0195, +0.0962, -0.0483, -0.0484, +0.2464, -0.5537, +0.1422, +0.1233,
-0.1036, +0.0864, -0.2107, +0.1319, +0.2002, +0.3051, -0.2054, +0.3069,
+0.2754, +0.1618, -0.0593, -0.0373, +0.2155, -0.1157, -0.1199, +0.2342
],
[
-0.1789, -0.1216, +0.0442, -0.1111, +0.1411, -0.0572, -0.4238, +0.0134,
-0.1511, +0.0625, -0.0139, -0.2257, -0.1143, -0.2315, +0.3597, -0.1227,
+0.0240, +0.2061, -0.0474, +0.0561, -0.2806, -0.0939, -0.0608, +0.1852,
-0.0210, -0.3526, +0.0992, -0.3513, -0.0787, +0.1074, -0.0475, -0.1759
],
[
-0.0510, +0.0215, +0.1585, -0.0757, +0.0357, -0.0553, -0.1151, -0.1353,
+0.1000, -0.2570, -0.0664, -0.1762, +0.0430, -0.0365, +0.0198, +0.1154,
-0.5763, +0.0393, -0.0443, +0.0504, +0.0482, +0.1528, +0.1955, -0.0493,
+0.2712, -0.0688, -0.1406, +0.1479, +0.0204, +0.0838, -0.2282, +0.2307
],
[
-0.1682, -0.0467, -0.0758, +0.3832, -0.1471, +0.0612, +0.3901, +0.1065,
+0.2009, -0.3104, -0.2998, -0.3175, -0.0722, +0.1549, -0.2472, -0.1729,
+0.0841, -0.1691, +0.1407, -0.1969, -0.0491, +0.0103, +0.1179, -0.1327,
-0.1275, +0.0368, +0.0953, -0.1660, -0.0245, -0.3851, +0.1340, -0.1417
],
[
+0.0114, -0.0822, -0.2575, -0.0169, +0.1292, +0.0791, -0.0803, +0.0061,
-0.0445, -0.2228, +0.0215, +0.1863, +0.2645, -0.0295, +0.0756, -0.2138,
-0.1607, +0.0527, +0.0592, -0.1770, -0.0982, -0.1096, +0.0925, -0.0325,
+0.0047, +0.1512, +0.0663, -0.1348, +0.0084, -0.1352, +0.0189, +0.1428
],
[
+0.0052, +0.1124, +0.1083, +0.1163, +0.0787, +0.0839, +0.0839, +0.0506,
+0.0537, +0.1066, +0.1034, -0.1299, -0.1434, +0.0188, +0.1823, +0.1403,
-0.4525, +0.0949, -0.0981, +0.0722, -0.1085, -0.2382, +0.1028, +0.0664,
+0.1976, +0.1073, -0.2736, +0.2433, -0.3520, -0.0386, -0.2319, -0.0724
],
[
-0.3279, -0.1491, -0.1409, +0.2056, -0.1464, +0.0543, +0.1842, +0.1104,
-0.2819, +0.0769, -0.1159, +0.0228, -0.0988, +0.0026, -0.1204, -0.0780,
-0.2018, +0.1755, +0.1574, +0.0222, +0.1662, -0.2193, -0.0718, +0.0010,
-0.0123, -0.0120, +0.2587, +0.0358, -0.1435, +0.0017, -0.2620, +0.0965
],
[
-0.1144, -0.1048, +0.2211, -0.0726, -0.1721, -0.2475, -0.3226, +0.0120,
+0.0908, +0.0375, -0.0974, +0.0490, -0.1180, -0.3155, -0.2565, -0.0092,
-0.4400, +0.2027, -0.1459, +0.1043, +0.0771, +0.0825, -0.1541, -0.0713,
-0.0437, -0.0249, -0.1757, -0.1115, +0.0457, +0.1141, -0.2567, +0.0405
],
[
+0.0587, +0.1083, +0.0729, +0.2131, -0.1586, +0.2208, -0.1576, -0.0811,
-0.0467, +0.2201, -0.1082, -0.2077, +0.0030, -0.1222, +0.2023, +0.1155,
-0.1616, +0.0105, +0.1167, -0.1257, +0.4859, +0.1337, -0.0169, -0.0163,
+0.2076, +0.0367, -0.0050, -0.2590, -0.0800, -0.2192, +0.0938, +0.1126
],
[
-0.3834, -0.0180, -0.2714, +0.0303, +0.0784, -0.1242, +0.1105, +0.0237,
-0.0085, +0.2615, +0.0189, -0.3734, +0.0088, +0.1211, -0.0838, +0.0067,
+0.1956, +0.1577, +0.2132, -0.0044, -0.2748, +0.1417, +0.0201, +0.1002,
+0.0311, -0.0052, -0.1695, -0.0750, +0.2200, -0.2848, +0.0438, -0.0442
],
[
-0.1496, +0.1258, +0.1903, -0.0337, -0.1470, -0.0530, +0.0519, -0.0037,
+0.0342, +0.0404, -0.0950, -0.0840, +0.1083, -0.0488, +0.0427, +0.1454,
+0.0851, -0.0203, -0.2354, +0.1562, +0.1899, +0.3145, +0.0013, +0.1608,
+0.0126, +0.2080, -0.1409, -0.0746, +0.0580, -0.1045, -0.1753, +0.1225
],
[
-0.0349, +0.1354, -0.1052, -0.1189, +0.0288, -0.0257, +0.0813, -0.1559,
+0.1267, +0.0664, +0.2004, +0.1232, +0.2557, -0.1729, -0.0666, +0.1644,
+0.1043, -0.2672, +0.0537, +0.0566, -0.1738, +0.0036, +0.1406, -0.0574,
-0.0556, +0.3336, -0.0328, -0.1624, +0.0132, -0.0627, -0.1523, +0.0552
],
[
-0.3105, +0.2681, -0.5462, +0.2785, -0.2453, -0.2965, +0.1436, +0.0786,
-0.3242, -0.3518, +0.1025, +0.2219, -0.1324, +0.1681, +0.0701, -0.0938,
+0.1574, -0.5157, +0.3574, -0.1100, +0.2647, -0.1698, +0.2684, -0.3876,
-0.6240, -0.1013, +0.2920, -0.3569, -0.0008, +0.0974, +0.1444, -0.3349
],
[
+0.0848, -0.1191, +0.2283, +0.0922, +0.2880, -0.1747, -0.4457, +0.1013,
+0.2494, +0.1487, +0.1013, -0.0403, -0.0236, -0.1965, -0.0655, +0.0818,
+0.0493, -0.0605, -0.1889, +0.1772, -0.2826, +0.2783, -0.1653, +0.3505,
+0.4192, -0.1048, -0.1459, +0.0779, -0.0154, -0.1573, -0.1254, -0.1118
],
[
-0.1817, +0.0719, +0.1352, +0.3208, +0.2142, -0.1149, +0.0020, +0.1617,
+0.1055, +0.0395, -0.1802, -0.0631, -0.3172, +0.1971, +0.0197, +0.1271,
-0.2375, -0.1849, -0.0134, +0.1223, +0.2566, +0.0311, -0.2746, +0.0278,
+0.1233, +0.0167, -0.0363, +0.2146, -0.0466, +0.0732, -0.1490, +0.1040
],
[
+0.1008, -0.1501, +0.0264, -0.4661, -0.0553, +0.0431, -0.3076, -0.0461,
+0.1393, -0.1225, +0.2811, -0.0363, -0.0403, -0.3370, -0.0865, -0.1179,
+0.1106, +0.2035, -0.2432, -0.0859, +0.0600, -0.0890, -0.0749, +0.0483,
+0.0615, -0.0239, -0.4674, +0.0199, +0.0669, +0.1410, +0.1846, +0.2626
],
[
+0.0663, +0.1486, -0.3928, +0.3257, -0.0316, +0.1377, +0.0418, +0.1921,
-0.1616, -0.2265, -0.0917, +0.1582, -0.0537, +0.0295, -0.2264, -0.1921,
-0.0225, +0.0928, +0.0747, -0.5268, -0.0068, -0.3328, +0.0437, -0.2361,
-0.1408, -0.1234, +0.2216, -0.1372, -0.0499, +0.1940, +0.0098, -0.2953
],
[
+0.0290, -0.1583, -0.0172, -0.1748, -0.0042, -0.0725, -0.2227, -0.1366,
-0.1771, +0.1987, +0.3142, +0.1889, +0.0195, -0.5461, +0.0921, +0.1407,
-0.1656, +0.1985, +0.0113, +0.2613, +0.2925, +0.1166, -0.1286, +0.1031,
-0.2228, -0.0605, -0.2151, +0.2477, +0.1602, -0.0109, +0.0207, +0.1257
],
[
+0.0630, -0.1688, +0.1662, -0.2327, +0.2832, +0.1350, -0.1658, +0.0504,
-0.0502, +0.1736, +0.1002, -0.0051, -0.0311, -0.0628, +0.0039, +0.5085,
-0.2191, +0.5105, -0.0927, +0.2833, -0.2828, +0.1078, +0.0406, -0.0392,
-0.2372, +0.1508, +0.0556, +0.0313, +0.1296, +0.1315, -0.1143, +0.1632
]
])
weights_dense2_b = np.array([ -0.0655, +0.0020, +0.0358, -0.0192, +0.0570, +0.0000, +0.0711, -0.0145, +0.0294, +0.0139, -0.0215, -0.0952, +0.0000, +0.0526, -0.0585, +0.0633, -0.0332, +0.0030, +0.0107, +0.0830, +0.0140, +0.0888, -0.1115, -0.0722, +0.0240, +0.0476, -0.0807, -0.0421, +0.0000, -0.0557, -0.0403, +0.0034])
weights_final_w = np.array([
[ -0.0230],
[ +0.0730],
[ -0.2093],
[ +0.0463],
[ -0.1983],
[ -0.0031],
[ +0.2101],
[ -0.0066],
[ -0.1481],
[ -0.1615],
[ -0.1766],
[ +0.1332],
[ -0.0012],
[ +0.2332],
[ -0.0380],
[ -0.3066],
[ -0.1738],
[ -0.2982],
[ +0.0285],
[ -0.1548],
[ +0.2539],
[ -0.2544],
[ +0.2006],
[ -0.4121],
[ -0.2084],
[ -0.0381],
[ +0.2733],
[ -0.3076],
[ +0.0013],
[ +0.0957],
[ -0.1298],
[ -0.1112]
weights_dense2_b = np.array([
-0.0655, +0.0020, +0.0358, -0.0192, +0.0570, +0.0000, +0.0711, -0.0145,
+0.0294, +0.0139, -0.0215, -0.0952, +0.0000, +0.0526, -0.0585, +0.0633,
-0.0332, +0.0030, +0.0107, +0.0830, +0.0140, +0.0888, -0.1115, -0.0722,
+0.0240, +0.0476, -0.0807, -0.0421, +0.0000, -0.0557, -0.0403, +0.0034
])
weights_final_b = np.array([ +0.0352])
weights_final_w = np.array([[-0.0230], [+0.0730], [-0.2093], [+0.0463],
[-0.1983], [-0.0031], [+0.2101], [-0.0066],
[-0.1481], [-0.1615], [-0.1766], [+0.1332],
[-0.0012], [+0.2332], [-0.0380], [-0.3066],
[-0.1738], [-0.2982], [+0.0285], [-0.1548],
[+0.2539], [-0.2544], [+0.2006], [-0.4121],
[-0.2084], [-0.0381], [+0.2733], [-0.3076],
[+0.0013], [+0.0957], [-0.1298], [-0.1112]])
if __name__=="__main__":
main()
weights_final_b = np.array([+0.0352])
# yapf: enable
if __name__ == "__main__":
main()

View File

@@ -2,175 +2,538 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import gym
import numpy as np
import pybullet_envs
import time
def relu(x):
return np.maximum(x, 0)
return np.maximum(x, 0)
class SmallReactivePolicy:
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64.0)
assert weights_dense2_w.shape == (64.0, 32.0)
assert weights_final_w.shape == (32.0, action_space.shape[0])
"Simple multi-layer perceptron policy, no internal state"
def __init__(self, observation_space, action_space):
assert weights_dense1_w.shape == (observation_space.shape[0], 64.0)
assert weights_dense2_w.shape == (64.0, 32.0)
assert weights_final_w.shape == (32.0, action_space.shape[0])
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def act(self, ob):
x = ob
x = relu(np.dot(x, weights_dense1_w) + weights_dense1_b)
x = relu(np.dot(x, weights_dense2_w) + weights_dense2_b)
x = np.dot(x, weights_final_w) + weights_final_b
return x
def main():
env = gym.make("InvertedPendulumSwingupBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
env = gym.make("InvertedPendulumSwingupBulletEnv-v0")
env.render(mode="human")
pi = SmallReactivePolicy(env.observation_space, env.action_space)
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
while 1:
frame = 0
score = 0
restart_delay = 0
obs = env.reset()
time.sleep(1. / 60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open == False:
return
if not done: continue
if restart_delay == 0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60 * 2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay > 0: continue
break
while 1:
time.sleep(1./60.)
a = pi.act(obs)
obs, r, done, _ = env.step(a)
score += r
frame += 1
still_open = env.render("human")
if still_open==False:
return
if not done: continue
if restart_delay==0:
print("score=%0.2f in %i frames" % (score, frame))
restart_delay = 60*2 # 2 sec at 60 fps
else:
restart_delay -= 1
if restart_delay > 0: continue
break
weights_dense1_w = np.array([
[ +0.5877, -0.5825, -0.5542, -0.2557, -0.4485, +1.4126, +0.2701, -0.6204, -0.2580, +0.2106, -0.2296, +0.7949, +0.6224, -0.0186, +0.4216, +1.0924, -0.1538, -0.2818, +0.4855, -0.2496, +0.7461, -0.6156, +0.0801, +0.7871, -0.4312, -0.9585, +0.1566, -0.2218, -1.0393, +0.6104, -0.5339, +0.8258, +0.4064, +0.0503, +0.4753, -0.8161, +0.0812, +0.2311, -0.9492, -1.1791, +1.2375, +0.2916, +1.2290, +0.2796, -0.8864, -1.1424, -0.5714, +0.1413, +0.7340, -0.4152, +0.2832, -0.3886, +0.4810, -0.7092, -0.5966, +0.1089, +0.1007, +0.5226, -0.3343, +0.1760, +0.4099, -0.9913, -1.1694, -1.0018],
[ +0.4054, +0.2495, +0.5483, +0.7193, -0.1833, -0.2237, -0.4353, -0.1005, +0.2848, +0.3193, +0.2551, -0.1267, -0.7200, +0.3952, +0.3390, +0.2123, +0.1388, +0.8869, -0.1095, -0.1718, -0.4128, -0.7047, -1.1383, +0.6552, -0.0037, -0.4306, +0.2749, -0.9121, +0.4406, -0.0163, +0.4852, +0.6150, +0.1354, -0.7839, +0.2261, +0.3988, -0.2867, -0.5369, -0.0788, +0.0125, +0.2645, +0.1614, +0.7531, +0.5786, +0.6903, -0.7974, -0.2934, -0.3407, -0.7366, -0.1585, +1.0333, -0.0183, +0.2690, -0.5674, -0.0266, +0.0898, -0.1441, -0.0988, +0.7260, +0.7994, +0.1521, -0.3210, -0.1403, -0.2685],
[ -0.1050, -0.1826, +0.4717, -0.3515, +0.9648, -0.6372, -0.4686, +0.6959, +0.3540, +0.3515, +0.3239, -1.6177, -0.0651, +0.4653, +0.5058, +0.3465, -0.6693, -0.1118, -0.9582, -1.5053, -0.2256, -0.1989, -0.1901, -0.4282, -1.3479, -0.5629, +0.6828, -0.3515, -0.4724, +0.4618, +0.3008, +0.1280, +0.3720, -0.0545, +0.3104, -0.2527, +0.4614, +0.4994, -0.0099, +0.4597, -0.2667, -0.0374, -0.3393, +0.2675, -0.2635, -0.6062, +0.6404, +0.4500, -0.5105, -1.5838, -0.1396, +0.8804, +0.5794, -0.6823, -0.2125, +0.4510, +0.2424, +0.3407, -0.3354, +0.1306, -1.0006, +0.2358, +0.6479, +0.2027],
[ +0.7453, +0.8937, -0.9068, +0.2950, +0.4412, -0.6005, -1.3008, -0.0299, -0.6434, +1.4992, +0.7437, +0.4271, -0.0549, +1.2337, +1.6758, -0.7335, +0.2251, -1.1287, -1.0611, -0.4609, -1.6821, -0.3495, -0.5520, +0.2407, -1.0738, +0.9423, -0.6853, -0.0193, +0.6365, +0.3979, -1.8896, -1.1404, +0.4708, -0.2113, +1.3380, +0.6163, +0.5543, +0.4372, -0.3004, +1.0200, -0.4211, +0.5034, -0.1635, +2.0363, +0.1362, -0.2348, +0.7659, -1.6971, -1.3513, -0.2940, +1.2592, -0.3885, +0.5544, +0.8858, +0.0189, -1.8006, +1.3254, +0.6919, +0.3571, -0.5189, -0.0115, -1.7036, -0.8770, +1.2328],
[ -0.3661, +0.5205, +0.6454, +0.9826, -0.2945, -0.3074, +0.6830, +0.3798, +0.0578, +0.2303, +0.0181, -0.3768, -0.1607, +0.9089, +0.2910, -0.0265, -0.7435, +0.2932, -0.4173, +0.2959, +0.2079, +0.2649, +0.4184, +0.5963, +0.2120, +0.1885, +0.3611, +0.5193, +0.4538, +0.7072, +0.2274, +0.2233, +0.3970, +0.0560, +0.2132, +0.0186, +0.1522, -0.2460, +0.6636, +0.4592, -0.5299, +1.1159, -0.2861, +0.3664, -0.0648, +0.1958, -0.0180, -0.2585, +0.1408, +0.2639, -0.3697, +0.4727, +1.0321, +0.0851, +0.8350, +0.0830, +0.1625, -0.3849, +0.3014, -0.1514, -0.5960, -0.4083, -0.1023, +0.2080]
# yapf: disable
weights_dense1_w = np.array(
[[
+0.5877, -0.5825, -0.5542, -0.2557, -0.4485, +1.4126, +0.2701, -0.6204,
-0.2580, +0.2106, -0.2296, +0.7949, +0.6224, -0.0186, +0.4216, +1.0924,
-0.1538, -0.2818, +0.4855, -0.2496, +0.7461, -0.6156, +0.0801, +0.7871,
-0.4312, -0.9585, +0.1566, -0.2218, -1.0393, +0.6104, -0.5339, +0.8258,
+0.4064, +0.0503, +0.4753, -0.8161, +0.0812, +0.2311, -0.9492, -1.1791,
+1.2375, +0.2916, +1.2290, +0.2796, -0.8864, -1.1424, -0.5714, +0.1413,
+0.7340, -0.4152, +0.2832, -0.3886, +0.4810, -0.7092, -0.5966, +0.1089,
+0.1007, +0.5226, -0.3343, +0.1760, +0.4099, -0.9913, -1.1694, -1.0018
],
[
+0.4054, +0.2495, +0.5483, +0.7193, -0.1833, -0.2237, -0.4353,
-0.1005, +0.2848, +0.3193, +0.2551, -0.1267, -0.7200, +0.3952,
+0.3390, +0.2123, +0.1388, +0.8869, -0.1095, -0.1718, -0.4128,
-0.7047, -1.1383, +0.6552, -0.0037, -0.4306, +0.2749, -0.9121,
+0.4406, -0.0163, +0.4852, +0.6150, +0.1354, -0.7839, +0.2261,
+0.3988, -0.2867, -0.5369, -0.0788, +0.0125, +0.2645, +0.1614,
+0.7531, +0.5786, +0.6903, -0.7974, -0.2934, -0.3407, -0.7366,
-0.1585, +1.0333, -0.0183, +0.2690, -0.5674, -0.0266, +0.0898,
-0.1441, -0.0988, +0.7260, +0.7994, +0.1521, -0.3210, -0.1403, -0.2685
],
[
-0.1050, -0.1826, +0.4717, -0.3515, +0.9648, -0.6372, -0.4686,
+0.6959, +0.3540, +0.3515, +0.3239, -1.6177, -0.0651, +0.4653,
+0.5058, +0.3465, -0.6693, -0.1118, -0.9582, -1.5053, -0.2256,
-0.1989, -0.1901, -0.4282, -1.3479, -0.5629, +0.6828, -0.3515,
-0.4724, +0.4618, +0.3008, +0.1280, +0.3720, -0.0545, +0.3104,
-0.2527, +0.4614, +0.4994, -0.0099, +0.4597, -0.2667, -0.0374,
-0.3393, +0.2675, -0.2635, -0.6062, +0.6404, +0.4500, -0.5105,
-1.5838, -0.1396, +0.8804, +0.5794, -0.6823, -0.2125, +0.4510,
+0.2424, +0.3407, -0.3354, +0.1306, -1.0006, +0.2358, +0.6479, +0.2027
],
[
+0.7453, +0.8937, -0.9068, +0.2950, +0.4412, -0.6005, -1.3008,
-0.0299, -0.6434, +1.4992, +0.7437, +0.4271, -0.0549, +1.2337,
+1.6758, -0.7335, +0.2251, -1.1287, -1.0611, -0.4609, -1.6821,
-0.3495, -0.5520, +0.2407, -1.0738, +0.9423, -0.6853, -0.0193,
+0.6365, +0.3979, -1.8896, -1.1404, +0.4708, -0.2113, +1.3380,
+0.6163, +0.5543, +0.4372, -0.3004, +1.0200, -0.4211, +0.5034,
-0.1635, +2.0363, +0.1362, -0.2348, +0.7659, -1.6971, -1.3513,
-0.2940, +1.2592, -0.3885, +0.5544, +0.8858, +0.0189, -1.8006,
+1.3254, +0.6919, +0.3571, -0.5189, -0.0115, -1.7036, -0.8770, +1.2328
],
[
-0.3661, +0.5205, +0.6454, +0.9826, -0.2945, -0.3074, +0.6830,
+0.3798, +0.0578, +0.2303, +0.0181, -0.3768, -0.1607, +0.9089,
+0.2910, -0.0265, -0.7435, +0.2932, -0.4173, +0.2959, +0.2079,
+0.2649, +0.4184, +0.5963, +0.2120, +0.1885, +0.3611, +0.5193,
+0.4538, +0.7072, +0.2274, +0.2233, +0.3970, +0.0560, +0.2132,
+0.0186, +0.1522, -0.2460, +0.6636, +0.4592, -0.5299, +1.1159,
-0.2861, +0.3664, -0.0648, +0.1958, -0.0180, -0.2585, +0.1408,
+0.2639, -0.3697, +0.4727, +1.0321, +0.0851, +0.8350, +0.0830,
+0.1625, -0.3849, +0.3014, -0.1514, -0.5960, -0.4083, -0.1023, +0.2080
]])
weights_dense1_b = np.array([
-0.4441, -0.2462, -0.2997, +0.3283, -0.2751, +0.0474, +0.0720, -0.2133,
-0.0770, -0.0053, +0.0138, -0.3554, -0.2999, -0.2340, +0.0054, +0.4380,
-0.1461, -0.2035, -0.8094, +0.0909, -0.1714, +0.2412, -0.1519, +0.0391,
+0.1525, +0.1798, +0.1041, +0.4503, -0.0088, +0.0323, -0.0414, +0.4621,
+0.1720, -0.1793, +0.1734, +0.1588, +0.2802, +0.1220, +0.1011, -0.1334,
-0.0663, +0.4778, +0.1110, -0.1536, +0.1873, -0.0090, -0.5979, +0.3604,
-0.2515, +0.4471, +0.2444, -0.2565, -0.1102, +0.0982, -0.0625, +0.3902,
-0.0248, -0.2240, +0.0894, -0.0671, -0.3344, -0.0089, -0.0793, +0.2673
])
weights_dense1_b = np.array([ -0.4441, -0.2462, -0.2997, +0.3283, -0.2751, +0.0474, +0.0720, -0.2133, -0.0770, -0.0053, +0.0138, -0.3554, -0.2999, -0.2340, +0.0054, +0.4380, -0.1461, -0.2035, -0.8094, +0.0909, -0.1714, +0.2412, -0.1519, +0.0391, +0.1525, +0.1798, +0.1041, +0.4503, -0.0088, +0.0323, -0.0414, +0.4621, +0.1720, -0.1793, +0.1734, +0.1588, +0.2802, +0.1220, +0.1011, -0.1334, -0.0663, +0.4778, +0.1110, -0.1536, +0.1873, -0.0090, -0.5979, +0.3604, -0.2515, +0.4471, +0.2444, -0.2565, -0.1102, +0.0982, -0.0625, +0.3902, -0.0248, -0.2240, +0.0894, -0.0671, -0.3344, -0.0089, -0.0793, +0.2673])
weights_dense2_w = np.array([
[ +0.1063, +0.2017, +0.0029, -0.2442, -0.1362, +0.2871, +0.2270, -0.1260, +0.5271, -0.1744, -0.4323, +0.3637, -0.0083, -0.0547, +0.4549, -0.0164, +0.0913, -0.1635, +0.3583, +0.3020, +0.2240, -0.3561, +0.0689, +0.0126, +0.0508, -1.2876, -0.0003, -0.0464, -0.2184, -0.2538, -0.5314, +0.5790],
[ -0.2180, +0.9455, +0.1446, -0.0724, +0.3771, -0.4290, +0.3908, -0.1787, -0.1009, -0.0539, -0.5364, -0.5032, -0.0631, -0.1185, -0.9890, +0.1935, -1.3280, -0.9275, +0.0670, -0.4234, -0.2061, +0.2674, +0.2963, +0.5353, -0.0221, -0.3095, +0.3255, -0.4568, +0.1337, -0.2826, -0.0538, -1.2748],
[ +0.3038, +0.0690, +0.1495, -0.1801, -0.0140, -0.1370, -0.2094, -1.9336, +0.2150, -0.5506, +0.3097, -0.9412, +0.1507, -0.0708, -0.8874, -0.1183, -0.0580, -0.7503, +0.2276, -0.3497, +0.0067, +0.2541, -0.1207, +0.5209, +0.5381, -1.2157, +0.4692, -0.0536, -0.2078, -0.9902, -1.0954, -1.3646],
[ +0.0581, -1.0529, -0.0581, +0.0473, -0.1228, +0.0913, -0.7037, +0.0711, +0.2062, -0.2102, +0.0475, -0.5266, +0.1324, -1.7822, -0.2985, +0.0172, +0.0110, -0.1624, -0.3990, -0.3165, +0.1287, -0.5655, +1.3905, -1.5117, +0.1874, -0.5032, -0.3292, +0.3378, -0.4749, +0.0765, +0.4345, -0.1121],
[ -0.1315, +0.2873, -1.0164, +0.2925, -0.5024, +0.2321, -1.3038, -0.7796, +0.0830, -0.3378, -0.1037, +0.0033, -0.7885, +0.4841, +0.1578, +0.1771, +0.1991, -0.1073, -0.0181, +0.0496, +0.0919, +0.0585, +0.4595, +0.1634, -0.2220, -0.0226, +0.4703, -1.8576, +0.3075, -0.4581, +0.2507, +0.2085],
[ +0.2704, +0.0379, +0.2313, -0.5561, -0.7413, -0.7693, +0.4787, +0.3033, -1.3572, -0.1323, -0.5202, -0.6937, -0.6824, -0.1782, -1.1647, -0.3461, -0.8537, +0.5416, +0.0638, -0.4208, -0.4464, +0.0009, -0.4284, +0.1806, +0.4172, -0.5477, +0.5549, +0.1937, -0.6029, +0.2084, -0.8289, -0.4554],
[ +0.3719, +0.4292, +0.2655, -0.1071, -0.1848, -0.0651, -0.4942, +0.0514, -0.1364, -0.1573, -0.0880, -0.4625, -0.0889, +0.2049, -1.2166, -0.2164, -0.3680, -0.7242, -0.1208, -0.3569, +0.0591, +0.3773, -1.2525, +0.4139, -0.1203, -0.2808, -0.2460, -0.3056, -0.2309, +0.1638, +0.1502, -0.2354],
[ +0.2204, +0.3725, +0.1919, +0.1579, +0.0064, +0.0469, -0.5103, -0.5866, +0.0043, -0.2127, -0.0816, +0.4270, -0.0504, +0.2804, -0.1278, -0.0507, +0.1206, -0.6903, -0.2278, -0.0725, +0.2198, +0.1067, +0.2162, +0.2341, -0.6394, -1.2196, +0.3075, -1.0066, +0.2299, -0.1218, -0.0533, +0.3365],
[ +0.2458, -0.1112, -0.6971, +0.1730, +0.0093, -0.0066, -0.2500, -1.2508, -0.0108, -0.4091, -0.5608, -0.0239, +0.4287, -0.1187, +0.0476, -0.1859, +0.1335, +0.0564, +0.2657, +0.3620, +0.4023, +0.0518, -0.1151, +0.0172, +0.0270, -0.4894, +0.3967, +0.1362, +0.1078, -1.4673, -0.6417, +0.0105],
[ -1.2388, -0.5692, +0.2738, -0.8659, +0.1514, +0.0501, -0.3654, -0.9175, +0.1314, -0.4386, +0.1715, +0.2538, +0.1051, -0.1091, +0.1875, -0.0295, -0.4012, -0.5032, -0.6742, -0.1109, +0.1125, -0.5023, -0.2032, -0.2740, -0.9510, +0.9708, -0.0643, -0.5463, -0.0895, -0.7491, +0.6833, +0.1855],
[ -0.4298, -0.0464, -0.0294, -0.0743, +0.0902, -0.6215, +0.0848, -0.3727, +0.2700, -0.3201, -0.2578, +0.2471, -0.6535, +0.2581, +0.2505, -0.1900, +0.1637, -1.5921, -0.1360, -0.0777, -0.0092, +0.0816, +0.0996, -0.0197, -0.7934, +0.0909, +0.2011, +0.1988, +0.1273, -0.0366, +0.0466, +0.1477],
[ +0.1492, +0.1446, +0.4695, -0.4109, -0.0883, -0.1199, +0.5098, +0.4549, -0.2600, +0.1315, -0.2831, +0.4905, +0.0915, +0.1289, -1.1824, +0.3743, -0.3307, -0.2300, -0.6317, -0.2493, -1.2151, -0.1466, -0.4567, -1.0819, +0.2878, -1.0267, +0.2882, +0.5518, -0.0761, +0.3592, +0.1387, -0.6827],
[ +0.1444, -0.1397, +0.1136, +0.0452, -0.3338, +0.1050, +0.2811, -0.1238, -0.4973, -0.0804, +0.0148, +0.1621, -0.8240, +0.2157, +0.1887, +0.0192, -1.2242, +0.2255, -0.2271, -0.4326, -0.0362, +0.0116, -0.2229, +0.4142, +0.3929, -0.2313, +0.1735, +0.0598, +0.1726, +0.1078, +0.1444, +0.3110],
[ -0.7894, -0.0617, +0.3583, -0.7723, +0.1178, +0.0533, -0.2285, -1.2298, +0.1727, -0.3313, +0.1193, -0.6488, +0.2996, -0.5132, -0.3868, +0.0174, +0.1475, +0.3516, -0.5912, -0.8573, +0.0606, -0.0528, -0.1981, +0.0196, -0.1688, -0.3554, -0.0234, -0.7206, +0.2903, -0.9404, -1.5141, -0.2722],
[ -1.2703, -0.7481, +0.4099, -0.7886, +0.2750, -0.0530, -0.6855, -0.7960, +0.2931, +0.0986, +0.2574, +0.3546, -0.1636, -0.6219, +0.3183, +0.1384, -0.0684, -1.2439, -0.8255, -0.1529, +0.2066, -0.4686, +0.3696, -0.2439, -1.6751, +0.7610, -0.5769, -0.5236, +0.2315, -0.4293, +0.7452, +0.6290],
[ +0.1636, -0.0258, -0.0946, +0.5087, -0.2138, -0.5867, -0.1223, +0.0970, -0.5604, -0.3155, +0.2778, +0.2844, -0.6220, +0.0870, +0.1567, -0.8622, +0.2385, +0.3428, +0.1315, +0.2830, -0.3414, -0.1083, -0.0021, +0.4448, -0.1093, +0.5797, +0.5512, +0.0886, +0.2515, -0.1098, -0.5983, -0.1664],
[ +0.0332, -0.1306, +0.2431, -0.5394, -0.2755, -0.4544, +0.3230, +0.0475, -0.4289, +0.1263, -0.7816, +0.2001, +0.1425, +0.2706, -1.0709, -0.3947, -1.3802, -0.1414, -0.1457, -0.7114, -0.6793, -0.0257, -0.8971, -0.2432, +0.0006, -0.3711, +0.2958, -0.0177, +0.1747, -0.0733, -0.3160, -0.6292],
[ +0.2540, +0.4159, -0.4193, +0.4756, -0.5615, -0.0777, -0.1692, -0.2047, -0.6844, -0.2723, +0.0727, -0.1912, +0.0989, +0.1546, +0.4719, -0.2639, -0.1997, +0.2235, +0.5461, +0.2992, -1.6747, -0.3055, -0.7582, +0.0934, +0.2088, -0.2527, +0.2810, -0.0126, -0.2710, -0.7904, -0.2154, -0.5613],
[ -0.2470, +0.1133, -0.1563, -0.4254, +0.5442, +0.1291, +0.2176, +0.0374, -0.8939, -0.4140, +0.1537, -0.1740, +0.9369, -0.0037, -0.4261, -0.7104, -0.7777, +0.1905, -0.5320, -0.1168, +0.0347, -0.0454, -0.3947, -0.6101, +0.2560, -0.2748, -0.0115, +0.0442, -0.0840, -0.0564, -0.2105, -0.3223],
[ -0.0404, +0.1026, -0.3563, -0.2962, -0.7801, -0.2794, -0.1065, +0.4522, +0.2426, +0.1916, -0.8589, +0.1918, +0.4101, -0.1290, -0.3302, +0.1000, -0.0601, -0.2014, -0.7935, +0.4843, -0.6731, +0.2180, +0.1019, -0.2928, +0.0366, -0.4442, -0.0406, -0.4545, -0.2187, +0.1910, +0.9510, -0.1191],
[ +0.0344, -0.6187, -0.1423, +0.3670, -0.7356, -0.0288, -0.1769, -0.9789, -1.3008, -0.4707, +0.1346, -0.1823, -0.2180, -0.4896, -0.0455, -0.7968, -0.3335, +0.6360, +0.2356, -0.0207, -0.2652, +0.2302, -0.3929, +0.2243, +0.6438, +0.7061, +0.2904, +0.1324, -0.4476, +0.2047, -0.6898, -0.6214],
[ -0.0215, -0.7005, -0.0687, +0.0166, -0.3514, -0.0745, +0.0922, +0.5453, +0.0969, +0.0386, -0.0103, +0.1984, -1.0903, -0.2738, -0.4855, +0.3083, +0.2451, +0.5611, -0.3741, +0.2794, +0.0953, -0.3711, -0.1832, -0.2603, +0.3729, +0.2859, -0.3258, -1.2615, +0.0928, -0.1043, +0.1818, +0.1052],
[ +0.2063, -0.4528, -0.0057, -0.0972, -0.1732, +0.0062, -0.5985, +0.2504, -0.3243, -0.5488, -0.1981, +0.0969, -0.8003, -0.2163, -0.6253, +0.1420, -0.1593, +0.1623, -0.0719, +0.0738, +0.3514, -0.4224, +0.0098, -0.0067, +0.2754, +0.1454, -0.3292, -0.0407, -0.7088, +0.7650, -0.0182, -0.0452],
[ -0.1059, -0.6218, +0.1371, -0.2479, -0.0653, -0.0035, -0.3983, +0.0243, -0.2188, -0.3608, +0.3230, -0.6048, +0.0848, -0.9398, +0.1182, -0.2141, +0.0755, +0.1749, -0.5544, +0.0777, +0.0288, -0.4650, -0.1328, +0.0272, -0.1134, -0.5497, -0.7305, +0.2035, -0.1138, -0.3764, -0.1077, -0.0619],
[ -0.2962, -0.2979, -0.5164, -1.1713, -1.1070, -0.3612, +0.0832, +0.5215, +0.4963, +0.1109, -2.0335, +0.0426, +0.6391, +0.1183, -0.3604, -0.0953, +0.1748, +0.1531, +0.1823, +0.3383, -0.3340, -0.1464, +0.0583, -0.7169, +0.1044, -0.1128, +0.1358, -0.5949, -0.5330, +0.0007, +0.4265, -0.1255],
[ -0.6321, -0.4892, -0.1697, -0.0665, -0.1715, -0.0042, -0.1025, +0.2831, +0.3383, +0.0200, +0.3494, +0.2269, +0.0419, +0.0365, -0.4095, +0.2798, -0.3788, +0.0791, -0.6231, -0.0929, -0.2438, -0.3717, +1.1090, -0.7410, +0.5276, -0.0525, +0.1586, -0.7940, -0.1403, +0.5189, +0.4408, +0.2783],
[ +0.0863, -0.1234, +0.1770, +0.1606, -0.0455, -0.0650, -0.5722, -1.1812, +0.1314, -0.7228, +0.3411, -0.0359, -0.0146, +0.0060, +0.2504, -0.1236, +0.2839, -0.7190, +0.0244, +0.0833, +0.0597, +0.0164, +0.1194, +0.2457, -0.8212, -1.6772, +0.3122, -0.0719, +0.1411, -0.3111, -1.3788, +0.1171],
[ -0.4888, -1.0319, -0.1769, +0.1639, +0.0734, -0.4566, -1.0295, +0.5195, -0.5277, +0.0296, -0.0732, +0.2698, -0.4389, -0.6899, -0.6707, +0.0360, -0.0028, -0.6112, -0.8115, -0.2616, -0.0706, -0.5321, -0.2747, -1.1524, -0.0645, -0.0421, -0.3517, -0.4075, -0.1166, +0.6472, +0.0250, -0.3585],
[ -0.3122, -0.2761, -0.0860, -0.2080, -0.2592, -0.1262, -0.0000, +0.0064, +0.3869, -0.0712, +0.0700, -0.9122, +0.1585, -1.0705, -0.4595, +0.1414, -0.4563, -0.3509, +0.1370, -0.4546, +0.0924, -0.5005, +0.8518, -1.4722, +0.4280, -0.2569, -0.1950, -0.3892, +0.0974, +0.0142, -0.0750, -1.0935],
[ -0.2389, -0.1222, +0.1513, -1.0903, -0.0777, +0.2233, -0.2945, -1.0573, -0.6673, -0.9787, +0.4047, -1.2823, +0.0238, -0.9849, +0.1218, -0.0379, +0.1686, -1.5184, -0.0359, -0.2899, -0.0147, -0.2620, -0.0294, +0.1790, -0.4546, -0.1393, -0.2614, -0.1130, +0.3277, -0.5504, -1.4897, +0.4290],
[ +0.3427, -0.1801, -0.9729, -0.2763, -0.8175, -0.2292, -0.2283, -1.0905, -0.3877, -0.3596, -0.0185, -0.5790, -0.1083, +0.1029, +0.2087, -0.2265, +0.3843, +0.3569, +0.4135, +0.1367, +0.1019, -0.0472, -0.1326, +0.3414, +0.3957, +0.2921, +0.2106, -0.0877, -0.3301, -1.3795, -1.9779, -0.4937],
[ +0.1940, -0.2997, -0.4792, +0.2675, -0.6258, -0.0457, -0.5112, -0.0076, -0.6497, -0.7706, +0.1871, -0.1602, -0.0135, +0.4243, -0.5747, -0.5883, +0.4021, -0.2582, +0.3381, +0.3950, +0.0503, +0.0106, +0.2930, +0.2948, +0.0231, +0.4963, +0.6190, +0.3516, -0.9469, -0.0323, -0.0254, -0.3314],
[ -0.0666, -0.3086, +0.0050, -0.7425, +0.0498, -0.1735, +0.0643, -0.7302, -0.2838, -0.4926, +0.2588, -1.0888, +0.0914, -0.2110, +0.3146, +0.0769, +0.1527, -0.7908, +0.1144, -0.4159, -0.1099, -0.2469, +0.1520, +0.3110, -0.6905, +0.1466, -0.1214, -0.5032, +0.0486, -0.3263, +0.0748, +0.4858],
[ +0.3977, -0.0844, +0.0825, -0.0687, -0.8396, +0.2654, -0.0521, -0.1041, -0.5838, -0.3881, -0.0133, +0.0767, +0.3582, +0.1250, -0.3787, +0.2232, -1.6387, +0.1836, -0.2685, -0.4428, +0.1816, -0.1108, +0.1340, +0.0555, -0.0085, +0.0386, +0.1277, +0.0295, -0.7560, +0.0657, +0.0095, +0.0913],
[ -0.3619, +0.2578, +0.3163, +0.1775, +0.1437, -0.1839, +0.1491, -0.4246, +0.3383, -0.5554, +0.2321, +0.2196, -0.2709, -0.0673, +0.0790, +0.0549, +0.0146, -1.4400, -0.3682, -0.4452, +0.1132, -0.0693, +0.4161, -0.0508, -0.2573, +0.3547, +0.2300, -0.0433, +0.3701, -0.0716, +0.0865, +0.3202],
[ -0.2407, -0.3514, -0.2882, -0.1980, +0.3598, -0.3302, +0.3311, +0.1154, +0.1423, -0.2290, -0.6468, +0.2341, +0.0219, -0.3510, -0.8240, +0.1463, -0.3198, -0.0513, -0.9552, -0.2212, -0.1091, -0.5052, +0.1874, -0.1514, -0.7181, +0.1132, -0.5173, +0.2874, +0.4601, +0.3317, +0.1209, -0.4715],
[ +0.4039, -0.0515, -0.1019, +0.4119, +0.1023, -0.0505, +0.3062, -0.5871, -0.3284, -0.6936, -0.2142, -0.0067, -0.8245, +0.0604, +0.2082, +0.2818, +0.4094, -1.2403, +0.2902, -0.4497, +0.3492, -0.2630, +0.2257, +0.2616, -0.0756, +0.3950, +0.1607, -0.4299, -0.0042, -0.3791, +0.0144, +0.3923],
[ +0.2782, -0.1456, -0.0002, +0.3011, -0.2252, +0.0572, +0.1349, -0.1567, -0.2850, -0.2994, +0.1602, -0.0868, -0.5167, +0.4240, +0.2210, +0.1657, +0.0883, -0.1288, -0.0227, -0.3949, +0.1043, -0.1381, +0.0739, -0.0357, -0.1723, -0.2657, +0.1199, -0.1253, -0.8570, +0.1793, +0.0042, +0.2571],
[ +0.1808, +0.0781, -0.0530, +0.3645, -0.0659, -0.0229, +0.0723, -0.2956, +0.0014, +0.0886, -0.2523, -1.1491, +0.1169, +0.1121, -0.8267, +0.0281, -0.1044, -0.2294, +0.0513, -0.9215, +0.2674, +0.0013, -0.0650, +0.2553, +0.0816, -0.7934, +0.2155, -1.3771, -0.1983, -0.3055, +0.2549, +0.0883],
[ -0.1989, -0.3779, +0.2484, +0.0978, +0.3002, -0.2595, -0.0993, -0.7726, -0.0245, -0.6115, +0.0579, -0.7989, -0.0208, -0.0149, -1.4722, +0.3503, -0.1758, -0.4039, -1.9504, -0.2489, -0.2551, +0.0146, -0.1026, -0.6208, +0.3920, -0.8281, -0.3682, -0.3127, +0.1773, -0.0195, -0.3558, -0.4386],
[ +0.3965, +0.2776, -0.0051, -0.3705, -0.3877, +0.0462, +0.2481, +0.0638, -0.5678, +0.2069, -0.2101, -0.3165, +0.0694, +0.3458, -1.0740, -0.2276, -0.2802, +0.1290, +0.3323, -0.6620, -1.0497, +0.0449, -1.4877, +0.6505, -0.0039, -0.5675, +0.1965, +0.1813, -0.1576, +0.2611, +0.0413, -0.7096],
[ -0.2771, -0.2090, +0.3171, -1.1884, +0.0306, -0.0635, -0.3072, +0.1631, -0.3107, -0.4344, +0.0475, -1.1032, +0.0050, -1.6227, -0.2919, +0.1205, +0.2610, -0.8912, -0.0364, -0.0302, +0.2187, -0.3477, -0.2162, +0.0541, -0.1731, -0.5533, -1.1136, -0.3114, -0.0904, +0.0234, -0.1263, -0.4608],
[ +0.2534, +0.2506, -0.5988, +0.3239, -0.5094, +0.2584, -0.1520, -0.3674, -0.5281, -0.2938, -0.0664, +0.3468, +0.1871, +0.4229, -1.1005, +0.0895, -0.1058, -0.2018, +0.5277, +0.1065, -2.9736, +0.0834, -0.4339, +0.5220, -0.3065, +0.0976, +0.4859, -0.0876, -0.5134, +0.0273, -0.4311, -0.0629],
[ -1.0013, -0.7660, +0.4058, -3.0321, +0.0533, +0.0794, -1.2917, -1.0423, +0.0235, -0.2441, +0.2986, +0.2793, +0.3185, -0.7738, +0.0709, +0.1806, +0.0065, -0.3429, -0.5904, -0.2240, -0.2247, -0.1551, +0.2479, -0.7799, -0.4368, +0.2717, -0.3030, +0.2230, -0.1252, -0.1713, -0.4256, +0.0946],
[ -0.5044, -0.3197, -0.0715, -0.0414, -0.2140, -0.2098, +0.3549, +0.0071, +0.2459, +0.0855, -0.4905, +0.4785, -0.0644, -0.0442, -0.5088, +0.1229, +0.3045, +0.0949, +0.5608, +0.0035, +0.2524, -0.1201, +0.4582, -0.9841, -0.2432, -0.4455, +0.1591, -0.0743, +0.1235, +0.1924, -0.2510, -0.0401],
[ +0.5910, -0.1650, -0.3341, +0.3136, -0.0819, -0.1846, -0.3609, +0.2772, -0.0841, +0.0612, -1.0691, +0.0500, -0.9307, +0.4375, -0.9497, -0.0597, -0.7687, +0.2086, +0.2169, -0.2657, -0.5765, -0.1814, -1.1223, +0.2315, +0.8662, +0.0936, +0.0851, -1.8539, -0.0759, +0.4064, +0.2069, -0.8922],
[ -0.1478, +0.3415, -0.2042, +0.5568, -0.7672, -0.1465, -0.1311, -0.2273, +0.0602, -0.2321, -0.2689, +0.1515, -1.0434, +0.2948, -0.4986, +0.1426, -0.7398, -0.4810, -0.0648, -0.3290, -0.1646, -0.1314, +0.0100, +0.3540, -0.2790, -0.0118, +0.4205, -0.5476, -0.1409, -0.1341, +0.3308, +0.1991],
[ +0.1532, -0.2862, -1.0844, +0.2213, -1.5302, -0.1382, -0.3119, -1.5098, -0.5984, -0.8033, +0.0835, -0.5982, -0.9022, +0.0325, -0.0693, -0.7834, +0.2342, +0.2223, +0.3314, +0.1252, +0.2134, -0.1843, -0.2085, +0.3213, +0.2308, +0.4200, +0.0852, -0.1438, -0.4427, +0.2863, -0.6166, -0.2677],
[ +0.2118, -0.5590, -0.3589, +0.1854, -1.1902, -0.2337, +0.3533, -0.0890, -0.3013, +0.4551, -0.2130, -1.0383, -0.2290, -0.1976, -1.3175, -0.5657, -0.2857, +0.5560, +0.1437, -0.3211, +0.1788, -0.1494, -1.0336, +0.2679, +0.5221, +0.5256, +0.1761, -0.0573, -0.2895, -0.0307, -0.2395, -0.8144],
[ -0.6139, -1.0856, -0.5362, -1.1959, -0.3413, -0.2647, -0.3687, +0.4510, +0.0818, +0.0710, -0.3482, -0.0611, +0.0474, -0.7248, -0.3042, -0.0303, -0.3762, +0.1941, -0.8735, +0.1872, -0.3612, -0.4090, +0.2817, -0.5842, +0.5135, +0.8080, -0.9240, -0.1925, -0.6654, +0.4267, +0.5304, -0.3396],
[ +0.1054, -0.1771, -0.1990, +0.3935, -0.1743, +0.0638, +0.3047, -0.0899, +0.4220, +0.1633, +0.1666, +0.1688, +0.0731, -0.0455, +0.2421, +0.4481, +0.5427, -0.1530, -0.1694, +0.4192, -0.3225, +0.1410, +0.2042, -2.2442, -0.4848, -0.9054, -0.2178, +0.3965, +0.4502, +0.1305, -0.0444, +0.1641],
[ +0.1336, +0.4509, +0.0056, +0.0940, -0.3145, -0.1580, -0.1152, -0.2864, -0.0145, -0.3372, +0.1072, -0.3662, -0.9957, +0.3660, +0.1886, -0.2086, +0.2193, -0.6053, +0.0879, +0.0350, +0.0216, +0.3407, -0.0691, +0.1355, -0.2493, -1.5064, +0.3744, -0.2654, -0.1921, -0.6361, -0.6030, +0.3290],
[ -0.4868, -0.0926, +0.1334, -0.8699, +0.0689, +0.1350, +0.0003, -1.6050, -0.2677, -0.6097, +0.0119, -1.0122, -0.1318, -0.8405, -0.1366, -0.1088, +0.0375, -1.0216, -0.0891, -0.2447, -0.0060, -0.3751, +0.1240, +0.0514, -0.5080, -1.2536, +0.4369, -0.1020, +0.1563, -0.6330, -2.3150, +0.0109],
[ -0.5112, +0.0425, -0.1887, -0.0305, +0.0264, +0.3452, -0.0750, +0.4954, +0.4284, -0.0069, +0.2399, +0.9169, -0.3441, +0.0420, -0.3492, +0.4726, -0.1203, -0.0110, -1.1251, -0.1880, -0.2703, -0.1990, +0.8598, -0.0085, +0.4910, -0.1798, +0.1495, -0.4904, -0.3907, +0.5274, +0.4777, +0.4670],
[ +0.4048, -0.2962, -0.0535, +0.3467, -0.0456, -0.0875, -0.0220, -0.2064, -0.8052, -0.2940, -0.1660, -1.3446, -0.0124, -0.3980, -0.0199, +0.0871, -0.4781, -1.0247, +0.2848, -0.2992, -0.1778, -0.0626, -0.0618, +0.0792, -0.7679, -1.4193, +0.0787, -0.3910, -0.1448, -0.2650, -0.3079, -1.2104],
[ +0.4581, -0.6689, -0.1144, -0.1282, -2.0230, -0.1221, -0.2954, -1.2605, -1.0560, -0.8669, +0.2610, -0.3799, -0.2883, -0.2970, +0.1364, -1.5987, +0.2303, +0.6106, +0.3841, +0.0955, -0.3148, -0.2655, +0.0052, +0.2312, +0.1658, +0.4766, +0.1847, -0.1055, -0.8075, -0.1123, -0.6706, -0.6556],
[ +0.1192, -0.1971, +0.4472, +0.1296, +0.0370, -0.1341, -0.7736, -0.1778, -0.0172, -0.2200, +0.1248, -0.4126, -0.3722, -0.2830, +0.0294, +0.2753, -0.2527, -1.0083, -0.7886, -1.5356, +0.0627, -0.2736, +0.4009, -0.4766, -0.2815, +0.8060, -0.0681, -0.8295, +0.4980, -0.0494, +0.4414, +0.4709],
[ -0.2893, -0.0060, +0.1617, +0.3636, -0.0534, -0.1653, +0.2161, -0.2260, +0.0668, -0.3423, +0.0087, +0.3678, -0.1448, +0.3106, +0.2831, +0.0889, -0.1325, -0.0667, -0.1139, +0.1482, +0.1164, -0.1613, +0.0733, +0.0005, -0.0419, -0.0656, +0.0986, -0.1560, -0.1506, -0.1254, -0.0902, +0.2643],
[ -0.2274, -0.5965, -0.0342, -0.6827, -0.1276, +0.0802, -1.2401, +0.2169, +0.0531, -0.0964, +0.2187, +0.0299, +0.2797, -0.7842, -0.5032, +0.1321, -0.2005, -0.3383, -0.3343, +0.1237, -0.0915, -0.6670, +0.0473, -0.6602, +0.1260, -1.2568, -0.2235, +0.1255, +0.3263, +0.1078, -0.0685, -0.0085],
[ +0.3530, -0.3798, -0.5576, +0.1040, -0.1875, +0.1399, -0.1539, -1.3570, -0.1105, +0.0370, -0.4067, +0.2991, +0.2811, +0.1082, -0.0573, +0.2104, -0.1550, +0.3365, +0.5019, +0.4842, +0.4671, +0.2578, -0.0029, +0.0016, -0.1533, -0.2459, +0.1866, +0.0699, -0.1873, -1.1082, -0.9151, -0.1758],
[ +0.2397, +0.2045, -0.2370, -0.3293, -0.3153, -0.2131, +0.1407, -0.0721, +0.0723, -0.0019, -0.3940, +0.1340, +0.3550, +0.1190, -0.6068, -0.0747, -0.7712, +0.1922, +0.6519, -0.0651, -0.4332, +0.0494, -0.7192, +0.4279, -0.1762, -0.5548, +0.1749, -0.2149, -0.6916, -0.0448, -0.1025, +0.0212],
[ -0.1101, -0.2853, -0.3405, +0.3059, -0.5009, +0.1139, +0.0602, -0.5256, -0.9340, +0.1189, -0.9900, -0.5092, -1.9114, +0.1249, -0.7890, -1.1437, -0.4686, +0.3687, -0.2993, -0.1058, +0.0966, -0.0284, -0.4845, -0.1683, +0.3489, -0.0173, -0.0521, -0.1265, -0.0182, -0.2870, +0.0246, -1.0009],
[ -0.1411, +0.1840, -0.3968, +0.2893, -0.9532, -0.2235, -0.1156, -0.7018, -0.2859, -0.1742, -0.6094, -0.0247, -1.0472, +0.1916, -0.4825, -0.4209, +0.2371, +0.0900, +0.0646, -0.1665, +0.5168, +0.0670, -0.1779, +0.3494, +0.3035, +0.0548, +0.2939, -0.3871, -0.0828, -0.5370, +0.0804, -0.2175],
[ +0.4992, +0.1187, -0.0464, +0.7284, +0.1106, -0.0542, -0.3548, +0.3451, +0.0281, -0.4796, -0.2282, -0.3789, -0.1253, -0.0824, -0.3919, +0.1890, -0.1683, -2.1362, -0.9594, -0.6882, +0.6158, -0.2412, +0.2336, -0.0142, -0.9257, +0.3819, -0.1836, -0.7676, +0.3713, -0.1364, +0.3317, +0.3696]
[
+0.1063, +0.2017, +0.0029, -0.2442, -0.1362, +0.2871, +0.2270, -0.1260,
+0.5271, -0.1744, -0.4323, +0.3637, -0.0083, -0.0547, +0.4549, -0.0164,
+0.0913, -0.1635, +0.3583, +0.3020, +0.2240, -0.3561, +0.0689, +0.0126,
+0.0508, -1.2876, -0.0003, -0.0464, -0.2184, -0.2538, -0.5314, +0.5790
],
[
-0.2180, +0.9455, +0.1446, -0.0724, +0.3771, -0.4290, +0.3908, -0.1787,
-0.1009, -0.0539, -0.5364, -0.5032, -0.0631, -0.1185, -0.9890, +0.1935,
-1.3280, -0.9275, +0.0670, -0.4234, -0.2061, +0.2674, +0.2963, +0.5353,
-0.0221, -0.3095, +0.3255, -0.4568, +0.1337, -0.2826, -0.0538, -1.2748
],
[
+0.3038, +0.0690, +0.1495, -0.1801, -0.0140, -0.1370, -0.2094, -1.9336,
+0.2150, -0.5506, +0.3097, -0.9412, +0.1507, -0.0708, -0.8874, -0.1183,
-0.0580, -0.7503, +0.2276, -0.3497, +0.0067, +0.2541, -0.1207, +0.5209,
+0.5381, -1.2157, +0.4692, -0.0536, -0.2078, -0.9902, -1.0954, -1.3646
],
[
+0.0581, -1.0529, -0.0581, +0.0473, -0.1228, +0.0913, -0.7037, +0.0711,
+0.2062, -0.2102, +0.0475, -0.5266, +0.1324, -1.7822, -0.2985, +0.0172,
+0.0110, -0.1624, -0.3990, -0.3165, +0.1287, -0.5655, +1.3905, -1.5117,
+0.1874, -0.5032, -0.3292, +0.3378, -0.4749, +0.0765, +0.4345, -0.1121
],
[
-0.1315, +0.2873, -1.0164, +0.2925, -0.5024, +0.2321, -1.3038, -0.7796,
+0.0830, -0.3378, -0.1037, +0.0033, -0.7885, +0.4841, +0.1578, +0.1771,
+0.1991, -0.1073, -0.0181, +0.0496, +0.0919, +0.0585, +0.4595, +0.1634,
-0.2220, -0.0226, +0.4703, -1.8576, +0.3075, -0.4581, +0.2507, +0.2085
],
[
+0.2704, +0.0379, +0.2313, -0.5561, -0.7413, -0.7693, +0.4787, +0.3033,
-1.3572, -0.1323, -0.5202, -0.6937, -0.6824, -0.1782, -1.1647, -0.3461,
-0.8537, +0.5416, +0.0638, -0.4208, -0.4464, +0.0009, -0.4284, +0.1806,
+0.4172, -0.5477, +0.5549, +0.1937, -0.6029, +0.2084, -0.8289, -0.4554
],
[
+0.3719, +0.4292, +0.2655, -0.1071, -0.1848, -0.0651, -0.4942, +0.0514,
-0.1364, -0.1573, -0.0880, -0.4625, -0.0889, +0.2049, -1.2166, -0.2164,
-0.3680, -0.7242, -0.1208, -0.3569, +0.0591, +0.3773, -1.2525, +0.4139,
-0.1203, -0.2808, -0.2460, -0.3056, -0.2309, +0.1638, +0.1502, -0.2354
],
[
+0.2204, +0.3725, +0.1919, +0.1579, +0.0064, +0.0469, -0.5103, -0.5866,
+0.0043, -0.2127, -0.0816, +0.4270, -0.0504, +0.2804, -0.1278, -0.0507,
+0.1206, -0.6903, -0.2278, -0.0725, +0.2198, +0.1067, +0.2162, +0.2341,
-0.6394, -1.2196, +0.3075, -1.0066, +0.2299, -0.1218, -0.0533, +0.3365
],
[
+0.2458, -0.1112, -0.6971, +0.1730, +0.0093, -0.0066, -0.2500, -1.2508,
-0.0108, -0.4091, -0.5608, -0.0239, +0.4287, -0.1187, +0.0476, -0.1859,
+0.1335, +0.0564, +0.2657, +0.3620, +0.4023, +0.0518, -0.1151, +0.0172,
+0.0270, -0.4894, +0.3967, +0.1362, +0.1078, -1.4673, -0.6417, +0.0105
],
[
-1.2388, -0.5692, +0.2738, -0.8659, +0.1514, +0.0501, -0.3654, -0.9175,
+0.1314, -0.4386, +0.1715, +0.2538, +0.1051, -0.1091, +0.1875, -0.0295,
-0.4012, -0.5032, -0.6742, -0.1109, +0.1125, -0.5023, -0.2032, -0.2740,
-0.9510, +0.9708, -0.0643, -0.5463, -0.0895, -0.7491, +0.6833, +0.1855
],
[
-0.4298, -0.0464, -0.0294, -0.0743, +0.0902, -0.6215, +0.0848, -0.3727,
+0.2700, -0.3201, -0.2578, +0.2471, -0.6535, +0.2581, +0.2505, -0.1900,
+0.1637, -1.5921, -0.1360, -0.0777, -0.0092, +0.0816, +0.0996, -0.0197,
-0.7934, +0.0909, +0.2011, +0.1988, +0.1273, -0.0366, +0.0466, +0.1477
],
[
+0.1492, +0.1446, +0.4695, -0.4109, -0.0883, -0.1199, +0.5098, +0.4549,
-0.2600, +0.1315, -0.2831, +0.4905, +0.0915, +0.1289, -1.1824, +0.3743,
-0.3307, -0.2300, -0.6317, -0.2493, -1.2151, -0.1466, -0.4567, -1.0819,
+0.2878, -1.0267, +0.2882, +0.5518, -0.0761, +0.3592, +0.1387, -0.6827
],
[
+0.1444, -0.1397, +0.1136, +0.0452, -0.3338, +0.1050, +0.2811, -0.1238,
-0.4973, -0.0804, +0.0148, +0.1621, -0.8240, +0.2157, +0.1887, +0.0192,
-1.2242, +0.2255, -0.2271, -0.4326, -0.0362, +0.0116, -0.2229, +0.4142,
+0.3929, -0.2313, +0.1735, +0.0598, +0.1726, +0.1078, +0.1444, +0.3110
],
[
-0.7894, -0.0617, +0.3583, -0.7723, +0.1178, +0.0533, -0.2285, -1.2298,
+0.1727, -0.3313, +0.1193, -0.6488, +0.2996, -0.5132, -0.3868, +0.0174,
+0.1475, +0.3516, -0.5912, -0.8573, +0.0606, -0.0528, -0.1981, +0.0196,
-0.1688, -0.3554, -0.0234, -0.7206, +0.2903, -0.9404, -1.5141, -0.2722
],
[
-1.2703, -0.7481, +0.4099, -0.7886, +0.2750, -0.0530, -0.6855, -0.7960,
+0.2931, +0.0986, +0.2574, +0.3546, -0.1636, -0.6219, +0.3183, +0.1384,
-0.0684, -1.2439, -0.8255, -0.1529, +0.2066, -0.4686, +0.3696, -0.2439,
-1.6751, +0.7610, -0.5769, -0.5236, +0.2315, -0.4293, +0.7452, +0.6290
],
[
+0.1636, -0.0258, -0.0946, +0.5087, -0.2138, -0.5867, -0.1223, +0.0970,
-0.5604, -0.3155, +0.2778, +0.2844, -0.6220, +0.0870, +0.1567, -0.8622,
+0.2385, +0.3428, +0.1315, +0.2830, -0.3414, -0.1083, -0.0021, +0.4448,
-0.1093, +0.5797, +0.5512, +0.0886, +0.2515, -0.1098, -0.5983, -0.1664
],
[
+0.0332, -0.1306, +0.2431, -0.5394, -0.2755, -0.4544, +0.3230, +0.0475,
-0.4289, +0.1263, -0.7816, +0.2001, +0.1425, +0.2706, -1.0709, -0.3947,
-1.3802, -0.1414, -0.1457, -0.7114, -0.6793, -0.0257, -0.8971, -0.2432,
+0.0006, -0.3711, +0.2958, -0.0177, +0.1747, -0.0733, -0.3160, -0.6292
],
[
+0.2540, +0.4159, -0.4193, +0.4756, -0.5615, -0.0777, -0.1692, -0.2047,
-0.6844, -0.2723, +0.0727, -0.1912, +0.0989, +0.1546, +0.4719, -0.2639,
-0.1997, +0.2235, +0.5461, +0.2992, -1.6747, -0.3055, -0.7582, +0.0934,
+0.2088, -0.2527, +0.2810, -0.0126, -0.2710, -0.7904, -0.2154, -0.5613
],
[
-0.2470, +0.1133, -0.1563, -0.4254, +0.5442, +0.1291, +0.2176, +0.0374,
-0.8939, -0.4140, +0.1537, -0.1740, +0.9369, -0.0037, -0.4261, -0.7104,
-0.7777, +0.1905, -0.5320, -0.1168, +0.0347, -0.0454, -0.3947, -0.6101,
+0.2560, -0.2748, -0.0115, +0.0442, -0.0840, -0.0564, -0.2105, -0.3223
],
[
-0.0404, +0.1026, -0.3563, -0.2962, -0.7801, -0.2794, -0.1065, +0.4522,
+0.2426, +0.1916, -0.8589, +0.1918, +0.4101, -0.1290, -0.3302, +0.1000,
-0.0601, -0.2014, -0.7935, +0.4843, -0.6731, +0.2180, +0.1019, -0.2928,
+0.0366, -0.4442, -0.0406, -0.4545, -0.2187, +0.1910, +0.9510, -0.1191
],
[
+0.0344, -0.6187, -0.1423, +0.3670, -0.7356, -0.0288, -0.1769, -0.9789,
-1.3008, -0.4707, +0.1346, -0.1823, -0.2180, -0.4896, -0.0455, -0.7968,
-0.3335, +0.6360, +0.2356, -0.0207, -0.2652, +0.2302, -0.3929, +0.2243,
+0.6438, +0.7061, +0.2904, +0.1324, -0.4476, +0.2047, -0.6898, -0.6214
],
[
-0.0215, -0.7005, -0.0687, +0.0166, -0.3514, -0.0745, +0.0922, +0.5453,
+0.0969, +0.0386, -0.0103, +0.1984, -1.0903, -0.2738, -0.4855, +0.3083,
+0.2451, +0.5611, -0.3741, +0.2794, +0.0953, -0.3711, -0.1832, -0.2603,
+0.3729, +0.2859, -0.3258, -1.2615, +0.0928, -0.1043, +0.1818, +0.1052
],
[
+0.2063, -0.4528, -0.0057, -0.0972, -0.1732, +0.0062, -0.5985, +0.2504,
-0.3243, -0.5488, -0.1981, +0.0969, -0.8003, -0.2163, -0.6253, +0.1420,
-0.1593, +0.1623, -0.0719, +0.0738, +0.3514, -0.4224, +0.0098, -0.0067,
+0.2754, +0.1454, -0.3292, -0.0407, -0.7088, +0.7650, -0.0182, -0.0452
],
[
-0.1059, -0.6218, +0.1371, -0.2479, -0.0653, -0.0035, -0.3983, +0.0243,
-0.2188, -0.3608, +0.3230, -0.6048, +0.0848, -0.9398, +0.1182, -0.2141,
+0.0755, +0.1749, -0.5544, +0.0777, +0.0288, -0.4650, -0.1328, +0.0272,
-0.1134, -0.5497, -0.7305, +0.2035, -0.1138, -0.3764, -0.1077, -0.0619
],
[
-0.2962, -0.2979, -0.5164, -1.1713, -1.1070, -0.3612, +0.0832, +0.5215,
+0.4963, +0.1109, -2.0335, +0.0426, +0.6391, +0.1183, -0.3604, -0.0953,
+0.1748, +0.1531, +0.1823, +0.3383, -0.3340, -0.1464, +0.0583, -0.7169,
+0.1044, -0.1128, +0.1358, -0.5949, -0.5330, +0.0007, +0.4265, -0.1255
],
[
-0.6321, -0.4892, -0.1697, -0.0665, -0.1715, -0.0042, -0.1025, +0.2831,
+0.3383, +0.0200, +0.3494, +0.2269, +0.0419, +0.0365, -0.4095, +0.2798,
-0.3788, +0.0791, -0.6231, -0.0929, -0.2438, -0.3717, +1.1090, -0.7410,
+0.5276, -0.0525, +0.1586, -0.7940, -0.1403, +0.5189, +0.4408, +0.2783
],
[
+0.0863, -0.1234, +0.1770, +0.1606, -0.0455, -0.0650, -0.5722, -1.1812,
+0.1314, -0.7228, +0.3411, -0.0359, -0.0146, +0.0060, +0.2504, -0.1236,
+0.2839, -0.7190, +0.0244, +0.0833, +0.0597, +0.0164, +0.1194, +0.2457,
-0.8212, -1.6772, +0.3122, -0.0719, +0.1411, -0.3111, -1.3788, +0.1171
],
[
-0.4888, -1.0319, -0.1769, +0.1639, +0.0734, -0.4566, -1.0295, +0.5195,
-0.5277, +0.0296, -0.0732, +0.2698, -0.4389, -0.6899, -0.6707, +0.0360,
-0.0028, -0.6112, -0.8115, -0.2616, -0.0706, -0.5321, -0.2747, -1.1524,
-0.0645, -0.0421, -0.3517, -0.4075, -0.1166, +0.6472, +0.0250, -0.3585
],
[
-0.3122, -0.2761, -0.0860, -0.2080, -0.2592, -0.1262, -0.0000, +0.0064,
+0.3869, -0.0712, +0.0700, -0.9122, +0.1585, -1.0705, -0.4595, +0.1414,
-0.4563, -0.3509, +0.1370, -0.4546, +0.0924, -0.5005, +0.8518, -1.4722,
+0.4280, -0.2569, -0.1950, -0.3892, +0.0974, +0.0142, -0.0750, -1.0935
],
[
-0.2389, -0.1222, +0.1513, -1.0903, -0.0777, +0.2233, -0.2945, -1.0573,
-0.6673, -0.9787, +0.4047, -1.2823, +0.0238, -0.9849, +0.1218, -0.0379,
+0.1686, -1.5184, -0.0359, -0.2899, -0.0147, -0.2620, -0.0294, +0.1790,
-0.4546, -0.1393, -0.2614, -0.1130, +0.3277, -0.5504, -1.4897, +0.4290
],
[
+0.3427, -0.1801, -0.9729, -0.2763, -0.8175, -0.2292, -0.2283, -1.0905,
-0.3877, -0.3596, -0.0185, -0.5790, -0.1083, +0.1029, +0.2087, -0.2265,
+0.3843, +0.3569, +0.4135, +0.1367, +0.1019, -0.0472, -0.1326, +0.3414,
+0.3957, +0.2921, +0.2106, -0.0877, -0.3301, -1.3795, -1.9779, -0.4937
],
[
+0.1940, -0.2997, -0.4792, +0.2675, -0.6258, -0.0457, -0.5112, -0.0076,
-0.6497, -0.7706, +0.1871, -0.1602, -0.0135, +0.4243, -0.5747, -0.5883,
+0.4021, -0.2582, +0.3381, +0.3950, +0.0503, +0.0106, +0.2930, +0.2948,
+0.0231, +0.4963, +0.6190, +0.3516, -0.9469, -0.0323, -0.0254, -0.3314
],
[
-0.0666, -0.3086, +0.0050, -0.7425, +0.0498, -0.1735, +0.0643, -0.7302,
-0.2838, -0.4926, +0.2588, -1.0888, +0.0914, -0.2110, +0.3146, +0.0769,
+0.1527, -0.7908, +0.1144, -0.4159, -0.1099, -0.2469, +0.1520, +0.3110,
-0.6905, +0.1466, -0.1214, -0.5032, +0.0486, -0.3263, +0.0748, +0.4858
],
[
+0.3977, -0.0844, +0.0825, -0.0687, -0.8396, +0.2654, -0.0521, -0.1041,
-0.5838, -0.3881, -0.0133, +0.0767, +0.3582, +0.1250, -0.3787, +0.2232,
-1.6387, +0.1836, -0.2685, -0.4428, +0.1816, -0.1108, +0.1340, +0.0555,
-0.0085, +0.0386, +0.1277, +0.0295, -0.7560, +0.0657, +0.0095, +0.0913
],
[
-0.3619, +0.2578, +0.3163, +0.1775, +0.1437, -0.1839, +0.1491, -0.4246,
+0.3383, -0.5554, +0.2321, +0.2196, -0.2709, -0.0673, +0.0790, +0.0549,
+0.0146, -1.4400, -0.3682, -0.4452, +0.1132, -0.0693, +0.4161, -0.0508,
-0.2573, +0.3547, +0.2300, -0.0433, +0.3701, -0.0716, +0.0865, +0.3202
],
[
-0.2407, -0.3514, -0.2882, -0.1980, +0.3598, -0.3302, +0.3311, +0.1154,
+0.1423, -0.2290, -0.6468, +0.2341, +0.0219, -0.3510, -0.8240, +0.1463,
-0.3198, -0.0513, -0.9552, -0.2212, -0.1091, -0.5052, +0.1874, -0.1514,
-0.7181, +0.1132, -0.5173, +0.2874, +0.4601, +0.3317, +0.1209, -0.4715
],
[
+0.4039, -0.0515, -0.1019, +0.4119, +0.1023, -0.0505, +0.3062, -0.5871,
-0.3284, -0.6936, -0.2142, -0.0067, -0.8245, +0.0604, +0.2082, +0.2818,
+0.4094, -1.2403, +0.2902, -0.4497, +0.3492, -0.2630, +0.2257, +0.2616,
-0.0756, +0.3950, +0.1607, -0.4299, -0.0042, -0.3791, +0.0144, +0.3923
],
[
+0.2782, -0.1456, -0.0002, +0.3011, -0.2252, +0.0572, +0.1349, -0.1567,
-0.2850, -0.2994, +0.1602, -0.0868, -0.5167, +0.4240, +0.2210, +0.1657,
+0.0883, -0.1288, -0.0227, -0.3949, +0.1043, -0.1381, +0.0739, -0.0357,
-0.1723, -0.2657, +0.1199, -0.1253, -0.8570, +0.1793, +0.0042, +0.2571
],
[
+0.1808, +0.0781, -0.0530, +0.3645, -0.0659, -0.0229, +0.0723, -0.2956,
+0.0014, +0.0886, -0.2523, -1.1491, +0.1169, +0.1121, -0.8267, +0.0281,
-0.1044, -0.2294, +0.0513, -0.9215, +0.2674, +0.0013, -0.0650, +0.2553,
+0.0816, -0.7934, +0.2155, -1.3771, -0.1983, -0.3055, +0.2549, +0.0883
],
[
-0.1989, -0.3779, +0.2484, +0.0978, +0.3002, -0.2595, -0.0993, -0.7726,
-0.0245, -0.6115, +0.0579, -0.7989, -0.0208, -0.0149, -1.4722, +0.3503,
-0.1758, -0.4039, -1.9504, -0.2489, -0.2551, +0.0146, -0.1026, -0.6208,
+0.3920, -0.8281, -0.3682, -0.3127, +0.1773, -0.0195, -0.3558, -0.4386
],
[
+0.3965, +0.2776, -0.0051, -0.3705, -0.3877, +0.0462, +0.2481, +0.0638,
-0.5678, +0.2069, -0.2101, -0.3165, +0.0694, +0.3458, -1.0740, -0.2276,
-0.2802, +0.1290, +0.3323, -0.6620, -1.0497, +0.0449, -1.4877, +0.6505,
-0.0039, -0.5675, +0.1965, +0.1813, -0.1576, +0.2611, +0.0413, -0.7096
],
[
-0.2771, -0.2090, +0.3171, -1.1884, +0.0306, -0.0635, -0.3072, +0.1631,
-0.3107, -0.4344, +0.0475, -1.1032, +0.0050, -1.6227, -0.2919, +0.1205,
+0.2610, -0.8912, -0.0364, -0.0302, +0.2187, -0.3477, -0.2162, +0.0541,
-0.1731, -0.5533, -1.1136, -0.3114, -0.0904, +0.0234, -0.1263, -0.4608
],
[
+0.2534, +0.2506, -0.5988, +0.3239, -0.5094, +0.2584, -0.1520, -0.3674,
-0.5281, -0.2938, -0.0664, +0.3468, +0.1871, +0.4229, -1.1005, +0.0895,
-0.1058, -0.2018, +0.5277, +0.1065, -2.9736, +0.0834, -0.4339, +0.5220,
-0.3065, +0.0976, +0.4859, -0.0876, -0.5134, +0.0273, -0.4311, -0.0629
],
[
-1.0013, -0.7660, +0.4058, -3.0321, +0.0533, +0.0794, -1.2917, -1.0423,
+0.0235, -0.2441, +0.2986, +0.2793, +0.3185, -0.7738, +0.0709, +0.1806,
+0.0065, -0.3429, -0.5904, -0.2240, -0.2247, -0.1551, +0.2479, -0.7799,
-0.4368, +0.2717, -0.3030, +0.2230, -0.1252, -0.1713, -0.4256, +0.0946
],
[
-0.5044, -0.3197, -0.0715, -0.0414, -0.2140, -0.2098, +0.3549, +0.0071,
+0.2459, +0.0855, -0.4905, +0.4785, -0.0644, -0.0442, -0.5088, +0.1229,
+0.3045, +0.0949, +0.5608, +0.0035, +0.2524, -0.1201, +0.4582, -0.9841,
-0.2432, -0.4455, +0.1591, -0.0743, +0.1235, +0.1924, -0.2510, -0.0401
],
[
+0.5910, -0.1650, -0.3341, +0.3136, -0.0819, -0.1846, -0.3609, +0.2772,
-0.0841, +0.0612, -1.0691, +0.0500, -0.9307, +0.4375, -0.9497, -0.0597,
-0.7687, +0.2086, +0.2169, -0.2657, -0.5765, -0.1814, -1.1223, +0.2315,
+0.8662, +0.0936, +0.0851, -1.8539, -0.0759, +0.4064, +0.2069, -0.8922
],
[
-0.1478, +0.3415, -0.2042, +0.5568, -0.7672, -0.1465, -0.1311, -0.2273,
+0.0602, -0.2321, -0.2689, +0.1515, -1.0434, +0.2948, -0.4986, +0.1426,
-0.7398, -0.4810, -0.0648, -0.3290, -0.1646, -0.1314, +0.0100, +0.3540,
-0.2790, -0.0118, +0.4205, -0.5476, -0.1409, -0.1341, +0.3308, +0.1991
],
[
+0.1532, -0.2862, -1.0844, +0.2213, -1.5302, -0.1382, -0.3119, -1.5098,
-0.5984, -0.8033, +0.0835, -0.5982, -0.9022, +0.0325, -0.0693, -0.7834,
+0.2342, +0.2223, +0.3314, +0.1252, +0.2134, -0.1843, -0.2085, +0.3213,
+0.2308, +0.4200, +0.0852, -0.1438, -0.4427, +0.2863, -0.6166, -0.2677
],
[
+0.2118, -0.5590, -0.3589, +0.1854, -1.1902, -0.2337, +0.3533, -0.0890,
-0.3013, +0.4551, -0.2130, -1.0383, -0.2290, -0.1976, -1.3175, -0.5657,
-0.2857, +0.5560, +0.1437, -0.3211, +0.1788, -0.1494, -1.0336, +0.2679,
+0.5221, +0.5256, +0.1761, -0.0573, -0.2895, -0.0307, -0.2395, -0.8144
],
[
-0.6139, -1.0856, -0.5362, -1.1959, -0.3413, -0.2647, -0.3687, +0.4510,
+0.0818, +0.0710, -0.3482, -0.0611, +0.0474, -0.7248, -0.3042, -0.0303,
-0.3762, +0.1941, -0.8735, +0.1872, -0.3612, -0.4090, +0.2817, -0.5842,
+0.5135, +0.8080, -0.9240, -0.1925, -0.6654, +0.4267, +0.5304, -0.3396
],
[
+0.1054, -0.1771, -0.1990, +0.3935, -0.1743, +0.0638, +0.3047, -0.0899,
+0.4220, +0.1633, +0.1666, +0.1688, +0.0731, -0.0455, +0.2421, +0.4481,
+0.5427, -0.1530, -0.1694, +0.4192, -0.3225, +0.1410, +0.2042, -2.2442,
-0.4848, -0.9054, -0.2178, +0.3965, +0.4502, +0.1305, -0.0444, +0.1641
],
[
+0.1336, +0.4509, +0.0056, +0.0940, -0.3145, -0.1580, -0.1152, -0.2864,
-0.0145, -0.3372, +0.1072, -0.3662, -0.9957, +0.3660, +0.1886, -0.2086,
+0.2193, -0.6053, +0.0879, +0.0350, +0.0216, +0.3407, -0.0691, +0.1355,
-0.2493, -1.5064, +0.3744, -0.2654, -0.1921, -0.6361, -0.6030, +0.3290
],
[
-0.4868, -0.0926, +0.1334, -0.8699, +0.0689, +0.1350, +0.0003, -1.6050,
-0.2677, -0.6097, +0.0119, -1.0122, -0.1318, -0.8405, -0.1366, -0.1088,
+0.0375, -1.0216, -0.0891, -0.2447, -0.0060, -0.3751, +0.1240, +0.0514,
-0.5080, -1.2536, +0.4369, -0.1020, +0.1563, -0.6330, -2.3150, +0.0109
],
[
-0.5112, +0.0425, -0.1887, -0.0305, +0.0264, +0.3452, -0.0750, +0.4954,
+0.4284, -0.0069, +0.2399, +0.9169, -0.3441, +0.0420, -0.3492, +0.4726,
-0.1203, -0.0110, -1.1251, -0.1880, -0.2703, -0.1990, +0.8598, -0.0085,
+0.4910, -0.1798, +0.1495, -0.4904, -0.3907, +0.5274, +0.4777, +0.4670
],
[
+0.4048, -0.2962, -0.0535, +0.3467, -0.0456, -0.0875, -0.0220, -0.2064,
-0.8052, -0.2940, -0.1660, -1.3446, -0.0124, -0.3980, -0.0199, +0.0871,
-0.4781, -1.0247, +0.2848, -0.2992, -0.1778, -0.0626, -0.0618, +0.0792,
-0.7679, -1.4193, +0.0787, -0.3910, -0.1448, -0.2650, -0.3079, -1.2104
],
[
+0.4581, -0.6689, -0.1144, -0.1282, -2.0230, -0.1221, -0.2954, -1.2605,
-1.0560, -0.8669, +0.2610, -0.3799, -0.2883, -0.2970, +0.1364, -1.5987,
+0.2303, +0.6106, +0.3841, +0.0955, -0.3148, -0.2655, +0.0052, +0.2312,
+0.1658, +0.4766, +0.1847, -0.1055, -0.8075, -0.1123, -0.6706, -0.6556
],
[
+0.1192, -0.1971, +0.4472, +0.1296, +0.0370, -0.1341, -0.7736, -0.1778,
-0.0172, -0.2200, +0.1248, -0.4126, -0.3722, -0.2830, +0.0294, +0.2753,
-0.2527, -1.0083, -0.7886, -1.5356, +0.0627, -0.2736, +0.4009, -0.4766,
-0.2815, +0.8060, -0.0681, -0.8295, +0.4980, -0.0494, +0.4414, +0.4709
],
[
-0.2893, -0.0060, +0.1617, +0.3636, -0.0534, -0.1653, +0.2161, -0.2260,
+0.0668, -0.3423, +0.0087, +0.3678, -0.1448, +0.3106, +0.2831, +0.0889,
-0.1325, -0.0667, -0.1139, +0.1482, +0.1164, -0.1613, +0.0733, +0.0005,
-0.0419, -0.0656, +0.0986, -0.1560, -0.1506, -0.1254, -0.0902, +0.2643
],
[
-0.2274, -0.5965, -0.0342, -0.6827, -0.1276, +0.0802, -1.2401, +0.2169,
+0.0531, -0.0964, +0.2187, +0.0299, +0.2797, -0.7842, -0.5032, +0.1321,
-0.2005, -0.3383, -0.3343, +0.1237, -0.0915, -0.6670, +0.0473, -0.6602,
+0.1260, -1.2568, -0.2235, +0.1255, +0.3263, +0.1078, -0.0685, -0.0085
],
[
+0.3530, -0.3798, -0.5576, +0.1040, -0.1875, +0.1399, -0.1539, -1.3570,
-0.1105, +0.0370, -0.4067, +0.2991, +0.2811, +0.1082, -0.0573, +0.2104,
-0.1550, +0.3365, +0.5019, +0.4842, +0.4671, +0.2578, -0.0029, +0.0016,
-0.1533, -0.2459, +0.1866, +0.0699, -0.1873, -1.1082, -0.9151, -0.1758
],
[
+0.2397, +0.2045, -0.2370, -0.3293, -0.3153, -0.2131, +0.1407, -0.0721,
+0.0723, -0.0019, -0.3940, +0.1340, +0.3550, +0.1190, -0.6068, -0.0747,
-0.7712, +0.1922, +0.6519, -0.0651, -0.4332, +0.0494, -0.7192, +0.4279,
-0.1762, -0.5548, +0.1749, -0.2149, -0.6916, -0.0448, -0.1025, +0.0212
],
[
-0.1101, -0.2853, -0.3405, +0.3059, -0.5009, +0.1139, +0.0602, -0.5256,
-0.9340, +0.1189, -0.9900, -0.5092, -1.9114, +0.1249, -0.7890, -1.1437,
-0.4686, +0.3687, -0.2993, -0.1058, +0.0966, -0.0284, -0.4845, -0.1683,
+0.3489, -0.0173, -0.0521, -0.1265, -0.0182, -0.2870, +0.0246, -1.0009
],
[
-0.1411, +0.1840, -0.3968, +0.2893, -0.9532, -0.2235, -0.1156, -0.7018,
-0.2859, -0.1742, -0.6094, -0.0247, -1.0472, +0.1916, -0.4825, -0.4209,
+0.2371, +0.0900, +0.0646, -0.1665, +0.5168, +0.0670, -0.1779, +0.3494,
+0.3035, +0.0548, +0.2939, -0.3871, -0.0828, -0.5370, +0.0804, -0.2175
],
[
+0.4992, +0.1187, -0.0464, +0.7284, +0.1106, -0.0542, -0.3548, +0.3451,
+0.0281, -0.4796, -0.2282, -0.3789, -0.1253, -0.0824, -0.3919, +0.1890,
-0.1683, -2.1362, -0.9594, -0.6882, +0.6158, -0.2412, +0.2336, -0.0142,
-0.9257, +0.3819, -0.1836, -0.7676, +0.3713, -0.1364, +0.3317, +0.3696
]
])
weights_dense2_b = np.array([ -0.0528, +0.0930, -0.3614, +0.2145, -0.3644, -0.0033, -0.0702, -0.0928, -0.1018, +0.0424, +0.0130, +0.2634, -0.1167, +0.2412, +0.0852, +0.0047, +0.1958, -0.1322, +0.0218, +0.2207, +0.1946, +0.0936, +0.2900, +0.2404, -0.1711, +0.1214, +0.2968, -0.2935, -0.0390, +0.1330, +0.0325, +0.2185])
weights_final_w = np.array([
[ -0.2378],
[ +0.1955],
[ -0.2006],
[ -0.5372],
[ -0.3298],
[ +0.0891],
[ -0.3930],
[ +0.8978],
[ +0.3177],
[ +0.5357],
[ +0.2878],
[ +0.4998],
[ +0.2550],
[ -0.2619],
[ +1.1990],
[ +0.3115],
[ +0.3655],
[ +0.5774],
[ -0.4641],
[ +0.2613],
[ +0.1928],
[ +0.1458],
[ +0.4138],
[ -0.4969],
[ +0.4147],
[ +1.0689],
[ -0.1562],
[ -0.3669],
[ -0.3073],
[ +0.3354],
[ +0.9354],
[ +0.8831]
weights_dense2_b = np.array([
-0.0528, +0.0930, -0.3614, +0.2145, -0.3644, -0.0033, -0.0702, -0.0928,
-0.1018, +0.0424, +0.0130, +0.2634, -0.1167, +0.2412, +0.0852, +0.0047,
+0.1958, -0.1322, +0.0218, +0.2207, +0.1946, +0.0936, +0.2900, +0.2404,
-0.1711, +0.1214, +0.2968, -0.2935, -0.0390, +0.1330, +0.0325, +0.2185
])
weights_final_b = np.array([ +0.2753])
weights_final_w = np.array([[-0.2378], [+0.1955], [-0.2006], [-0.5372],
[-0.3298], [+0.0891], [-0.3930], [+0.8978],
[+0.3177], [+0.5357], [+0.2878], [+0.4998],
[+0.2550], [-0.2619], [+1.1990], [+0.3115],
[+0.3655], [+0.5774], [-0.4641], [+0.2613],
[+0.1928], [+0.1458], [+0.4138], [-0.4969],
[+0.4147], [+1.0689], [-0.1562], [-0.3669],
[-0.3073], [+0.3354], [+0.9354], [+0.8831]])
if __name__=="__main__":
main()
weights_final_b = np.array([+0.2753])
# yapf: enable
if __name__ == "__main__":
main()

View File

@@ -2,39 +2,40 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
from pybullet_envs.bullet.kukaCamGymEnv import KukaCamGymEnv
import time
def main():
environment = KukaCamGymEnv(renders=True,isDiscrete=False)
motorsIds=[]
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 1
motorsIds.append(environment._p.addUserDebugParameter("posX",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("posY",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("posZ",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("yaw",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
done = False
while (not done):
action=[]
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
if __name__=="__main__":
main()
environment = KukaCamGymEnv(renders=True, isDiscrete=False)
motorsIds = []
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 1
motorsIds.append(environment._p.addUserDebugParameter("posX", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("posY", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("posZ", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("yaw", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle", 0, 0.3, .3))
done = False
while (not done):
action = []
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
if __name__ == "__main__":
main()

View File

@@ -2,39 +2,40 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
import time
def main():
environment = KukaGymEnv(renders=True,isDiscrete=False, maxSteps = 10000000)
motorsIds=[]
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 0.01
motorsIds.append(environment._p.addUserDebugParameter("posX",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("posY",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("posZ",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("yaw",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
done = False
while (not done):
action=[]
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step2(action)
obs = environment.getExtendedObservation()
if __name__=="__main__":
main()
environment = KukaGymEnv(renders=True, isDiscrete=False, maxSteps=10000000)
motorsIds = []
#motorsIds.append(environment._p.addUserDebugParameter("posX",0.4,0.75,0.537))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 0.01
motorsIds.append(environment._p.addUserDebugParameter("posX", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("posY", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("posZ", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("yaw", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("fingerAngle", 0, 0.3, .3))
done = False
while (not done):
action = []
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step2(action)
obs = environment.getExtendedObservation()
if __name__ == "__main__":
main()

View File

@@ -2,37 +2,38 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
import time
def main():
environment = KukaGymEnv(renders=True,isDiscrete=False, maxSteps = 10000000)
motorsIds=[]
#motorsIds.append(environment._p.addUserDebugParameter("posX",-1,1,0))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 1
motorsIds.append(environment._p.addUserDebugParameter("posX",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("posY",-dv,dv,0))
motorsIds.append(environment._p.addUserDebugParameter("yaw",-dv,dv,0))
done = False
while (not done):
action=[]
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
if __name__=="__main__":
main()
environment = KukaGymEnv(renders=True, isDiscrete=False, maxSteps=10000000)
motorsIds = []
#motorsIds.append(environment._p.addUserDebugParameter("posX",-1,1,0))
#motorsIds.append(environment._p.addUserDebugParameter("posY",-.22,.3,0.0))
#motorsIds.append(environment._p.addUserDebugParameter("posZ",0.1,1,0.2))
#motorsIds.append(environment._p.addUserDebugParameter("yaw",-3.14,3.14,0))
#motorsIds.append(environment._p.addUserDebugParameter("fingerAngle",0,0.3,.3))
dv = 1
motorsIds.append(environment._p.addUserDebugParameter("posX", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("posY", -dv, dv, 0))
motorsIds.append(environment._p.addUserDebugParameter("yaw", -dv, dv, 0))
done = False
while (not done):
action = []
for motorId in motorsIds:
action.append(environment._p.readUserDebugParameter(motorId))
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
if __name__ == "__main__":
main()

View File

@@ -5,88 +5,165 @@ import pybullet_data
#cid = p.connect(p.UDP,"192.168.86.100")
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI)
if (cid < 0):
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
p.resetSimulation()
objects = [p.loadURDF("plane.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("samurai.urdf", 0.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("pr2_gripper.urdf", 0.500000,0.300006,0.700000,-0.000000,-0.000000,-0.000031,1.000000)]
objects = [
p.loadURDF("plane.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 1.000000)
]
objects = [
p.loadURDF("samurai.urdf", 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("pr2_gripper.urdf", 0.500000, 0.300006, 0.700000, -0.000000, -0.000000, -0.000031,
1.000000)
]
pr2_gripper = objects[0]
print ("pr2_gripper=")
print (pr2_gripper)
print("pr2_gripper=")
print(pr2_gripper)
jointPositions=[ 0.550569, 0.000000, 0.549657, 0.000000 ]
for jointIndex in range (p.getNumJoints(pr2_gripper)):
p.resetJointState(pr2_gripper,jointIndex,jointPositions[jointIndex])
jointPositions = [0.550569, 0.000000, 0.549657, 0.000000]
for jointIndex in range(p.getNumJoints(pr2_gripper)):
p.resetJointState(pr2_gripper, jointIndex, jointPositions[jointIndex])
pr2_cid = p.createConstraint(pr2_gripper,-1,-1,-1,p.JOINT_FIXED,[0,0,0],[0.2,0,0],[0.500000,0.300006,0.700000])
print ("pr2_cid")
print (pr2_cid)
pr2_cid = p.createConstraint(pr2_gripper, -1, -1, -1, p.JOINT_FIXED, [0, 0, 0], [0.2, 0, 0],
[0.500000, 0.300006, 0.700000])
print("pr2_cid")
print(pr2_cid)
objects = [p.loadURDF("kuka_iiwa/model_vr_limits.urdf", 1.400000,-0.200000,0.600000,0.000000,0.000000,0.000000,1.000000)]
objects = [
p.loadURDF("kuka_iiwa/model_vr_limits.urdf", 1.400000, -0.200000, 0.600000, 0.000000, 0.000000,
0.000000, 1.000000)
]
kuka = objects[0]
jointPositions=[ -0.000000, -0.000000, 0.000000, 1.570793, 0.000000, -1.036725, 0.000001 ]
for jointIndex in range (p.getNumJoints(kuka)):
p.resetJointState(kuka,jointIndex,jointPositions[jointIndex])
p.setJointMotorControl2(kuka,jointIndex,p.POSITION_CONTROL,jointPositions[jointIndex],0)
jointPositions = [-0.000000, -0.000000, 0.000000, 1.570793, 0.000000, -1.036725, 0.000001]
for jointIndex in range(p.getNumJoints(kuka)):
p.resetJointState(kuka, jointIndex, jointPositions[jointIndex])
p.setJointMotorControl2(kuka, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex], 0)
objects = [p.loadURDF("lego/lego.urdf", 1.000000,-0.200000,0.700000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("lego/lego.urdf", 1.000000,-0.200000,0.800000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("lego/lego.urdf", 1.000000,-0.200000,0.900000,0.000000,0.000000,0.000000,1.000000)]
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.700000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.800000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("lego/lego.urdf", 1.000000, -0.200000, 0.900000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = p.loadSDF("gripper/wsg50_one_motor_gripper_new_free_base.sdf")
kuka_gripper = objects[0]
print ("kuka gripper=")
print("kuka gripper=")
print(kuka_gripper)
p.resetBasePositionAndOrientation(kuka_gripper,[0.923103,-0.200000,1.250036],[-0.000000,0.964531,-0.000002,-0.263970])
jointPositions=[ 0.000000, -0.011130, -0.206421, 0.205143, -0.009999, 0.000000, -0.010055, 0.000000 ]
for jointIndex in range (p.getNumJoints(kuka_gripper)):
p.resetJointState(kuka_gripper,jointIndex,jointPositions[jointIndex])
p.setJointMotorControl2(kuka_gripper,jointIndex,p.POSITION_CONTROL,jointPositions[jointIndex],0)
p.resetBasePositionAndOrientation(kuka_gripper, [0.923103, -0.200000, 1.250036],
[-0.000000, 0.964531, -0.000002, -0.263970])
jointPositions = [
0.000000, -0.011130, -0.206421, 0.205143, -0.009999, 0.000000, -0.010055, 0.000000
]
for jointIndex in range(p.getNumJoints(kuka_gripper)):
p.resetJointState(kuka_gripper, jointIndex, jointPositions[jointIndex])
p.setJointMotorControl2(kuka_gripper, jointIndex, p.POSITION_CONTROL, jointPositions[jointIndex],
0)
kuka_cid = p.createConstraint(kuka, 6, kuka_gripper, 0, p.JOINT_FIXED, [0, 0, 0], [0, 0, 0.05],
[0, 0, 0])
kuka_cid = p.createConstraint(kuka, 6, kuka_gripper,0,p.JOINT_FIXED, [0,0,0], [0,0,0.05],[0,0,0])
objects = [p.loadURDF("jenga/jenga.urdf", 1.300000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 1.200000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 1.100000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 1.000000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 0.900000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("jenga/jenga.urdf", 0.800000,-0.700000,0.750000,0.000000,0.707107,0.000000,0.707107)]
objects = [p.loadURDF("table/table.urdf", 1.000000,-0.200000,0.000000,0.000000,0.000000,0.707107,0.707107)]
objects = [p.loadURDF("teddy_vhacd.urdf", 1.050000,-0.500000,0.700000,0.000000,0.000000,0.707107,0.707107)]
objects = [p.loadURDF("cube_small.urdf", 0.950000,-0.100000,0.700000,0.000000,0.000000,0.707107,0.707107)]
objects = [p.loadURDF("sphere_small.urdf", 0.850000,-0.400000,0.700000,0.000000,0.000000,0.707107,0.707107)]
objects = [p.loadURDF("duck_vhacd.urdf", 0.850000,-0.400000,0.900000,0.000000,0.000000,0.707107,0.707107)]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.300000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.200000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.100000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 1.000000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 0.900000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("jenga/jenga.urdf", 0.800000, -0.700000, 0.750000, 0.000000, 0.707107, 0.000000,
0.707107)
]
objects = [
p.loadURDF("table/table.urdf", 1.000000, -0.200000, 0.000000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("teddy_vhacd.urdf", 1.050000, -0.500000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("cube_small.urdf", 0.950000, -0.100000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("sphere_small.urdf", 0.850000, -0.400000, 0.700000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = [
p.loadURDF("duck_vhacd.urdf", 0.850000, -0.400000, 0.900000, 0.000000, 0.000000, 0.707107,
0.707107)
]
objects = p.loadSDF("kiva_shelf/model.sdf")
ob = objects[0]
p.resetBasePositionAndOrientation(ob,[0.000000,1.000000,1.204500],[0.000000,0.000000,0.000000,1.000000])
objects = [p.loadURDF("teddy_vhacd.urdf", -0.100000,0.600000,0.850000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("sphere_small.urdf", -0.100000,0.955006,1.169706,0.633232,-0.000000,-0.000000,0.773962)]
objects = [p.loadURDF("cube_small.urdf", 0.300000,0.600000,0.850000,0.000000,0.000000,0.000000,1.000000)]
objects = [p.loadURDF("table_square/table_square.urdf", -1.000000,0.000000,0.000000,0.000000,0.000000,0.000000,1.000000)]
p.resetBasePositionAndOrientation(ob, [0.000000, 1.000000, 1.204500],
[0.000000, 0.000000, 0.000000, 1.000000])
objects = [
p.loadURDF("teddy_vhacd.urdf", -0.100000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("sphere_small.urdf", -0.100000, 0.955006, 1.169706, 0.633232, -0.000000, -0.000000,
0.773962)
]
objects = [
p.loadURDF("cube_small.urdf", 0.300000, 0.600000, 0.850000, 0.000000, 0.000000, 0.000000,
1.000000)
]
objects = [
p.loadURDF("table_square/table_square.urdf", -1.000000, 0.000000, 0.000000, 0.000000, 0.000000,
0.000000, 1.000000)
]
ob = objects[0]
jointPositions=[ 0.000000 ]
for jointIndex in range (p.getNumJoints(ob)):
p.resetJointState(ob,jointIndex,jointPositions[jointIndex])
jointPositions = [0.000000]
for jointIndex in range(p.getNumJoints(ob)):
p.resetJointState(ob, jointIndex, jointPositions[jointIndex])
objects = [p.loadURDF("husky/husky.urdf", 2.000000,-5.000000,1.000000,0.000000,0.000000,0.000000,1.000000)]
objects = [
p.loadURDF("husky/husky.urdf", 2.000000, -5.000000, 1.000000, 0.000000, 0.000000, 0.000000,
1.000000)
]
ob = objects[0]
jointPositions=[ 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000 ]
for jointIndex in range (p.getNumJoints(ob)):
p.resetJointState(ob,jointIndex,jointPositions[jointIndex])
jointPositions = [
0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000, 0.000000,
0.000000
]
for jointIndex in range(p.getNumJoints(ob)):
p.resetJointState(ob, jointIndex, jointPositions[jointIndex])
p.setGravity(0.000000,0.000000,0.000000)
p.setGravity(0,0,-10)
p.setGravity(0.000000, 0.000000, 0.000000)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(1)
ref_time = time.time()
running_time = 60 # seconds
while (time.time() < ref_time+running_time):
p.setGravity(0,0,-10)
#p.stepSimulation()
running_time = 60 # seconds
while (time.time() < ref_time + running_time):
p.setGravity(0, 0, -10)
#p.stepSimulation()
p.disconnect()

View File

@@ -7,58 +7,61 @@ p.connect(p.GUI)
p.setAdditionalSearchPath(pd.getDataPath())
plane = p.loadURDF("plane.urdf")
p.setGravity(0,0,-9.8)
p.setTimeStep(1./500)
p.setGravity(0, 0, -9.8)
p.setTimeStep(1. / 500)
#p.setDefaultContactERP(0)
#urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
urdfFlags = p.URDF_USE_SELF_COLLISION
quadruped = p.loadURDF("laikago/laikago.urdf",[0,0,.5],[0,0.5,0.5,0], flags = urdfFlags,useFixedBase=False)
quadruped = p.loadURDF("laikago/laikago.urdf", [0, 0, .5], [0, 0.5, 0.5, 0],
flags=urdfFlags,
useFixedBase=False)
#enable collision between lower legs
for j in range (p.getNumJoints(quadruped)):
print(p.getJointInfo(quadruped,j))
for j in range(p.getNumJoints(quadruped)):
print(p.getJointInfo(quadruped, j))
#2,5,8 and 11 are the lower legs
lower_legs = [2,5,8,11]
lower_legs = [2, 5, 8, 11]
for l0 in lower_legs:
for l1 in lower_legs:
if (l1>l0):
if (l1 > l0):
enableCollision = 1
print("collision for pair",l0,l1, p.getJointInfo(quadruped,l0)[12],p.getJointInfo(quadruped,l1)[12], "enabled=",enableCollision)
p.setCollisionFilterPair(quadruped, quadruped, 2,5,enableCollision)
print("collision for pair", l0, l1,
p.getJointInfo(quadruped, l0)[12],
p.getJointInfo(quadruped, l1)[12], "enabled=", enableCollision)
p.setCollisionFilterPair(quadruped, quadruped, 2, 5, enableCollision)
jointIds=[]
paramIds=[]
jointOffsets=[]
jointDirections=[-1,1,1,1,1,1,-1,1,1,1,1,1]
jointAngles=[0,0,0,0,0,0,0,0,0,0,0,0]
jointIds = []
paramIds = []
jointOffsets = []
jointDirections = [-1, 1, 1, 1, 1, 1, -1, 1, 1, 1, 1, 1]
jointAngles = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
for i in range (4):
for i in range(4):
jointOffsets.append(0)
jointOffsets.append(-0.7)
jointOffsets.append(0.7)
maxForceId = p.addUserDebugParameter("maxForce",0,100,20)
maxForceId = p.addUserDebugParameter("maxForce", 0, 100, 20)
for j in range (p.getNumJoints(quadruped)):
p.changeDynamics(quadruped,j,linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped,j)
#print(info)
jointName = info[1]
jointType = info[2]
if (jointType==p.JOINT_PRISMATIC or jointType==p.JOINT_REVOLUTE):
jointIds.append(j)
for j in range(p.getNumJoints(quadruped)):
p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped, j)
#print(info)
jointName = info[1]
jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
jointIds.append(j)
p.getCameraImage(480,320)
p.getCameraImage(480, 320)
p.setRealTimeSimulation(0)
joints=[]
joints = []
with open(pd.getDataPath()+"/laikago/data1.txt","r") as filestream:
with open(pd.getDataPath() + "/laikago/data1.txt", "r") as filestream:
for line in filestream:
print("line=",line)
print("line=", line)
maxForce = p.readUserDebugParameter(maxForceId)
currentline = line.split(",")
#print (currentline)
@@ -66,31 +69,35 @@ with open(pd.getDataPath()+"/laikago/data1.txt","r") as filestream:
frame = currentline[0]
t = currentline[1]
#print("frame[",frame,"]")
joints=currentline[2:14]
joints = currentline[2:14]
#print("joints=",joints)
for j in range (12):
for j in range(12):
targetPos = float(joints[j])
p.setJointMotorControl2(quadruped,jointIds[j],p.POSITION_CONTROL,jointDirections[j]*targetPos+jointOffsets[j], force=maxForce)
p.setJointMotorControl2(quadruped,
jointIds[j],
p.POSITION_CONTROL,
jointDirections[j] * targetPos + jointOffsets[j],
force=maxForce)
p.stepSimulation()
for lower_leg in lower_legs:
#print("points for ", quadruped, " link: ", lower_leg)
pts = p.getContactPoints(quadruped,-1, lower_leg)
pts = p.getContactPoints(quadruped, -1, lower_leg)
#print("num points=",len(pts))
#for pt in pts:
# print(pt[9])
time.sleep(1./500.)
for j in range (p.getNumJoints(quadruped)):
p.changeDynamics(quadruped,j,linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped,j)
js = p.getJointState(quadruped,j)
#print(info)
jointName = info[1]
jointType = info[2]
if (jointType==p.JOINT_PRISMATIC or jointType==p.JOINT_REVOLUTE):
paramIds.append(p.addUserDebugParameter(jointName.decode("utf-8"),-4,4,(js[0]-jointOffsets[j])/jointDirections[j]))
time.sleep(1. / 500.)
for j in range(p.getNumJoints(quadruped)):
p.changeDynamics(quadruped, j, linearDamping=0, angularDamping=0)
info = p.getJointInfo(quadruped, j)
js = p.getJointState(quadruped, j)
#print(info)
jointName = info[1]
jointType = info[2]
if (jointType == p.JOINT_PRISMATIC or jointType == p.JOINT_REVOLUTE):
paramIds.append(
p.addUserDebugParameter(jointName.decode("utf-8"), -4, 4,
(js[0] - jointOffsets[j]) / jointDirections[j]))
p.setRealTimeSimulation(1)
@@ -100,5 +107,8 @@ while (1):
c = paramIds[i]
targetPos = p.readUserDebugParameter(c)
maxForce = p.readUserDebugParameter(maxForceId)
p.setJointMotorControl2(quadruped,jointIds[i],p.POSITION_CONTROL,jointDirections[i]*targetPos+jointOffsets[i], force=maxForce)
p.setJointMotorControl2(quadruped,
jointIds[i],
p.POSITION_CONTROL,
jointDirections[i] * targetPos + jointOffsets[i],
force=maxForce)

View File

@@ -5,7 +5,7 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import math
import numpy as np
@@ -13,19 +13,19 @@ from pybullet_envs.bullet import minitaur_gym_env
import argparse
from pybullet_envs.bullet import minitaur_env_randomizer
def ResetPoseExample():
"""An example that the minitaur stands still using the reset pose."""
steps = 1000
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
environment = minitaur_gym_env.MinitaurBulletEnv(
render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
pd_control_enabled=True,
accurate_motor_model_enabled=True,
motor_overheat_protection=True,
env_randomizer = randomizer,
hard_reset=False)
environment = minitaur_gym_env.MinitaurBulletEnv(render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
pd_control_enabled=True,
accurate_motor_model_enabled=True,
motor_overheat_protection=True,
env_randomizer=randomizer,
hard_reset=False)
action = [math.pi / 2] * 8
for _ in range(steps):
_, _, done, _ = environment.step(action)
@@ -33,6 +33,7 @@ def ResetPoseExample():
break
environment.reset()
def MotorOverheatExample():
"""An example of minitaur motor overheat protection is triggered.
@@ -40,15 +41,14 @@ def MotorOverheatExample():
torques. The overheat protection will be triggered in ~1 sec.
"""
environment = minitaur_gym_env.MinitaurBulletEnv(
render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
motor_overheat_protection=True,
accurate_motor_model_enabled=True,
motor_kp=1.20,
motor_kd=0.00,
on_rack=False)
environment = minitaur_gym_env.MinitaurBulletEnv(render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
motor_overheat_protection=True,
accurate_motor_model_enabled=True,
motor_kp=1.20,
motor_kd=0.00,
on_rack=False)
action = [.0] * 8
for i in range(8):
@@ -68,6 +68,7 @@ def MotorOverheatExample():
actions_and_observations.append(current_row)
environment.reset()
def SineStandExample():
"""An example of minitaur standing and squatting on the floor.
@@ -75,15 +76,14 @@ def SineStandExample():
periodically in both simulation and experiment. We compare the measured motor
trajectories, torques and gains.
"""
environment = minitaur_gym_env.MinitaurBulletEnv(
render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
motor_overheat_protection=True,
accurate_motor_model_enabled=True,
motor_kp=1.20,
motor_kd=0.02,
on_rack=False)
environment = minitaur_gym_env.MinitaurBulletEnv(render=True,
leg_model_enabled=False,
motor_velocity_limit=np.inf,
motor_overheat_protection=True,
accurate_motor_model_enabled=True,
motor_kp=1.20,
motor_kd=0.02,
on_rack=False)
steps = 1000
amplitude = 0.5
speed = 3
@@ -102,20 +102,19 @@ def SineStandExample():
observation, _, _, _ = environment.step(action)
current_row.extend(observation.tolist())
actions_and_observations.append(current_row)
environment.reset()
def SinePolicyExample():
"""An example of minitaur walking with a sine gait."""
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
environment = minitaur_gym_env.MinitaurBulletEnv(
render=True,
motor_velocity_limit=np.inf,
pd_control_enabled=True,
hard_reset=False,
env_randomizer = randomizer,
on_rack=False)
environment = minitaur_gym_env.MinitaurBulletEnv(render=True,
motor_velocity_limit=np.inf,
pd_control_enabled=True,
hard_reset=False,
env_randomizer=randomizer,
on_rack=False)
sum_reward = 0
steps = 20000
amplitude_1_bound = 0.1
@@ -150,21 +149,23 @@ def SinePolicyExample():
def main():
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--env', help='environment ID (0==sine, 1==stand, 2=reset, 3=overheat)',type=int, default=0)
args = parser.parse_args()
print("--env=" + str(args.env))
if (args.env == 0):
SinePolicyExample()
if (args.env == 1):
SineStandExample()
if (args.env == 2):
ResetPoseExample()
if (args.env == 3):
MotorOverheatExample()
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--env',
help='environment ID (0==sine, 1==stand, 2=reset, 3=overheat)',
type=int,
default=0)
args = parser.parse_args()
print("--env=" + str(args.env))
if (args.env == 0):
SinePolicyExample()
if (args.env == 1):
SineStandExample()
if (args.env == 2):
ResetPoseExample()
if (args.env == 3):
MotorOverheatExample()
if __name__ == '__main__':
main()
main()

View File

@@ -2,43 +2,45 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
isDiscrete = False
def main():
environment = RacecarGymEnv(renders=True, isDiscrete=isDiscrete)
environment.reset()
targetVelocitySlider = environment._p.addUserDebugParameter("wheelVelocity",-1,1,0)
steeringSlider = environment._p.addUserDebugParameter("steering",-1,1,0)
while (True):
targetVelocity = environment._p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = environment._p.readUserDebugParameter(steeringSlider)
if (isDiscrete):
discreteAction = 0
if (targetVelocity<-0.33):
discreteAction=0
else:
if (targetVelocity>0.33):
discreteAction=6
else:
discreteAction=3
if (steeringAngle>-0.17):
if (steeringAngle>0.17):
discreteAction=discreteAction+2
else:
discreteAction=discreteAction+1
action=discreteAction
else:
action=[targetVelocity,steeringAngle]
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
print("obs")
print(obs)
if __name__=="__main__":
main()
def main():
environment = RacecarGymEnv(renders=True, isDiscrete=isDiscrete)
environment.reset()
targetVelocitySlider = environment._p.addUserDebugParameter("wheelVelocity", -1, 1, 0)
steeringSlider = environment._p.addUserDebugParameter("steering", -1, 1, 0)
while (True):
targetVelocity = environment._p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = environment._p.readUserDebugParameter(steeringSlider)
if (isDiscrete):
discreteAction = 0
if (targetVelocity < -0.33):
discreteAction = 0
else:
if (targetVelocity > 0.33):
discreteAction = 6
else:
discreteAction = 3
if (steeringAngle > -0.17):
if (steeringAngle > 0.17):
discreteAction = discreteAction + 2
else:
discreteAction = discreteAction + 1
action = discreteAction
else:
action = [targetVelocity, steeringAngle]
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
print("obs")
print(obs)
if __name__ == "__main__":
main()

View File

@@ -2,43 +2,45 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
isDiscrete = False
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
def main():
environment = RacecarZEDGymEnv(renders=True, isDiscrete=isDiscrete)
targetVelocitySlider = environment._p.addUserDebugParameter("wheelVelocity",-1,1,0)
steeringSlider = environment._p.addUserDebugParameter("steering",-1,1,0)
while (True):
targetVelocity = environment._p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = environment._p.readUserDebugParameter(steeringSlider)
if (isDiscrete):
discreteAction = 0
if (targetVelocity<-0.33):
discreteAction=0
else:
if (targetVelocity>0.33):
discreteAction=6
else:
discreteAction=3
if (steeringAngle>-0.17):
if (steeringAngle>0.17):
discreteAction=discreteAction+2
else:
discreteAction=discreteAction+1
action=discreteAction
else:
action=[targetVelocity,steeringAngle]
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
#print("obs")
#print(obs)
environment = RacecarZEDGymEnv(renders=True, isDiscrete=isDiscrete)
if __name__=="__main__":
main()
targetVelocitySlider = environment._p.addUserDebugParameter("wheelVelocity", -1, 1, 0)
steeringSlider = environment._p.addUserDebugParameter("steering", -1, 1, 0)
while (True):
targetVelocity = environment._p.readUserDebugParameter(targetVelocitySlider)
steeringAngle = environment._p.readUserDebugParameter(steeringSlider)
if (isDiscrete):
discreteAction = 0
if (targetVelocity < -0.33):
discreteAction = 0
else:
if (targetVelocity > 0.33):
discreteAction = 6
else:
discreteAction = 3
if (steeringAngle > -0.17):
if (steeringAngle > 0.17):
discreteAction = discreteAction + 2
else:
discreteAction = discreteAction + 1
action = discreteAction
else:
action = [targetVelocity, steeringAngle]
state, reward, done, info = environment.step(action)
obs = environment.getExtendedObservation()
#print("obs")
#print(obs)
if __name__ == "__main__":
main()

View File

@@ -3,7 +3,7 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import pybullet_data
import pybullet as p
@@ -12,8 +12,7 @@ import time
p.connect(p.GUI_SERVER)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
while(1):
#this is a no-op command, to allow GUI updates on Mac OSX (main thread)
p.setPhysicsEngineParameter()
time.sleep(0.01)
while (1):
#this is a no-op command, to allow GUI updates on Mac OSX (main thread)
p.setPhysicsEngineParameter()
time.sleep(0.01)

View File

@@ -2,7 +2,7 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import pybullet as p
import math
@@ -12,31 +12,31 @@ import pybullet_data
p.connect(p.GUI)
#p.loadURDF("wheel.urdf",[0,0,3])
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane=p.loadURDF("plane100.urdf",[0,0,0])
timestep = 1./240.
plane = p.loadURDF("plane100.urdf", [0, 0, 0])
timestep = 1. / 240.
bike=-1
for i in range (1):
bike = -1
for i in range(1):
bike=p.loadURDF("bicycle/bike.urdf",[0,0+3*i,1.5], [0,0,0,1], useFixedBase=False)
p.setJointMotorControl2(bike,0,p.VELOCITY_CONTROL,targetVelocity=0,force=0.05)
#p.setJointMotorControl2(bike,1,p.VELOCITY_CONTROL,targetVelocity=5, force=1000)
p.setJointMotorControl2(bike,1,p.VELOCITY_CONTROL,targetVelocity=5, force=0)
p.setJointMotorControl2(bike,2,p.VELOCITY_CONTROL,targetVelocity=15, force=20)
bike = p.loadURDF("bicycle/bike.urdf", [0, 0 + 3 * i, 1.5], [0, 0, 0, 1], useFixedBase=False)
p.setJointMotorControl2(bike, 0, p.VELOCITY_CONTROL, targetVelocity=0, force=0.05)
#p.setJointMotorControl2(bike,1,p.VELOCITY_CONTROL,targetVelocity=5, force=1000)
p.setJointMotorControl2(bike, 1, p.VELOCITY_CONTROL, targetVelocity=5, force=0)
p.setJointMotorControl2(bike, 2, p.VELOCITY_CONTROL, targetVelocity=15, force=20)
p.changeDynamics(plane,-1, mass=0,lateralFriction=1, linearDamping=0, angularDamping=0)
p.changeDynamics(bike,1,lateralFriction=1,linearDamping=0, angularDamping=0)
p.changeDynamics(bike,2,lateralFriction=1,linearDamping=0, angularDamping=0)
#p.resetJointState(bike,1,0,100)
#p.resetJointState(bike,2,0,100)
#p.resetBaseVelocity(bike,[0,0,0],[0,0,0])
p.changeDynamics(plane, -1, mass=0, lateralFriction=1, linearDamping=0, angularDamping=0)
p.changeDynamics(bike, 1, lateralFriction=1, linearDamping=0, angularDamping=0)
p.changeDynamics(bike, 2, lateralFriction=1, linearDamping=0, angularDamping=0)
#p.resetJointState(bike,1,0,100)
#p.resetJointState(bike,2,0,100)
#p.resetBaseVelocity(bike,[0,0,0],[0,0,0])
#p.setPhysicsEngineParameter(numSubSteps=0)
#bike=p.loadURDF("frame.urdf",useFixedBase=True)
#bike = p.loadURDF("handlebar.urdf", useFixedBase=True)
#p.loadURDF("handlebar.urdf",[0,2,1])
#coord = p.loadURDF("handlebar.urdf", [0.7700000000000005, 0, 0.22000000000000006],useFixedBase=True)# p.loadURDF("coordinateframe.urdf",[-2,0,1],useFixedBase=True)
#coord = p.loadURDF("coordinateframe.urdf",[-2,0,1],useFixedBase=True)
p.setGravity(0,0,-10)
p.setGravity(0, 0, -10)
p.setRealTimeSimulation(0)
#coordPos = [0,0,0]
#coordOrnEuler = [0,0,0]
@@ -44,100 +44,96 @@ p.setRealTimeSimulation(0)
#coordPos= [0.7000000000000004, 0, 0.22000000000000006]
#coordOrnEuler= [0, -0.2617993877991496, 0]
coordPos= [0.07, 0, -0.6900000000000004]
coordOrnEuler= [0, 0, 0]
coordPos = [0.07, 0, -0.6900000000000004]
coordOrnEuler = [0, 0, 0]
coordPos2= [0, 0, 0 ]
coordOrnEuler2= [0, 0, 0]
coordPos2 = [0, 0, 0]
coordOrnEuler2 = [0, 0, 0]
invPos,invOrn=p.invertTransform(coordPos,p.getQuaternionFromEuler(coordOrnEuler))
mPos,mOrn = p.multiplyTransforms(invPos,invOrn, coordPos2,p.getQuaternionFromEuler(coordOrnEuler2))
invPos, invOrn = p.invertTransform(coordPos, p.getQuaternionFromEuler(coordOrnEuler))
mPos, mOrn = p.multiplyTransforms(invPos, invOrn, coordPos2,
p.getQuaternionFromEuler(coordOrnEuler2))
eul = p.getEulerFromQuaternion(mOrn)
print("rpy=\"",eul[0],eul[1],eul[2],"\" xyz=\"", mPos[0],mPos[1], mPos[2])
print("rpy=\"", eul[0], eul[1], eul[2], "\" xyz=\"", mPos[0], mPos[1], mPos[2])
shift=0
shift = 0
gui = 1
frame=0
states=[]
frame = 0
states = []
states.append(p.saveState())
#observations=[]
#observations.append(obs)
running = True
reverting = False
p.getCameraImage(320,200)#,renderer=p.ER_BULLET_HARDWARE_OPENGL )
while (1):
p.getCameraImage(320, 200) #,renderer=p.ER_BULLET_HARDWARE_OPENGL )
updateCam = 0
keys = p.getKeyboardEvents()
for k,v in keys.items():
if (reverting or (k == p.B3G_LEFT_ARROW and (v&p.KEY_WAS_TRIGGERED))):
reverting=True
stateIndex = len(states)-1
#print("prestateIndex=",stateIndex)
time.sleep(timestep)
updateCam=1
if (stateIndex>0):
stateIndex-=1
states=states[:stateIndex+1]
#observations=observations[:stateIndex+1]
#print("states=",states)
#print("stateIndex =",stateIndex )
p.restoreState(states[stateIndex])
#obs=observations[stateIndex]
#obs, r, done, _ = env.step(a)
if (k == p.B3G_LEFT_ARROW and (v&p.KEY_WAS_RELEASED)):
reverting = False
while (1):
if (k == ord('1') and (v&p.KEY_WAS_TRIGGERED)):
gui = not gui
if (k == p.B3G_RIGHT_ARROW and (v&p.KEY_WAS_RELEASED)):
running=False
if (running or (k == p.B3G_RIGHT_ARROW and (v&p.KEY_WAS_TRIGGERED))):
running = True
if (running):
p.stepSimulation()
updateCam=1
time.sleep(timestep)
pts = p.getContactPoints()
#print("numPoints=",len(pts))
#for point in pts:
# print("Point:bodyA=", point[1],"bodyB=",point[2],"linkA=",point[3],"linkB=",point[4],"dist=",point[8],"force=",point[9])
states.append(p.saveState())
#observations.append(obs)
stateIndex = len(states)
#print("stateIndex =",stateIndex )
frame += 1
if (updateCam):
distance=5
yaw = 0
humanPos, humanOrn = p.getBasePositionAndOrientation(bike)
humanBaseVel = p.getBaseVelocity(bike)
#print("frame",frame, "humanPos=",humanPos, "humanVel=",humanBaseVel)
if (gui):
camInfo = p.getDebugVisualizerCamera()
curTargetPos = camInfo[11]
distance=camInfo[10]
yaw = camInfo[8]
pitch=camInfo[9]
targetPos = [0.95*curTargetPos[0]+0.05*humanPos[0],0.95*curTargetPos[1]+0.05*humanPos[1],curTargetPos[2]]
p.resetDebugVisualizerCamera(distance,yaw,pitch,targetPos);
updateCam = 0
keys = p.getKeyboardEvents()
for k, v in keys.items():
if (reverting or (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_TRIGGERED))):
reverting = True
stateIndex = len(states) - 1
#print("prestateIndex=",stateIndex)
time.sleep(timestep)
updateCam = 1
if (stateIndex > 0):
stateIndex -= 1
states = states[:stateIndex + 1]
#observations=observations[:stateIndex+1]
#print("states=",states)
#print("stateIndex =",stateIndex )
p.restoreState(states[stateIndex])
#obs=observations[stateIndex]
#obs, r, done, _ = env.step(a)
if (k == p.B3G_LEFT_ARROW and (v & p.KEY_WAS_RELEASED)):
reverting = False
if (k == ord('1') and (v & p.KEY_WAS_TRIGGERED)):
gui = not gui
if (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_RELEASED)):
running = False
if (running or (k == p.B3G_RIGHT_ARROW and (v & p.KEY_WAS_TRIGGERED))):
running = True
if (running):
p.stepSimulation()
updateCam = 1
time.sleep(timestep)
pts = p.getContactPoints()
#print("numPoints=",len(pts))
#for point in pts:
# print("Point:bodyA=", point[1],"bodyB=",point[2],"linkA=",point[3],"linkB=",point[4],"dist=",point[8],"force=",point[9])
states.append(p.saveState())
#observations.append(obs)
stateIndex = len(states)
#print("stateIndex =",stateIndex )
frame += 1
if (updateCam):
distance = 5
yaw = 0
humanPos, humanOrn = p.getBasePositionAndOrientation(bike)
humanBaseVel = p.getBaseVelocity(bike)
#print("frame",frame, "humanPos=",humanPos, "humanVel=",humanBaseVel)
if (gui):
camInfo = p.getDebugVisualizerCamera()
curTargetPos = camInfo[11]
distance = camInfo[10]
yaw = camInfo[8]
pitch = camInfo[9]
targetPos = [
0.95 * curTargetPos[0] + 0.05 * humanPos[0], 0.95 * curTargetPos[1] + 0.05 * humanPos[1],
curTargetPos[2]
]
p.resetDebugVisualizerCamera(distance, yaw, pitch, targetPos)

View File

@@ -2,7 +2,7 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import pybullet_envs
import gym
import argparse
@@ -10,48 +10,52 @@ import pybullet as p
def test(args):
count = 0
env = gym.make(args.env)
env.env.configure(args)
print("args.render=",args.render)
if (args.render==1):
env.render(mode="human")
env.reset()
if (args.resetbenchmark):
while (1):
env.reset()
print("p.getNumBodies()=",p.getNumBodies())
print("count=",count)
count+=1
print("action space:")
sample = env.action_space.sample()
action = sample*0.0
print("action=")
print(action)
for i in range(args.steps):
obs,rewards,done,_ =env.step(action)
if (args.rgb):
print(env.render(mode="rgb_array"))
print("obs=")
print(obs)
print("rewards")
print (rewards)
print ("done")
print(done)
count = 0
env = gym.make(args.env)
env.env.configure(args)
print("args.render=", args.render)
if (args.render == 1):
env.render(mode="human")
env.reset()
if (args.resetbenchmark):
while (1):
env.reset()
print("p.getNumBodies()=", p.getNumBodies())
print("count=", count)
count += 1
print("action space:")
sample = env.action_space.sample()
action = sample * 0.0
print("action=")
print(action)
for i in range(args.steps):
obs, rewards, done, _ = env.step(action)
if (args.rgb):
print(env.render(mode="rgb_array"))
print("obs=")
print(obs)
print("rewards")
print(rewards)
print("done")
print(done)
def main():
import argparse
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--env', help='environment ID', default='AntBulletEnv-v0')
parser.add_argument('--seed', help='RNG seed', type=int, default=0)
parser.add_argument('--render', help='OpenGL Visualizer', type=int, default=0)
parser.add_argument('--rgb',help='rgb_array gym rendering',type=int, default=0)
parser.add_argument('--resetbenchmark',help='Repeat reset to show reset performance',type=int, default=0)
parser.add_argument('--steps', help='Number of steps', type=int, default=1)
args = parser.parse_args()
test(args)
import argparse
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--env', help='environment ID', default='AntBulletEnv-v0')
parser.add_argument('--seed', help='RNG seed', type=int, default=0)
parser.add_argument('--render', help='OpenGL Visualizer', type=int, default=0)
parser.add_argument('--rgb', help='rgb_array gym rendering', type=int, default=0)
parser.add_argument('--resetbenchmark',
help='Repeat reset to show reset performance',
type=int,
default=0)
parser.add_argument('--steps', help='Number of steps', type=int, default=1)
args = parser.parse_args()
test(args)
if __name__ == '__main__':
main()
main()

View File

@@ -2,27 +2,29 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
os.sys.path.insert(0,parentdir)
os.sys.path.insert(0, parentdir)
import pybullet as p
import pybullet_data
import time
def test(args):
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
fileName = os.path.join("mjcf", args.mjcf)
print("fileName")
print(fileName)
p.loadMJCF(fileName)
while (1):
p.stepSimulation()
p.getCameraImage(320,240)
time.sleep(0.01)
def test(args):
p.connect(p.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
fileName = os.path.join("mjcf", args.mjcf)
print("fileName")
print(fileName)
p.loadMJCF(fileName)
while (1):
p.stepSimulation()
p.getCameraImage(320, 240)
time.sleep(0.01)
if __name__ == '__main__':
import argparse
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--mjcf', help='MJCF filename', default="humanoid.xml")
args = parser.parse_args()
test(args)
import argparse
parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
parser.add_argument('--mjcf', help='MJCF filename', default="humanoid.xml")
args = parser.parse_args()
test(args)