summaryrefslogtreecommitdiff
path: root/examples/pybullet/gym/pybullet_envs
diff options
context:
space:
mode:
authorErwin Coumans <erwincoumans@google.com>2019-04-27 07:31:15 -0700
committerErwin Coumans <erwincoumans@google.com>2019-04-27 07:31:15 -0700
commitef9570c315ee0db1dffbb950dbd46aa726e06f83 (patch)
tree44dcbe67c0cd84f189b5e0cd7cc5dfda3488c843 /examples/pybullet/gym/pybullet_envs
parentc59173504298ec79c04cbeb8df2b7766d4920627 (diff)
downloadbullet3-ef9570c315ee0db1dffbb950dbd46aa726e06f83.tar.gz
add yapf style and apply yapf to format all Python files
This recreates pull request #2192
Diffstat (limited to 'examples/pybullet/gym/pybullet_envs')
-rw-r--r--examples/pybullet/gym/pybullet_envs/ARS/ars.py460
-rw-r--r--examples/pybullet/gym/pybullet_envs/__init__.py202
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/configs.py44
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/networks.py61
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/ppo/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/ppo/algorithm.py285
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/ppo/memory.py29
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/ppo/normalize.py28
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/ppo/utility.py51
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/attr_dict.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/batch_env.py9
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/count_weights.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_batch_env.py44
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_env.py43
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/loop.py45
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/mock_algorithm.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/mock_environment.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/simulate.py49
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/streaming_mean.py6
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/tools/wrappers.py15
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/train_ppo.py77
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/utility.py22
-rw-r--r--examples/pybullet/gym/pybullet_envs/agents/visualize_ppo.py71
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_diverse_object_grasping.py42
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_grasping.py34
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_cartpole.py45
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_racecar.py34
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_zed_racecar.py34
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/train_kuka_cam_grasping.py55
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/train_kuka_grasping.py49
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_cartpole.py40
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_racecar.py45
-rw-r--r--examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_zed_racecar.py52
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/bullet_client.py8
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py35
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/env_randomizer_base.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/kuka.py195
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/kukaCamGymEnv.py190
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/kukaGymEnv.py209
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/kuka_diverse_object_gym_env.py68
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/minitaur.py195
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/minitaur_duck_gym_env.py167
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/minitaur_env_randomizer.py12
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py167
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/motor.py31
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/racecar.py220
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py104
-rw-r--r--examples/pybullet/gym/pybullet_envs/bullet/racecarZEDGymEnv.py149
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/DeepMimic_Optimizer.py51
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/action_space.py7
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/env.py24
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_pose_interpolator.py415
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py813
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/motion_capture_data.py33
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/pybullet_deep_mimic_env.py604
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadrupedPoseInterpolator.py94
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadruped_stable_pd.py791
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/testHumanoid.py68
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py342
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/agent_builder.py25
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/exp_params.py99
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/__init__.py2
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/fc_2layers_1024units.py13
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/net_builder.py17
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/normalizer.py288
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/path.py85
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/pg_agent.py668
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/ppo_agent.py715
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/replay_buffer.py678
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_agent.py1165
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_util.py27
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_world.py271
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/mpi_solver.py185
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/solver.py18
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_agent.py284
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_normalizer.py113
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_util.py151
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/camera.py36
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/deepmimic_json_generator.py89
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/h36m_dataset.py224
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/humanoid.py778
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/inverse_kinematics.py240
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/mocap_dataset.py65
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/quaternion.py39
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/render_reference.py132
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/skeleton.py153
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/transformation.py1488
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/mpi_run.py28
-rw-r--r--examples/pybullet/gym/pybullet_envs/deep_mimic/testrl.py131
-rw-r--r--examples/pybullet/gym/pybullet_envs/env_bases.py246
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/dominoes.py53
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py2413
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py2357
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HopperBulletEnv_v0_2017may.py2118
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py8306
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py8307
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py713
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py663
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py665
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py2269
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/kukaCamGymEnvTest.py61
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest.py61
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest2.py57
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/kuka_setup.py207
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/laikago.py110
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/minitaur_gym_env_example.py105
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py72
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/racecarZEDGymEnvTest.py72
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/runServer.py11
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/testBike.py208
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/testEnv.py86
-rw-r--r--examples/pybullet/gym/pybullet_envs/examples/testMJCF.py38
-rw-r--r--examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py323
-rw-r--r--examples/pybullet/gym/pybullet_envs/gym_manipulator_envs.py419
-rw-r--r--examples/pybullet/gym/pybullet_envs/gym_pendulum_envs.py153
-rw-r--r--examples/pybullet/gym/pybullet_envs/kerasrl_utils.py36
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/__init__.py2
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras.py32
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras_lstm.py54
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/minitaur_raibert_controller_example.py62
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/proto2csv.py7
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py2
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/algorithm.py279
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/memory.py29
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/normalize.py28
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/utility.py51
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/configs.py6
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/networks.py67
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train.py80
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train_ppo_test.py18
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/utility.py39
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/visualize.py73
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict_test.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/batch_env.py9
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights_test.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_batch_env.py44
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_env.py43
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop.py45
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop_test.py54
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_algorithm.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_environment.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate.py49
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate_test.py8
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/streaming_mean.py6
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers.py15
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers_test.py29
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/__init__.py3
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/bullet_client.py10
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_alternating_legs_env_randomizer.py26
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py16
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_config.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_from_config.py61
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py39
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_terrain_randomizer.py47
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur.py265
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env.py61
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env_example.py13
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env.py72
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env_example.py2
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_derpy.py100
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env.py77
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env_example.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py153
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env_example.py26
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py18
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging_pb2.py449
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_proto_dump_example.py18
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller.py93
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller_example.py19
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_rainbow_dash.py98
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env.py24
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env_example.py10
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env.py80
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env_example.py20
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env.py31
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env_example.py5
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env.py60
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env_example.py14
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py13
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent.py56
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent_example.py17
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/timestamp_pb2.py115
-rw-r--r--examples/pybullet/gym/pybullet_envs/minitaur/envs/vector_pb2.py887
-rw-r--r--examples/pybullet/gym/pybullet_envs/prediction/__init__.py1
-rw-r--r--examples/pybullet/gym/pybullet_envs/prediction/boxstack_pybullet_sim.py111
-rw-r--r--examples/pybullet/gym/pybullet_envs/prediction/pybullet_sim_gym_env.py69
-rw-r--r--examples/pybullet/gym/pybullet_envs/prediction/test_pybullet_sim_gym_env.py45
-rw-r--r--examples/pybullet/gym/pybullet_envs/robot_bases.py621
-rw-r--r--examples/pybullet/gym/pybullet_envs/robot_locomotors.py583
-rw-r--r--examples/pybullet/gym/pybullet_envs/robot_manipulators.py601
-rw-r--r--examples/pybullet/gym/pybullet_envs/robot_pendula.py160
-rw-r--r--examples/pybullet/gym/pybullet_envs/scene_abstract.py103
-rw-r--r--examples/pybullet/gym/pybullet_envs/scene_stadium.py84
202 files changed, 37797 insertions, 14030 deletions
diff --git a/examples/pybullet/gym/pybullet_envs/ARS/ars.py b/examples/pybullet/gym/pybullet_envs/ARS/ars.py
index 760ebd732..9e9c2b559 100644
--- a/examples/pybullet/gym/pybullet_envs/ARS/ars.py
+++ b/examples/pybullet/gym/pybullet_envs/ARS/ars.py
@@ -4,7 +4,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)
# Importing the libraries
import os
@@ -20,17 +20,17 @@ import argparse
# Setting the Hyper Parameters
class Hp():
-
- def __init__(self):
- self.nb_steps = 10000
- self.episode_length = 1000
- self.learning_rate = 0.02
- self.nb_directions = 16
- self.nb_best_directions = 16
- assert self.nb_best_directions <= self.nb_directions
- self.noise = 0.03
- self.seed = 1
- self.env_name = 'HalfCheetahBulletEnv-v0'
+
+ def __init__(self):
+ self.nb_steps = 10000
+ self.episode_length = 1000
+ self.learning_rate = 0.02
+ self.nb_directions = 16
+ self.nb_best_directions = 16
+ assert self.nb_best_directions <= self.nb_directions
+ self.noise = 0.03
+ self.seed = 1
+ self.env_name = 'HalfCheetahBulletEnv-v0'
# Multiprocess Exploring the policy on one specific direction and over one episode
@@ -39,239 +39,255 @@ _RESET = 1
_CLOSE = 2
_EXPLORE = 3
-def ExploreWorker(rank,childPipe, envname, args):
- env = gym.make(envname)
- nb_inputs = env.observation_space.shape[0]
- normalizer = Normalizer(nb_inputs)
- observation_n = env.reset()
- n=0
- while True:
- n+=1
- try:
- # Only block for short times to have keyboard exceptions be raised.
- if not childPipe.poll(0.001):
- continue
- message, payload = childPipe.recv()
- except (EOFError, KeyboardInterrupt):
- break
- if message == _RESET:
- observation_n = env.reset()
- childPipe.send(["reset ok"])
- continue
- if message == _EXPLORE:
- #normalizer = payload[0] #use our local normalizer
- policy = payload[1]
- hp = payload[2]
- direction = payload[3]
- delta = payload[4]
- state = env.reset()
- done = False
- num_plays = 0.
- sum_rewards = 0
- while not done and num_plays < hp.episode_length:
- normalizer.observe(state)
- state = normalizer.normalize(state)
- action = policy.evaluate(state, delta, direction,hp)
- state, reward, done, _ = env.step(action)
- reward = max(min(reward, 1), -1)
- sum_rewards += reward
- num_plays += 1
- childPipe.send([sum_rewards])
+
+def ExploreWorker(rank, childPipe, envname, args):
+ env = gym.make(envname)
+ nb_inputs = env.observation_space.shape[0]
+ normalizer = Normalizer(nb_inputs)
+ observation_n = env.reset()
+ n = 0
+ while True:
+ n += 1
+ try:
+ # Only block for short times to have keyboard exceptions be raised.
+ if not childPipe.poll(0.001):
continue
- if message == _CLOSE:
- childPipe.send(["close ok"])
- break
- childPipe.close()
-
+ message, payload = childPipe.recv()
+ except (EOFError, KeyboardInterrupt):
+ break
+ if message == _RESET:
+ observation_n = env.reset()
+ childPipe.send(["reset ok"])
+ continue
+ if message == _EXPLORE:
+ #normalizer = payload[0] #use our local normalizer
+ policy = payload[1]
+ hp = payload[2]
+ direction = payload[3]
+ delta = payload[4]
+ state = env.reset()
+ done = False
+ num_plays = 0.
+ sum_rewards = 0
+ while not done and num_plays < hp.episode_length:
+ normalizer.observe(state)
+ state = normalizer.normalize(state)
+ action = policy.evaluate(state, delta, direction, hp)
+ state, reward, done, _ = env.step(action)
+ reward = max(min(reward, 1), -1)
+ sum_rewards += reward
+ num_plays += 1
+ childPipe.send([sum_rewards])
+ continue
+ if message == _CLOSE:
+ childPipe.send(["close ok"])
+ break
+ childPipe.close()
+
# Normalizing the states
+
class Normalizer():
-
- def __init__(self, nb_inputs):
- self.n = np.zeros(nb_inputs)
- self.mean = np.zeros(nb_inputs)
- self.mean_diff = np.zeros(nb_inputs)
- self.var = np.zeros(nb_inputs)
-
- def observe(self, x):
- self.n += 1.
- last_mean = self.mean.copy()
- self.mean += (x - self.mean) / self.n
- self.mean_diff += (x - last_mean) * (x - self.mean)
- self.var = (self.mean_diff / self.n).clip(min = 1e-2)
-
- def normalize(self, inputs):
- obs_mean = self.mean
- obs_std = np.sqrt(self.var)
- return (inputs - obs_mean) / obs_std
+
+ def __init__(self, nb_inputs):
+ self.n = np.zeros(nb_inputs)
+ self.mean = np.zeros(nb_inputs)
+ self.mean_diff = np.zeros(nb_inputs)
+ self.var = np.zeros(nb_inputs)
+
+ def observe(self, x):
+ self.n += 1.
+ last_mean = self.mean.copy()
+ self.mean += (x - self.mean) / self.n
+ self.mean_diff += (x - last_mean) * (x - self.mean)
+ self.var = (self.mean_diff / self.n).clip(min=1e-2)
+
+ def normalize(self, inputs):
+ obs_mean = self.mean
+ obs_std = np.sqrt(self.var)
+ return (inputs - obs_mean) / obs_std
+
# Building the AI
+
class Policy():
- def __init__(self, input_size, output_size, env_name, args):
- try:
- self.theta = np.load(args.policy)
- except:
- self.theta = np.zeros((output_size, input_size))
- self.env_name = env_name
- print("Starting policy theta=",self.theta)
- def evaluate(self, input, delta, direction, hp):
- if direction is None:
- return np.clip(self.theta.dot(input), -1.0, 1.0)
- elif direction == "positive":
- return np.clip((self.theta + hp.noise*delta).dot(input), -1.0, 1.0)
- else:
- return np.clip((self.theta - hp.noise*delta).dot(input), -1.0, 1.0)
-
- def sample_deltas(self):
- return [np.random.randn(*self.theta.shape) for _ in range(hp.nb_directions)]
-
- def update(self, rollouts, sigma_r, args):
- step = np.zeros(self.theta.shape)
- for r_pos, r_neg, d in rollouts:
- step += (r_pos - r_neg) * d
- self.theta += hp.learning_rate / (hp.nb_best_directions * sigma_r) * step
- timestr = time.strftime("%Y%m%d-%H%M%S")
- np.save(args.logdir+"/policy_"+self.env_name+"_"+timestr+".npy", self.theta)
+
+ def __init__(self, input_size, output_size, env_name, args):
+ try:
+ self.theta = np.load(args.policy)
+ except:
+ self.theta = np.zeros((output_size, input_size))
+ self.env_name = env_name
+ print("Starting policy theta=", self.theta)
+
+ def evaluate(self, input, delta, direction, hp):
+ if direction is None:
+ return np.clip(self.theta.dot(input), -1.0, 1.0)
+ elif direction == "positive":
+ return np.clip((self.theta + hp.noise * delta).dot(input), -1.0, 1.0)
+ else:
+ return np.clip((self.theta - hp.noise * delta).dot(input), -1.0, 1.0)
+
+ def sample_deltas(self):
+ return [np.random.randn(*self.theta.shape) for _ in range(hp.nb_directions)]
+
+ def update(self, rollouts, sigma_r, args):
+ step = np.zeros(self.theta.shape)
+ for r_pos, r_neg, d in rollouts:
+ step += (r_pos - r_neg) * d
+ self.theta += hp.learning_rate / (hp.nb_best_directions * sigma_r) * step
+ timestr = time.strftime("%Y%m%d-%H%M%S")
+ np.save(args.logdir + "/policy_" + self.env_name + "_" + timestr + ".npy", self.theta)
# Exploring the policy on one specific direction and over one episode
+
def explore(env, normalizer, policy, direction, delta, hp):
- state = env.reset()
- done = False
- num_plays = 0.
- sum_rewards = 0
- while not done and num_plays < hp.episode_length:
- normalizer.observe(state)
- state = normalizer.normalize(state)
- action = policy.evaluate(state, delta, direction, hp)
- state, reward, done, _ = env.step(action)
- reward = max(min(reward, 1), -1)
- sum_rewards += reward
- num_plays += 1
- return sum_rewards
+ state = env.reset()
+ done = False
+ num_plays = 0.
+ sum_rewards = 0
+ while not done and num_plays < hp.episode_length:
+ normalizer.observe(state)
+ state = normalizer.normalize(state)
+ action = policy.evaluate(state, delta, direction, hp)
+ state, reward, done, _ = env.step(action)
+ reward = max(min(reward, 1), -1)
+ sum_rewards += reward
+ num_plays += 1
+ return sum_rewards
+
# Training the AI
+
def train(env, policy, normalizer, hp, parentPipes, args):
-
- for step in range(hp.nb_steps):
-
- # Initializing the perturbations deltas and the positive/negative rewards
- deltas = policy.sample_deltas()
- positive_rewards = [0] * hp.nb_directions
- negative_rewards = [0] * hp.nb_directions
-
- if parentPipes:
- for k in range(hp.nb_directions):
- parentPipe = parentPipes[k]
- parentPipe.send([_EXPLORE,[normalizer, policy, hp, "positive", deltas[k]]])
- for k in range(hp.nb_directions):
- positive_rewards[k] = parentPipes[k].recv()[0]
-
- for k in range(hp.nb_directions):
- parentPipe = parentPipes[k]
- parentPipe.send([_EXPLORE,[normalizer, policy, hp, "negative", deltas[k]]])
- for k in range(hp.nb_directions):
- negative_rewards[k] = parentPipes[k].recv()[0]
-
- else:
- # Getting the positive rewards in the positive directions
- for k in range(hp.nb_directions):
- positive_rewards[k] = explore(env, normalizer, policy, "positive", deltas[k], hp)
-
-
- # Getting the negative rewards in the negative/opposite directions
- for k in range(hp.nb_directions):
- negative_rewards[k] = explore(env, normalizer, policy, "negative", deltas[k], hp)
-
-
- # Gathering all the positive/negative rewards to compute the standard deviation of these rewards
- all_rewards = np.array(positive_rewards + negative_rewards)
- sigma_r = all_rewards.std()
-
- # Sorting the rollouts by the max(r_pos, r_neg) and selecting the best directions
- scores = {k:max(r_pos, r_neg) for k,(r_pos,r_neg) in enumerate(zip(positive_rewards, negative_rewards))}
- order = sorted(scores.keys(), key = lambda x:scores[x])[:hp.nb_best_directions]
- rollouts = [(positive_rewards[k], negative_rewards[k], deltas[k]) for k in order]
-
- # Updating our policy
- policy.update(rollouts, sigma_r, args)
-
- # Printing the final reward of the policy after the update
- reward_evaluation = explore(env, normalizer, policy, None, None, hp)
- print('Step:', step, 'Reward:', reward_evaluation)
+
+ for step in range(hp.nb_steps):
+
+ # Initializing the perturbations deltas and the positive/negative rewards
+ deltas = policy.sample_deltas()
+ positive_rewards = [0] * hp.nb_directions
+ negative_rewards = [0] * hp.nb_directions
+
+ if parentPipes:
+ for k in range(hp.nb_directions):
+ parentPipe = parentPipes[k]
+ parentPipe.send([_EXPLORE, [normalizer, policy, hp, "positive", deltas[k]]])
+ for k in range(hp.nb_directions):
+ positive_rewards[k] = parentPipes[k].recv()[0]
+
+ for k in range(hp.nb_directions):
+ parentPipe = parentPipes[k]
+ parentPipe.send([_EXPLORE, [normalizer, policy, hp, "negative", deltas[k]]])
+ for k in range(hp.nb_directions):
+ negative_rewards[k] = parentPipes[k].recv()[0]
+
+ else:
+ # Getting the positive rewards in the positive directions
+ for k in range(hp.nb_directions):
+ positive_rewards[k] = explore(env, normalizer, policy, "positive", deltas[k], hp)
+
+ # Getting the negative rewards in the negative/opposite directions
+ for k in range(hp.nb_directions):
+ negative_rewards[k] = explore(env, normalizer, policy, "negative", deltas[k], hp)
+
+ # Gathering all the positive/negative rewards to compute the standard deviation of these rewards
+ all_rewards = np.array(positive_rewards + negative_rewards)
+ sigma_r = all_rewards.std()
+
+ # Sorting the rollouts by the max(r_pos, r_neg) and selecting the best directions
+ scores = {
+ k: max(r_pos, r_neg)
+ for k, (r_pos, r_neg) in enumerate(zip(positive_rewards, negative_rewards))
+ }
+ order = sorted(scores.keys(), key=lambda x: scores[x])[:hp.nb_best_directions]
+ rollouts = [(positive_rewards[k], negative_rewards[k], deltas[k]) for k in order]
+
+ # Updating our policy
+ policy.update(rollouts, sigma_r, args)
+
+ # Printing the final reward of the policy after the update
+ reward_evaluation = explore(env, normalizer, policy, None, None, hp)
+ print('Step:', step, 'Reward:', reward_evaluation)
+
# Running the main code
+
def mkdir(base, name):
- path = os.path.join(base, name)
- if not os.path.exists(path):
- os.makedirs(path)
- return path
+ path = os.path.join(base, name)
+ if not os.path.exists(path):
+ os.makedirs(path)
+ return path
+if __name__ == "__main__":
+ mp.freeze_support()
+ parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
+ parser.add_argument('--env',
+ help='Gym environment name',
+ type=str,
+ default='HalfCheetahBulletEnv-v0')
+ parser.add_argument('--seed', help='RNG seed', type=int, default=1)
+ parser.add_argument('--render', help='OpenGL Visualizer', type=int, default=0)
+ parser.add_argument('--movie', help='rgb_array gym movie', type=int, default=0)
+ parser.add_argument('--steps', help='Number of steps', type=int, default=10000)
+ parser.add_argument('--policy', help='Starting policy file (npy)', type=str, default='')
+ parser.add_argument('--logdir',
+ help='Directory root to log policy files (npy)',
+ type=str,
+ default='.')
+ parser.add_argument('--mp', help='Enable multiprocessing', type=int, default=1)
-if __name__ == "__main__":
- mp.freeze_support()
-
- parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
- parser.add_argument('--env', help='Gym environment name', type=str, default='HalfCheetahBulletEnv-v0')
- parser.add_argument('--seed', help='RNG seed', type=int, default=1)
- parser.add_argument('--render', help='OpenGL Visualizer', type=int, default=0)
- parser.add_argument('--movie',help='rgb_array gym movie',type=int, default=0)
- parser.add_argument('--steps', help='Number of steps', type=int, default=10000)
- parser.add_argument('--policy', help='Starting policy file (npy)', type=str, default='')
- parser.add_argument('--logdir', help='Directory root to log policy files (npy)', type=str, default='.')
- parser.add_argument('--mp', help='Enable multiprocessing', type=int, default=1)
-
- args = parser.parse_args()
-
- hp = Hp()
- hp.env_name = args.env
- hp.seed = args.seed
- hp.nb_steps = args.steps
- print("seed = ", hp.seed)
- np.random.seed(hp.seed)
-
- parentPipes = None
- if args.mp:
- num_processes = hp.nb_directions
- processes = []
- childPipes = []
- parentPipes = []
-
- for pr in range (num_processes):
- parentPipe, childPipe = Pipe()
- parentPipes.append(parentPipe)
- childPipes.append(childPipe)
-
- for rank in range(num_processes):
- p = mp.Process(target=ExploreWorker, args=(rank,childPipes[rank], hp.env_name, args))
- p.start()
- processes.append(p)
-
- work_dir = mkdir('exp', 'brs')
- monitor_dir = mkdir(work_dir, 'monitor')
- env = gym.make(hp.env_name)
- if args.render:
- env.render(mode = "human")
- if args.movie:
- env = wrappers.Monitor(env, monitor_dir, force = True)
- nb_inputs = env.observation_space.shape[0]
- nb_outputs = env.action_space.shape[0]
- policy = Policy(nb_inputs, nb_outputs,hp.env_name, args)
- normalizer = Normalizer(nb_inputs)
-
- print("start training")
- train(env, policy, normalizer, hp, parentPipes, args)
-
- if args.mp:
- for parentPipe in parentPipes:
- parentPipe.send([_CLOSE,"pay2"])
-
- for p in processes:
- p.join()
+ args = parser.parse_args()
+
+ hp = Hp()
+ hp.env_name = args.env
+ hp.seed = args.seed
+ hp.nb_steps = args.steps
+ print("seed = ", hp.seed)
+ np.random.seed(hp.seed)
+
+ parentPipes = None
+ if args.mp:
+ num_processes = hp.nb_directions
+ processes = []
+ childPipes = []
+ parentPipes = []
+
+ for pr in range(num_processes):
+ parentPipe, childPipe = Pipe()
+ parentPipes.append(parentPipe)
+ childPipes.append(childPipe)
+
+ for rank in range(num_processes):
+ p = mp.Process(target=ExploreWorker, args=(rank, childPipes[rank], hp.env_name, args))
+ p.start()
+ processes.append(p)
+
+ work_dir = mkdir('exp', 'brs')
+ monitor_dir = mkdir(work_dir, 'monitor')
+ env = gym.make(hp.env_name)
+ if args.render:
+ env.render(mode="human")
+ if args.movie:
+ env = wrappers.Monitor(env, monitor_dir, force=True)
+ nb_inputs = env.observation_space.shape[0]
+ nb_outputs = env.action_space.shape[0]
+ policy = Policy(nb_inputs, nb_outputs, hp.env_name, args)
+ normalizer = Normalizer(nb_inputs)
+
+ print("start training")
+ train(env, policy, normalizer, hp, parentPipes, args)
+
+ if args.mp:
+ for parentPipe in parentPipes:
+ parentPipe.send([_CLOSE, "pay2"])
+
+ for p in processes:
+ p.join()
diff --git a/examples/pybullet/gym/pybullet_envs/__init__.py b/examples/pybullet/gym/pybullet_envs/__init__.py
index e34508ed2..03c064c36 100644
--- a/examples/pybullet/gym/pybullet_envs/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/__init__.py
@@ -1,25 +1,28 @@
import gym
from gym.envs.registration import registry, make, spec
-def register(id,*args,**kvargs):
- if id in registry.env_specs:
- return
- else:
- return gym.envs.registration.register(id,*args,**kvargs)
+
+
+def register(id, *args, **kvargs):
+ if id in registry.env_specs:
+ return
+ else:
+ return gym.envs.registration.register(id, *args, **kvargs)
+
# ------------bullet-------------
register(
- id='HumanoidDeepMimicBulletEnv-v1',
- entry_point='pybullet_envs.deep_mimic:HumanoidDeepMimicGymEnv',
- max_episode_steps=1000,
- reward_threshold=20000.0,
+ id='HumanoidDeepMimicBulletEnv-v1',
+ entry_point='pybullet_envs.deep_mimic:HumanoidDeepMimicGymEnv',
+ max_episode_steps=1000,
+ reward_threshold=20000.0,
)
register(
- id='CartPoleBulletEnv-v1',
- entry_point='pybullet_envs.bullet:CartPoleBulletEnv',
- max_episode_steps=200,
- reward_threshold=190.0,
+ id='CartPoleBulletEnv-v1',
+ entry_point='pybullet_envs.bullet:CartPoleBulletEnv',
+ max_episode_steps=200,
+ reward_threshold=190.0,
)
register(
@@ -36,7 +39,6 @@ register(
reward_threshold=5.0,
)
-
register(
id='MinitaurReactiveEnv-v0',
entry_point='pybullet_envs.minitaur.envs:MinitaurReactiveEnv',
@@ -44,7 +46,6 @@ register(
reward_threshold=5.0,
)
-
register(
id='MinitaurBallGymEnv-v0',
entry_point='pybullet_envs.minitaur.envs:MinitaurBallGymEnv',
@@ -52,7 +53,6 @@ register(
reward_threshold=5.0,
)
-
register(
id='MinitaurTrottingEnv-v0',
entry_point='pybullet_envs.minitaur.envs:MinitaurTrottingEnv',
@@ -81,8 +81,6 @@ register(
reward_threshold=5.0,
)
-
-
register(
id='RacecarBulletEnv-v0',
entry_point='pybullet_envs.bullet:RacecarGymEnv',
@@ -91,128 +89,113 @@ register(
)
register(
- id='RacecarZedBulletEnv-v0',
- entry_point='pybullet_envs.bullet:RacecarZEDGymEnv',
- max_episode_steps=1000,
- reward_threshold=5.0,
+ id='RacecarZedBulletEnv-v0',
+ entry_point='pybullet_envs.bullet:RacecarZEDGymEnv',
+ max_episode_steps=1000,
+ reward_threshold=5.0,
)
-
register(
- id='KukaBulletEnv-v0',
- entry_point='pybullet_envs.bullet:KukaGymEnv',
- max_episode_steps=1000,
- reward_threshold=5.0,
+ id='KukaBulletEnv-v0',
+ entry_point='pybullet_envs.bullet:KukaGymEnv',
+ max_episode_steps=1000,
+ reward_threshold=5.0,
)
register(
- id='KukaCamBulletEnv-v0',
- entry_point='pybullet_envs.bullet:KukaCamGymEnv',
- max_episode_steps=1000,
- reward_threshold=5.0,
+ id='KukaCamBulletEnv-v0',
+ entry_point='pybullet_envs.bullet:KukaCamGymEnv',
+ max_episode_steps=1000,
+ reward_threshold=5.0,
)
register(
- id='KukaDiverseObjectGrasping-v0',
- entry_point='pybullet_envs.bullet:KukaDiverseObjectEnv',
- max_episode_steps=1000,
- reward_threshold=5.0,
+ id='KukaDiverseObjectGrasping-v0',
+ entry_point='pybullet_envs.bullet:KukaDiverseObjectEnv',
+ max_episode_steps=1000,
+ reward_threshold=5.0,
)
register(
- id='InvertedPendulumBulletEnv-v0',
- entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumBulletEnv',
- max_episode_steps=1000,
- reward_threshold=950.0,
- )
+ id='InvertedPendulumBulletEnv-v0',
+ entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=950.0,
+)
register(
- id='InvertedDoublePendulumBulletEnv-v0',
- entry_point='pybullet_envs.gym_pendulum_envs:InvertedDoublePendulumBulletEnv',
- max_episode_steps=1000,
- reward_threshold=9100.0,
- )
+ id='InvertedDoublePendulumBulletEnv-v0',
+ entry_point='pybullet_envs.gym_pendulum_envs:InvertedDoublePendulumBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=9100.0,
+)
register(
- id='InvertedPendulumSwingupBulletEnv-v0',
- entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumSwingupBulletEnv',
- max_episode_steps=1000,
- reward_threshold=800.0,
- )
+ id='InvertedPendulumSwingupBulletEnv-v0',
+ entry_point='pybullet_envs.gym_pendulum_envs:InvertedPendulumSwingupBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=800.0,
+)
register(
- id='ReacherBulletEnv-v0',
- entry_point='pybullet_envs.gym_manipulator_envs:ReacherBulletEnv',
- max_episode_steps=150,
- reward_threshold=18.0,
- )
+ id='ReacherBulletEnv-v0',
+ entry_point='pybullet_envs.gym_manipulator_envs:ReacherBulletEnv',
+ max_episode_steps=150,
+ reward_threshold=18.0,
+)
register(
- id='PusherBulletEnv-v0',
- entry_point='pybullet_envs.gym_manipulator_envs:PusherBulletEnv',
- max_episode_steps=150,
- reward_threshold=18.0,
+ id='PusherBulletEnv-v0',
+ entry_point='pybullet_envs.gym_manipulator_envs:PusherBulletEnv',
+ max_episode_steps=150,
+ reward_threshold=18.0,
)
register(
- id='ThrowerBulletEnv-v0',
- entry_point='pybullet_envs.gym_manipulator_envs:ThrowerBulletEnv',
- max_episode_steps=100,
- reward_threshold=18.0,
+ id='ThrowerBulletEnv-v0',
+ entry_point='pybullet_envs.gym_manipulator_envs:ThrowerBulletEnv',
+ max_episode_steps=100,
+ reward_threshold=18.0,
)
register(
- id='StrikerBulletEnv-v0',
- entry_point='pybullet_envs.gym_manipulator_envs:StrikerBulletEnv',
- max_episode_steps=100,
- reward_threshold=18.0,
+ id='StrikerBulletEnv-v0',
+ entry_point='pybullet_envs.gym_manipulator_envs:StrikerBulletEnv',
+ max_episode_steps=100,
+ reward_threshold=18.0,
)
-register(
- id='Walker2DBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:Walker2DBulletEnv',
- max_episode_steps=1000,
- reward_threshold=2500.0
- )
-register(
- id='HalfCheetahBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:HalfCheetahBulletEnv',
- max_episode_steps=1000,
- reward_threshold=3000.0
- )
+register(id='Walker2DBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:Walker2DBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=2500.0)
+register(id='HalfCheetahBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:HalfCheetahBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=3000.0)
-register(
- id='AntBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:AntBulletEnv',
- max_episode_steps=1000,
- reward_threshold=2500.0
- )
+register(id='AntBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:AntBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=2500.0)
-register(
- id='HopperBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:HopperBulletEnv',
- max_episode_steps=1000,
- reward_threshold=2500.0
- )
+register(id='HopperBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:HopperBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=2500.0)
-register(
- id='HumanoidBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:HumanoidBulletEnv',
- max_episode_steps=1000
- )
+register(id='HumanoidBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:HumanoidBulletEnv',
+ max_episode_steps=1000)
-register(
- id='HumanoidFlagrunBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:HumanoidFlagrunBulletEnv',
- max_episode_steps=1000,
- reward_threshold=2000.0
- )
+register(id='HumanoidFlagrunBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:HumanoidFlagrunBulletEnv',
+ max_episode_steps=1000,
+ reward_threshold=2000.0)
-register(
- id='HumanoidFlagrunHarderBulletEnv-v0',
- entry_point='pybullet_envs.gym_locomotion_envs:HumanoidFlagrunHarderBulletEnv',
- max_episode_steps=1000
- )
+register(id='HumanoidFlagrunHarderBulletEnv-v0',
+ entry_point='pybullet_envs.gym_locomotion_envs:HumanoidFlagrunHarderBulletEnv',
+ max_episode_steps=1000)
#register(
# id='AtlasBulletEnv-v0',
@@ -220,6 +203,7 @@ register(
# max_episode_steps=1000
# )
+
def getList():
- btenvs = ['- ' + spec.id for spec in gym.envs.registry.all() if spec.id.find('Bullet')>=0]
- return btenvs
+ btenvs = ['- ' + spec.id for spec in gym.envs.registry.all() if spec.id.find('Bullet') >= 0]
+ return btenvs
diff --git a/examples/pybullet/gym/pybullet_envs/agents/__init__.py b/examples/pybullet/gym/pybullet_envs/agents/__init__.py
index c29ce33fe..9fc2d2951 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Executable scripts for reinforcement learning."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/configs.py b/examples/pybullet/gym/pybullet_envs/agents/configs.py
index 6ac584db6..992d226ef 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/configs.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/configs.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Example configurations using the PPO algorithm."""
from __future__ import absolute_import
@@ -29,6 +28,7 @@ import pybullet_envs.bullet.minitaur_gym_env as minitaur_gym_env
import pybullet_envs
import tensorflow as tf
+
def default():
"""Default configuration for PPO."""
# General
@@ -38,10 +38,7 @@ def default():
use_gpu = False
# Network
network = networks.feed_forward_gaussian
- weight_summaries = dict(
- all=r'.*',
- policy=r'.*/policy/.*',
- value=r'.*/value/.*')
+ weight_summaries = dict(all=r'.*', policy=r'.*/policy/.*', value=r'.*/value/.*')
policy_layers = 200, 100
value_layers = 200, 100
init_mean_factor = 0.1
@@ -52,7 +49,7 @@ def default():
optimizer = tf.train.AdamOptimizer
update_epochs_policy = 64
update_epochs_value = 64
- learning_rate = 1e-4
+ learning_rate = 1e-4
# Losses
discount = 0.995
kl_target = 1e-2
@@ -69,6 +66,7 @@ def pybullet_pendulum():
steps = 5e7 # 50M
return locals()
+
def pybullet_doublependulum():
locals().update(default())
env = 'InvertedDoublePendulumBulletEnv-v0'
@@ -76,6 +74,7 @@ def pybullet_doublependulum():
steps = 5e7 # 50M
return locals()
+
def pybullet_pendulumswingup():
locals().update(default())
env = 'InvertedPendulumSwingupBulletEnv-v0'
@@ -83,6 +82,7 @@ def pybullet_pendulumswingup():
steps = 5e7 # 50M
return locals()
+
def pybullet_cheetah():
"""Configuration for MuJoCo's half cheetah task."""
locals().update(default())
@@ -92,6 +92,7 @@ def pybullet_cheetah():
steps = 1e8 # 100M
return locals()
+
def pybullet_ant():
locals().update(default())
env = 'AntBulletEnv-v0'
@@ -99,6 +100,7 @@ def pybullet_ant():
steps = 5e7 # 50M
return locals()
+
def pybullet_kuka_grasping():
"""Configuration for Bullet Kuka grasping task."""
locals().update(default())
@@ -113,7 +115,7 @@ def pybullet_racecar():
"""Configuration for Bullet MIT Racecar task."""
locals().update(default())
# Environment
- env = 'RacecarBulletEnv-v0' #functools.partial(racecarGymEnv.RacecarGymEnv, isDiscrete=False, renders=True)
+ env = 'RacecarBulletEnv-v0' #functools.partial(racecarGymEnv.RacecarGymEnv, isDiscrete=False, renders=True)
max_length = 10
steps = 1e7 # 10M
return locals()
@@ -132,29 +134,27 @@ def pybullet_minitaur():
"""Configuration specific to minitaur_gym_env.MinitaurBulletEnv class."""
locals().update(default())
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
- env = functools.partial(
- minitaur_gym_env.MinitaurBulletEnv,
- accurate_motor_model_enabled=True,
- motor_overheat_protection=True,
- pd_control_enabled=True,
- env_randomizer=randomizer,
- render=False)
+ env = functools.partial(minitaur_gym_env.MinitaurBulletEnv,
+ accurate_motor_model_enabled=True,
+ motor_overheat_protection=True,
+ pd_control_enabled=True,
+ env_randomizer=randomizer,
+ render=False)
max_length = 1000
steps = 3e7 # 30M
return locals()
+
def pybullet_duck_minitaur():
"""Configuration specific to minitaur_gym_env.MinitaurBulletDuckEnv class."""
locals().update(default())
randomizer = (minitaur_env_randomizer.MinitaurEnvRandomizer())
- env = functools.partial(
- minitaur_gym_env.MinitaurBulletDuckEnv,
- accurate_motor_model_enabled=True,
- motor_overheat_protection=True,
- pd_control_enabled=True,
- env_randomizer=randomizer,
- render=False)
+ env = functools.partial(minitaur_gym_env.MinitaurBulletDuckEnv,
+ accurate_motor_model_enabled=True,
+ motor_overheat_protection=True,
+ pd_control_enabled=True,
+ env_randomizer=randomizer,
+ render=False)
max_length = 1000
steps = 3e7 # 30M
return locals()
-
diff --git a/examples/pybullet/gym/pybullet_envs/agents/networks.py b/examples/pybullet/gym/pybullet_envs/agents/networks.py
index 3d5de1fbb..3b6802d02 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/networks.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/networks.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Network definitions for the PPO algorithm."""
from __future__ import absolute_import
@@ -24,13 +23,10 @@ import operator
import tensorflow as tf
-
-NetworkOutput = collections.namedtuple(
- 'NetworkOutput', 'policy, mean, logstd, value, state')
+NetworkOutput = collections.namedtuple('NetworkOutput', 'policy, mean, logstd, value, state')
-def feed_forward_gaussian(
- config, action_size, observations, unused_length, state=None):
+def feed_forward_gaussian(config, action_size, observations, unused_length, state=None):
"""Independent feed forward networks for policy and value.
The policy network outputs the mean action and the log standard deviation
@@ -50,20 +46,22 @@ def feed_forward_gaussian(
factor=config.init_mean_factor)
logstd_initializer = tf.random_normal_initializer(config.init_logstd, 1e-10)
flat_observations = tf.reshape(observations, [
- tf.shape(observations)[0], tf.shape(observations)[1],
- functools.reduce(operator.mul, observations.shape.as_list()[2:], 1)])
+ tf.shape(observations)[0],
+ tf.shape(observations)[1],
+ functools.reduce(operator.mul,
+ observations.shape.as_list()[2:], 1)
+ ])
with tf.variable_scope('policy'):
x = flat_observations
for size in config.policy_layers:
x = tf.contrib.layers.fully_connected(x, size, tf.nn.relu)
- mean = tf.contrib.layers.fully_connected(
- x, action_size, tf.tanh,
- weights_initializer=mean_weights_initializer)
- logstd = tf.get_variable(
- 'logstd', mean.shape[2:], tf.float32, logstd_initializer)
- logstd = tf.tile(
- logstd[None, None],
- [tf.shape(mean)[0], tf.shape(mean)[1]] + [1] * (mean.shape.ndims - 2))
+ mean = tf.contrib.layers.fully_connected(x,
+ action_size,
+ tf.tanh,
+ weights_initializer=mean_weights_initializer)
+ logstd = tf.get_variable('logstd', mean.shape[2:], tf.float32, logstd_initializer)
+ logstd = tf.tile(logstd[None, None],
+ [tf.shape(mean)[0], tf.shape(mean)[1]] + [1] * (mean.shape.ndims - 2))
with tf.variable_scope('value'):
x = flat_observations
for size in config.value_layers:
@@ -72,13 +70,11 @@ def feed_forward_gaussian(
mean = tf.check_numerics(mean, 'mean')
logstd = tf.check_numerics(logstd, 'logstd')
value = tf.check_numerics(value, 'value')
- policy = tf.contrib.distributions.MultivariateNormalDiag(
- mean, tf.exp(logstd))
+ policy = tf.contrib.distributions.MultivariateNormalDiag(mean, tf.exp(logstd))
return NetworkOutput(policy, mean, logstd, value, state)
-def recurrent_gaussian(
- config, action_size, observations, length, state=None):
+def recurrent_gaussian(config, action_size, observations, length, state=None):
"""Independent recurrent policy and feed forward value networks.
The policy network outputs the mean action and the log standard deviation
@@ -100,21 +96,23 @@ def recurrent_gaussian(
logstd_initializer = tf.random_normal_initializer(config.init_logstd, 1e-10)
cell = tf.contrib.rnn.GRUBlockCell(config.policy_layers[-1])
flat_observations = tf.reshape(observations, [
- tf.shape(observations)[0], tf.shape(observations)[1],
- functools.reduce(operator.mul, observations.shape.as_list()[2:], 1)])
+ tf.shape(observations)[0],
+ tf.shape(observations)[1],
+ functools.reduce(operator.mul,
+ observations.shape.as_list()[2:], 1)
+ ])
with tf.variable_scope('policy'):
x = flat_observations
for size in config.policy_layers[:-1]:
x = tf.contrib.layers.fully_connected(x, size, tf.nn.relu)
x, state = tf.nn.dynamic_rnn(cell, x, length, state, tf.float32)
- mean = tf.contrib.layers.fully_connected(
- x, action_size, tf.tanh,
- weights_initializer=mean_weights_initializer)
- logstd = tf.get_variable(
- 'logstd', mean.shape[2:], tf.float32, logstd_initializer)
- logstd = tf.tile(
- logstd[None, None],
- [tf.shape(mean)[0], tf.shape(mean)[1]] + [1] * (mean.shape.ndims - 2))
+ mean = tf.contrib.layers.fully_connected(x,
+ action_size,
+ tf.tanh,
+ weights_initializer=mean_weights_initializer)
+ logstd = tf.get_variable('logstd', mean.shape[2:], tf.float32, logstd_initializer)
+ logstd = tf.tile(logstd[None, None],
+ [tf.shape(mean)[0], tf.shape(mean)[1]] + [1] * (mean.shape.ndims - 2))
with tf.variable_scope('value'):
x = flat_observations
for size in config.value_layers:
@@ -123,7 +121,6 @@ def recurrent_gaussian(
mean = tf.check_numerics(mean, 'mean')
logstd = tf.check_numerics(logstd, 'logstd')
value = tf.check_numerics(value, 'value')
- policy = tf.contrib.distributions.MultivariateNormalDiag(
- mean, tf.exp(logstd))
+ policy = tf.contrib.distributions.MultivariateNormalDiag(mean, tf.exp(logstd))
# assert state.shape.as_list()[0] is not None
return NetworkOutput(policy, mean, logstd, value, state)
diff --git a/examples/pybullet/gym/pybullet_envs/agents/ppo/__init__.py b/examples/pybullet/gym/pybullet_envs/agents/ppo/__init__.py
index 26a87baf9..6f4c222dd 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/ppo/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/ppo/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Proximal Policy Optimization algorithm."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/ppo/algorithm.py b/examples/pybullet/gym/pybullet_envs/agents/ppo/algorithm.py
index 9e97425f9..c6921095f 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/ppo/algorithm.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/ppo/algorithm.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Proximal Policy Optimization algorithm.
Based on John Schulman's implementation in Python and Theano:
@@ -49,51 +48,51 @@ class PPOAlgorithm(object):
self._is_training = is_training
self._should_log = should_log
self._config = config
- self._observ_filter = normalize.StreamingNormalize(
- self._batch_env.observ[0], center=True, scale=True, clip=5,
- name='normalize_observ')
- self._reward_filter = normalize.StreamingNormalize(
- self._batch_env.reward[0], center=False, scale=True, clip=10,
- name='normalize_reward')
+ self._observ_filter = normalize.StreamingNormalize(self._batch_env.observ[0],
+ center=True,
+ scale=True,
+ clip=5,
+ name='normalize_observ')
+ self._reward_filter = normalize.StreamingNormalize(self._batch_env.reward[0],
+ center=False,
+ scale=True,
+ clip=10,
+ name='normalize_reward')
# Memory stores tuple of observ, action, mean, logstd, reward.
- template = (
- self._batch_env.observ[0], self._batch_env.action[0],
- self._batch_env.action[0], self._batch_env.action[0],
- self._batch_env.reward[0])
- self._memory = memory.EpisodeMemory(
- template, config.update_every, config.max_length, 'memory')
+ template = (self._batch_env.observ[0], self._batch_env.action[0], self._batch_env.action[0],
+ self._batch_env.action[0], self._batch_env.reward[0])
+ self._memory = memory.EpisodeMemory(template, config.update_every, config.max_length, 'memory')
self._memory_index = tf.Variable(0, False)
use_gpu = self._config.use_gpu and utility.available_gpus()
with tf.device('/gpu:0' if use_gpu else '/cpu:0'):
# Create network variables for later calls to reuse.
action_size = self._batch_env.action.shape[1].value
- self._network = tf.make_template(
- 'network', functools.partial(config.network, config, action_size))
+ self._network = tf.make_template('network',
+ functools.partial(config.network, config, action_size))
output = self._network(
- tf.zeros_like(self._batch_env.observ)[:, None],
- tf.ones(len(self._batch_env)))
+ tf.zeros_like(self._batch_env.observ)[:, None], tf.ones(len(self._batch_env)))
with tf.variable_scope('ppo_temporary'):
- self._episodes = memory.EpisodeMemory(
- template, len(batch_env), config.max_length, 'episodes')
+ self._episodes = memory.EpisodeMemory(template, len(batch_env), config.max_length,
+ 'episodes')
if output.state is None:
self._last_state = None
else:
# Ensure the batch dimension is set.
tf.contrib.framework.nest.map_structure(
- lambda x: x.set_shape([len(batch_env)] + x.shape.as_list()[1:]),
- output.state)
+ lambda x: x.set_shape([len(batch_env)] + x.shape.as_list()[1:]), output.state)
# pylint: disable=undefined-variable
self._last_state = tf.contrib.framework.nest.map_structure(
- lambda x: tf.Variable(lambda: tf.zeros_like(x), False),
- output.state)
- self._last_action = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_action')
- self._last_mean = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_mean')
- self._last_logstd = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_logstd')
- self._penalty = tf.Variable(
- self._config.kl_init_penalty, False, dtype=tf.float32)
+ lambda x: tf.Variable(lambda: tf.zeros_like(x), False), output.state)
+ self._last_action = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_action')
+ self._last_mean = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_mean')
+ self._last_logstd = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_logstd')
+ self._penalty = tf.Variable(self._config.kl_init_penalty, False, dtype=tf.float32)
self._optimizer = self._config.optimizer(self._config.learning_rate)
def begin_episode(self, agent_indices):
@@ -109,8 +108,7 @@ class PPOAlgorithm(object):
if self._last_state is None:
reset_state = tf.no_op()
else:
- reset_state = utility.reinit_nested_vars(
- self._last_state, agent_indices)
+ reset_state = utility.reinit_nested_vars(self._last_state, agent_indices)
reset_buffer = self._episodes.clear(agent_indices)
with tf.control_dependencies([reset_state, reset_buffer]):
return tf.constant('')
@@ -130,36 +128,33 @@ class PPOAlgorithm(object):
if self._last_state is None:
state = None
else:
- state = tf.contrib.framework.nest.map_structure(
- lambda x: tf.gather(x, agent_indices), self._last_state)
+ state = tf.contrib.framework.nest.map_structure(lambda x: tf.gather(x, agent_indices),
+ self._last_state)
output = self._network(observ[:, None], tf.ones(observ.shape[0]), state)
- action = tf.cond(
- self._is_training, output.policy.sample, lambda: output.mean)
+ action = tf.cond(self._is_training, output.policy.sample, lambda: output.mean)
logprob = output.policy.log_prob(action)[:, 0]
# pylint: disable=g-long-lambda
- summary = tf.cond(self._should_log, lambda: tf.summary.merge([
- tf.summary.histogram('mean', output.mean[:, 0]),
- tf.summary.histogram('std', tf.exp(output.logstd[:, 0])),
- tf.summary.histogram('action', action[:, 0]),
- tf.summary.histogram('logprob', logprob)]), str)
+ summary = tf.cond(
+ self._should_log, lambda: tf.summary.merge([
+ tf.summary.histogram('mean', output.mean[:, 0]),
+ tf.summary.histogram('std', tf.exp(output.logstd[:, 0])),
+ tf.summary.histogram('action', action[:, 0]),
+ tf.summary.histogram('logprob', logprob)
+ ]), str)
# Remember current policy to append to memory in the experience callback.
if self._last_state is None:
assign_state = tf.no_op()
else:
- assign_state = utility.assign_nested_vars(
- self._last_state, output.state, agent_indices)
+ assign_state = utility.assign_nested_vars(self._last_state, output.state, agent_indices)
with tf.control_dependencies([
assign_state,
- tf.scatter_update(
- self._last_action, agent_indices, action[:, 0]),
- tf.scatter_update(
- self._last_mean, agent_indices, output.mean[:, 0]),
- tf.scatter_update(
- self._last_logstd, agent_indices, output.logstd[:, 0])]):
+ tf.scatter_update(self._last_action, agent_indices, action[:, 0]),
+ tf.scatter_update(self._last_mean, agent_indices, output.mean[:, 0]),
+ tf.scatter_update(self._last_logstd, agent_indices, output.logstd[:, 0])
+ ]):
return tf.check_numerics(action[:, 0], 'action'), tf.identity(summary)
- def experience(
- self, agent_indices, observ, action, reward, unused_done, unused_nextob):
+ def experience(self, agent_indices, observ, action, reward, unused_done, unused_nextob):
"""Process the transition tuple of the current step.
When training, add the current transition tuple to the memory and update
@@ -181,34 +176,36 @@ class PPOAlgorithm(object):
return tf.cond(
self._is_training,
# pylint: disable=g-long-lambda
- lambda: self._define_experience(
- agent_indices, observ, action, reward), str)
+ lambda: self._define_experience(agent_indices, observ, action, reward),
+ str)
def _define_experience(self, agent_indices, observ, action, reward):
"""Implement the branch of experience() entered during training."""
- update_filters = tf.summary.merge([
- self._observ_filter.update(observ),
- self._reward_filter.update(reward)])
+ update_filters = tf.summary.merge(
+ [self._observ_filter.update(observ),
+ self._reward_filter.update(reward)])
with tf.control_dependencies([update_filters]):
if self._config.train_on_agent_action:
# NOTE: Doesn't seem to change much.
action = self._last_action
- batch = (
- observ, action, tf.gather(self._last_mean, agent_indices),
- tf.gather(self._last_logstd, agent_indices), reward)
+ batch = (observ, action, tf.gather(self._last_mean,
+ agent_indices), tf.gather(self._last_logstd,
+ agent_indices), reward)
append = self._episodes.append(batch, agent_indices)
with tf.control_dependencies([append]):
norm_observ = self._observ_filter.transform(observ)
norm_reward = tf.reduce_mean(self._reward_filter.transform(reward))
# pylint: disable=g-long-lambda
- summary = tf.cond(self._should_log, lambda: tf.summary.merge([
- update_filters,
- self._observ_filter.summary(),
- self._reward_filter.summary(),
- tf.summary.scalar('memory_size', self._memory_index),
- tf.summary.histogram('normalized_observ', norm_observ),
- tf.summary.histogram('action', self._last_action),
- tf.summary.scalar('normalized_reward', norm_reward)]), str)
+ summary = tf.cond(
+ self._should_log, lambda: tf.summary.merge([
+ update_filters,
+ self._observ_filter.summary(),
+ self._reward_filter.summary(),
+ tf.summary.scalar('memory_size', self._memory_index),
+ tf.summary.histogram('normalized_observ', norm_observ),
+ tf.summary.histogram('action', self._last_action),
+ tf.summary.scalar('normalized_reward', norm_reward)
+ ]), str)
return summary
def end_episode(self, agent_indices):
@@ -226,20 +223,16 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('end_episode/'):
- return tf.cond(
- self._is_training,
- lambda: self._define_end_episode(agent_indices), str)
+ return tf.cond(self._is_training, lambda: self._define_end_episode(agent_indices), str)
def _define_end_episode(self, agent_indices):
"""Implement the branch of end_episode() entered during training."""
episodes, length = self._episodes.data(agent_indices)
space_left = self._config.update_every - self._memory_index
- use_episodes = tf.range(tf.minimum(
- tf.shape(agent_indices)[0], space_left))
+ use_episodes = tf.range(tf.minimum(tf.shape(agent_indices)[0], space_left))
episodes = [tf.gather(elem, use_episodes) for elem in episodes]
- append = self._memory.replace(
- episodes, tf.gather(length, use_episodes),
- use_episodes + self._memory_index)
+ append = self._memory.replace(episodes, tf.gather(length, use_episodes),
+ use_episodes + self._memory_index)
with tf.control_dependencies([append]):
inc_index = self._memory_index.assign_add(tf.shape(use_episodes)[0])
with tf.control_dependencies([inc_index]):
@@ -256,8 +249,7 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('training'):
- assert_full = tf.assert_equal(
- self._memory_index, self._config.update_every)
+ assert_full = tf.assert_equal(self._memory_index, self._config.update_every)
with tf.control_dependencies([assert_full]):
data = self._memory.data()
(observ, action, old_mean, old_logstd, reward), length = data
@@ -265,22 +257,18 @@ class PPOAlgorithm(object):
length = tf.identity(length)
observ = self._observ_filter.transform(observ)
reward = self._reward_filter.transform(reward)
- update_summary = self._perform_update_steps(
- observ, action, old_mean, old_logstd, reward, length)
+ update_summary = self._perform_update_steps(observ, action, old_mean, old_logstd, reward,
+ length)
with tf.control_dependencies([update_summary]):
- penalty_summary = self._adjust_penalty(
- observ, old_mean, old_logstd, length)
+ penalty_summary = self._adjust_penalty(observ, old_mean, old_logstd, length)
with tf.control_dependencies([penalty_summary]):
- clear_memory = tf.group(
- self._memory.clear(), self._memory_index.assign(0))
+ clear_memory = tf.group(self._memory.clear(), self._memory_index.assign(0))
with tf.control_dependencies([clear_memory]):
- weight_summary = utility.variable_summaries(
- tf.trainable_variables(), self._config.weight_summaries)
- return tf.summary.merge([
- update_summary, penalty_summary, weight_summary])
+ weight_summary = utility.variable_summaries(tf.trainable_variables(),
+ self._config.weight_summaries)
+ return tf.summary.merge([update_summary, penalty_summary, weight_summary])
- def _perform_update_steps(
- self, observ, action, old_mean, old_logstd, reward, length):
+ def _perform_update_steps(self, observ, action, old_mean, old_logstd, reward, length):
"""Perform multiple update steps of value function and policy.
The advantage is computed once at the beginning and shared across
@@ -298,37 +286,29 @@ class PPOAlgorithm(object):
Returns:
Summary tensor.
"""
- return_ = utility.discounted_return(
- reward, length, self._config.discount)
+ return_ = utility.discounted_return(reward, length, self._config.discount)
value = self._network(observ, length).value
if self._config.gae_lambda:
- advantage = utility.lambda_return(
- reward, value, length, self._config.discount,
- self._config.gae_lambda)
+ advantage = utility.lambda_return(reward, value, length, self._config.discount,
+ self._config.gae_lambda)
else:
advantage = return_ - value
mean, variance = tf.nn.moments(advantage, axes=[0, 1], keep_dims=True)
advantage = (advantage - mean) / (tf.sqrt(variance) + 1e-8)
- advantage = tf.Print(
- advantage, [tf.reduce_mean(return_), tf.reduce_mean(value)],
- 'return and value: ')
- advantage = tf.Print(
- advantage, [tf.reduce_mean(advantage)],
- 'normalized advantage: ')
+ advantage = tf.Print(advantage,
+ [tf.reduce_mean(return_), tf.reduce_mean(value)], 'return and value: ')
+ advantage = tf.Print(advantage, [tf.reduce_mean(advantage)], 'normalized advantage: ')
# pylint: disable=g-long-lambda
- value_loss, policy_loss, summary = tf.scan(
- lambda _1, _2: self._update_step(
- observ, action, old_mean, old_logstd, reward, advantage, length),
- tf.range(self._config.update_epochs),
- [0., 0., ''], parallel_iterations=1)
- print_losses = tf.group(
- tf.Print(0, [tf.reduce_mean(value_loss)], 'value loss: '),
- tf.Print(0, [tf.reduce_mean(policy_loss)], 'policy loss: '))
+ value_loss, policy_loss, summary = tf.scan(lambda _1, _2: self._update_step(
+ observ, action, old_mean, old_logstd, reward, advantage, length),
+ tf.range(self._config.update_epochs), [0., 0., ''],
+ parallel_iterations=1)
+ print_losses = tf.group(tf.Print(0, [tf.reduce_mean(value_loss)], 'value loss: '),
+ tf.Print(0, [tf.reduce_mean(policy_loss)], 'policy loss: '))
with tf.control_dependencies([value_loss, policy_loss, print_losses]):
return summary[self._config.update_epochs // 2]
- def _update_step(
- self, observ, action, old_mean, old_logstd, reward, advantage, length):
+ def _update_step(self, observ, action, old_mean, old_logstd, reward, advantage, length):
"""Compute the current combined loss and perform a gradient update step.
Args:
@@ -345,27 +325,20 @@ class PPOAlgorithm(object):
"""
value_loss, value_summary = self._value_loss(observ, reward, length)
network = self._network(observ, length)
- policy_loss, policy_summary = self._policy_loss(
- network.mean, network.logstd, old_mean, old_logstd, action,
- advantage, length)
- value_gradients, value_variables = (
- zip(*self._optimizer.compute_gradients(value_loss)))
- policy_gradients, policy_variables = (
- zip(*self._optimizer.compute_gradients(policy_loss)))
+ policy_loss, policy_summary = self._policy_loss(network.mean, network.logstd, old_mean,
+ old_logstd, action, advantage, length)
+ value_gradients, value_variables = (zip(*self._optimizer.compute_gradients(value_loss)))
+ policy_gradients, policy_variables = (zip(*self._optimizer.compute_gradients(policy_loss)))
all_gradients = value_gradients + policy_gradients
all_variables = value_variables + policy_variables
- optimize = self._optimizer.apply_gradients(
- zip(all_gradients, all_variables))
+ optimize = self._optimizer.apply_gradients(zip(all_gradients, all_variables))
summary = tf.summary.merge([
value_summary, policy_summary,
- tf.summary.scalar(
- 'value_gradient_norm', tf.global_norm(value_gradients)),
- tf.summary.scalar(
- 'policy_gradient_norm', tf.global_norm(policy_gradients)),
- utility.gradient_summaries(
- zip(value_gradients, value_variables), dict(value=r'.*')),
- utility.gradient_summaries(
- zip(policy_gradients, policy_variables), dict(policy=r'.*'))])
+ tf.summary.scalar('value_gradient_norm', tf.global_norm(value_gradients)),
+ tf.summary.scalar('policy_gradient_norm', tf.global_norm(policy_gradients)),
+ utility.gradient_summaries(zip(value_gradients, value_variables), dict(value=r'.*')),
+ utility.gradient_summaries(zip(policy_gradients, policy_variables), dict(policy=r'.*'))
+ ])
with tf.control_dependencies([optimize]):
return [tf.identity(x) for x in (value_loss, policy_loss, summary)]
@@ -385,18 +358,17 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('value_loss'):
value = self._network(observ, length).value
- return_ = utility.discounted_return(
- reward, length, self._config.discount)
+ return_ = utility.discounted_return(reward, length, self._config.discount)
advantage = return_ - value
- value_loss = 0.5 * self._mask(advantage ** 2, length)
+ value_loss = 0.5 * self._mask(advantage**2, length)
summary = tf.summary.merge([
tf.summary.histogram('value_loss', value_loss),
- tf.summary.scalar('avg_value_loss', tf.reduce_mean(value_loss))])
+ tf.summary.scalar('avg_value_loss', tf.reduce_mean(value_loss))
+ ])
value_loss = tf.reduce_mean(value_loss)
return tf.check_numerics(value_loss, 'value_loss'), summary
- def _policy_loss(
- self, mean, logstd, old_mean, old_logstd, action, advantage, length):
+ def _policy_loss(self, mean, logstd, old_mean, old_logstd, action, advantage, length):
"""Compute the policy loss composed of multiple components.
1. The policy gradient loss is importance sampled from the data-collecting
@@ -420,24 +392,20 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('policy_loss'):
entropy = utility.diag_normal_entropy(mean, logstd)
- kl = tf.reduce_mean(self._mask(utility.diag_normal_kl(
- old_mean, old_logstd, mean, logstd), length), 1)
+ kl = tf.reduce_mean(
+ self._mask(utility.diag_normal_kl(old_mean, old_logstd, mean, logstd), length), 1)
policy_gradient = tf.exp(
utility.diag_normal_logpdf(mean, logstd, action) -
utility.diag_normal_logpdf(old_mean, old_logstd, action))
- surrogate_loss = -tf.reduce_mean(self._mask(
- policy_gradient * tf.stop_gradient(advantage), length), 1)
+ surrogate_loss = -tf.reduce_mean(
+ self._mask(policy_gradient * tf.stop_gradient(advantage), length), 1)
kl_penalty = self._penalty * kl
cutoff_threshold = self._config.kl_target * self._config.kl_cutoff_factor
- cutoff_count = tf.reduce_sum(
- tf.cast(kl > cutoff_threshold, tf.int32))
- with tf.control_dependencies([tf.cond(
- cutoff_count > 0,
- lambda: tf.Print(0, [cutoff_count], 'kl cutoff! '), int)]):
- kl_cutoff = (
- self._config.kl_cutoff_coef *
- tf.cast(kl > cutoff_threshold, tf.float32) *
- (kl - cutoff_threshold) ** 2)
+ cutoff_count = tf.reduce_sum(tf.cast(kl > cutoff_threshold, tf.int32))
+ with tf.control_dependencies(
+ [tf.cond(cutoff_count > 0, lambda: tf.Print(0, [cutoff_count], 'kl cutoff! '), int)]):
+ kl_cutoff = (self._config.kl_cutoff_coef * tf.cast(kl > cutoff_threshold, tf.float32) *
+ (kl - cutoff_threshold)**2)
policy_loss = surrogate_loss + kl_penalty + kl_cutoff
summary = tf.summary.merge([
tf.summary.histogram('entropy', entropy),
@@ -449,7 +417,8 @@ class PPOAlgorithm(object):
tf.summary.histogram('policy_loss', policy_loss),
tf.summary.scalar('avg_surr_loss', tf.reduce_mean(surrogate_loss)),
tf.summary.scalar('avg_kl_penalty', tf.reduce_mean(kl_penalty)),
- tf.summary.scalar('avg_policy_loss', tf.reduce_mean(policy_loss))])
+ tf.summary.scalar('avg_policy_loss', tf.reduce_mean(policy_loss))
+ ])
policy_loss = tf.reduce_mean(policy_loss, 0)
return tf.check_numerics(policy_loss, 'policy_loss'), summary
@@ -471,30 +440,30 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('adjust_penalty'):
network = self._network(observ, length)
- assert_change = tf.assert_equal(
- tf.reduce_all(tf.equal(network.mean, old_mean)), False,
- message='policy should change')
+ assert_change = tf.assert_equal(tf.reduce_all(tf.equal(network.mean, old_mean)),
+ False,
+ message='policy should change')
print_penalty = tf.Print(0, [self._penalty], 'current penalty: ')
with tf.control_dependencies([assert_change, print_penalty]):
- kl_change = tf.reduce_mean(self._mask(utility.diag_normal_kl(
- old_mean, old_logstd, network.mean, network.logstd), length))
+ kl_change = tf.reduce_mean(
+ self._mask(utility.diag_normal_kl(old_mean, old_logstd, network.mean, network.logstd),
+ length))
kl_change = tf.Print(kl_change, [kl_change], 'kl change: ')
maybe_increase = tf.cond(
kl_change > 1.3 * self._config.kl_target,
# pylint: disable=g-long-lambda
- lambda: tf.Print(self._penalty.assign(
- self._penalty * 1.5), [0], 'increase penalty '),
+ lambda: tf.Print(self._penalty.assign(self._penalty * 1.5), [0], 'increase penalty '),
float)
maybe_decrease = tf.cond(
kl_change < 0.7 * self._config.kl_target,
# pylint: disable=g-long-lambda
- lambda: tf.Print(self._penalty.assign(
- self._penalty / 1.5), [0], 'decrease penalty '),
+ lambda: tf.Print(self._penalty.assign(self._penalty / 1.5), [0], 'decrease penalty '),
float)
with tf.control_dependencies([maybe_increase, maybe_decrease]):
return tf.summary.merge([
tf.summary.scalar('kl_change', kl_change),
- tf.summary.scalar('penalty', self._penalty)])
+ tf.summary.scalar('penalty', self._penalty)
+ ])
def _mask(self, tensor, length):
"""Set padding elements of a batch of sequences to zero.
diff --git a/examples/pybullet/gym/pybullet_envs/agents/ppo/memory.py b/examples/pybullet/gym/pybullet_envs/agents/ppo/memory.py
index 10e79ef72..eee19ac07 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/ppo/memory.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/ppo/memory.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Memory that stores episodes."""
from __future__ import absolute_import
@@ -43,10 +42,9 @@ class EpisodeMemory(object):
self._scope = var_scope
self._length = tf.Variable(tf.zeros(capacity, tf.int32), False)
self._buffers = [
- tf.Variable(tf.zeros(
- [capacity, max_length] + elem.shape.as_list(),
- elem.dtype), False)
- for elem in template]
+ tf.Variable(tf.zeros([capacity, max_length] + elem.shape.as_list(), elem.dtype), False)
+ for elem in template
+ ]
def length(self, rows=None):
"""Tensor holding the current length of episodes.
@@ -72,13 +70,11 @@ class EpisodeMemory(object):
"""
rows = tf.range(self._capacity) if rows is None else rows
assert rows.shape.ndims == 1
- assert_capacity = tf.assert_less(
- rows, self._capacity,
- message='capacity exceeded')
+ assert_capacity = tf.assert_less(rows, self._capacity, message='capacity exceeded')
with tf.control_dependencies([assert_capacity]):
- assert_max_length = tf.assert_less(
- tf.gather(self._length, rows), self._max_length,
- message='max length exceeded')
+ assert_max_length = tf.assert_less(tf.gather(self._length, rows),
+ self._max_length,
+ message='max length exceeded')
append_ops = []
with tf.control_dependencies([assert_max_length]):
for buffer_, elements in zip(self._buffers, transitions):
@@ -86,8 +82,7 @@ class EpisodeMemory(object):
indices = tf.stack([rows, timestep], 1)
append_ops.append(tf.scatter_nd_update(buffer_, indices, elements))
with tf.control_dependencies(append_ops):
- episode_mask = tf.reduce_sum(tf.one_hot(
- rows, self._capacity, dtype=tf.int32), 0)
+ episode_mask = tf.reduce_sum(tf.one_hot(rows, self._capacity, dtype=tf.int32), 0)
return self._length.assign_add(episode_mask)
def replace(self, episodes, length, rows=None):
@@ -103,11 +98,11 @@ class EpisodeMemory(object):
"""
rows = tf.range(self._capacity) if rows is None else rows
assert rows.shape.ndims == 1
- assert_capacity = tf.assert_less(
- rows, self._capacity, message='capacity exceeded')
+ assert_capacity = tf.assert_less(rows, self._capacity, message='capacity exceeded')
with tf.control_dependencies([assert_capacity]):
- assert_max_length = tf.assert_less_equal(
- length, self._max_length, message='max length exceeded')
+ assert_max_length = tf.assert_less_equal(length,
+ self._max_length,
+ message='max length exceeded')
replace_ops = []
with tf.control_dependencies([assert_max_length]):
for buffer_, elements in zip(self._buffers, episodes):
diff --git a/examples/pybullet/gym/pybullet_envs/agents/ppo/normalize.py b/examples/pybullet/gym/pybullet_envs/agents/ppo/normalize.py
index 6c4170519..4de38fd25 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/ppo/normalize.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/ppo/normalize.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Normalize tensors based on streaming estimates of mean and variance."""
from __future__ import absolute_import
@@ -24,8 +23,7 @@ import tensorflow as tf
class StreamingNormalize(object):
"""Normalize tensors based on streaming estimates of mean and variance."""
- def __init__(
- self, template, center=True, scale=True, clip=10, name='normalize'):
+ def __init__(self, template, center=True, scale=True, clip=10, name='normalize'):
"""Normalize tensors based on streaming estimates of mean and variance.
Centering the value, scaling it by the standard deviation, and clipping
@@ -69,8 +67,7 @@ class StreamingNormalize(object):
if self._scale:
# We cannot scale before seeing at least two samples.
value /= tf.cond(
- self._count > 1, lambda: self._std() + 1e-8,
- lambda: tf.ones_like(self._var_sum))[None]
+ self._count > 1, lambda: self._std() + 1e-8, lambda: tf.ones_like(self._var_sum))[None]
if self._clip:
value = tf.clip_by_value(value, -self._clip, self._clip)
# Remove batch dimension if necessary.
@@ -97,8 +94,7 @@ class StreamingNormalize(object):
mean_delta = tf.reduce_sum(value - self._mean[None, ...], 0)
new_mean = self._mean + mean_delta / step
new_mean = tf.cond(self._count > 1, lambda: new_mean, lambda: value[0])
- var_delta = (
- value - self._mean[None, ...]) * (value - new_mean[None, ...])
+ var_delta = (value - self._mean[None, ...]) * (value - new_mean[None, ...])
new_var_sum = self._var_sum + tf.reduce_sum(var_delta, 0)
with tf.control_dependencies([new_mean, new_var_sum]):
update = self._mean.assign(new_mean), self._var_sum.assign(new_var_sum)
@@ -116,10 +112,8 @@ class StreamingNormalize(object):
Operation.
"""
with tf.name_scope(self._name + '/reset'):
- return tf.group(
- self._count.assign(0),
- self._mean.assign(tf.zeros_like(self._mean)),
- self._var_sum.assign(tf.zeros_like(self._var_sum)))
+ return tf.group(self._count.assign(0), self._mean.assign(tf.zeros_like(self._mean)),
+ self._var_sum.assign(tf.zeros_like(self._var_sum)))
def summary(self):
"""Summary string of mean and standard deviation.
@@ -128,10 +122,8 @@ class StreamingNormalize(object):
Summary tensor.
"""
with tf.name_scope(self._name + '/summary'):
- mean_summary = tf.cond(
- self._count > 0, lambda: self._summary('mean', self._mean), str)
- std_summary = tf.cond(
- self._count > 1, lambda: self._summary('stddev', self._std()), str)
+ mean_summary = tf.cond(self._count > 0, lambda: self._summary('mean', self._mean), str)
+ std_summary = tf.cond(self._count > 1, lambda: self._summary('stddev', self._std()), str)
return tf.summary.merge([mean_summary, std_summary])
def _std(self):
@@ -143,10 +135,8 @@ class StreamingNormalize(object):
Returns:
Tensor of current variance.
"""
- variance = tf.cond(
- self._count > 1,
- lambda: self._var_sum / tf.cast(self._count - 1, tf.float32),
- lambda: tf.ones_like(self._var_sum) * float('nan'))
+ variance = tf.cond(self._count > 1, lambda: self._var_sum / tf.cast(
+ self._count - 1, tf.float32), lambda: tf.ones_like(self._var_sum) * float('nan'))
# The epsilon corrects for small negative variance values caused by
# the algorithm. It was empirically chosen to work with all environments
# tested.
diff --git a/examples/pybullet/gym/pybullet_envs/agents/ppo/utility.py b/examples/pybullet/gym/pybullet_envs/agents/ppo/utility.py
index c46934c49..29d9bf9ea 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/ppo/utility.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/ppo/utility.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Utilities for the PPO algorithm."""
from __future__ import absolute_import
@@ -37,8 +36,7 @@ def reinit_nested_vars(variables, indices=None):
Operation.
"""
if isinstance(variables, (tuple, list)):
- return tf.group(*[
- reinit_nested_vars(variable, indices) for variable in variables])
+ return tf.group(*[reinit_nested_vars(variable, indices) for variable in variables])
if indices is None:
return variables.assign(tf.zeros_like(variables))
else:
@@ -58,9 +56,8 @@ def assign_nested_vars(variables, tensors, indices=None):
Operation.
"""
if isinstance(variables, (tuple, list)):
- return tf.group(*[
- assign_nested_vars(variable, tensor)
- for variable, tensor in zip(variables, tensors)])
+ return tf.group(
+ *[assign_nested_vars(variable, tensor) for variable, tensor in zip(variables, tensors)])
if indices is None:
return variables.assign(tensors)
else:
@@ -71,10 +68,11 @@ def discounted_return(reward, length, discount):
"""Discounted Monte-Carlo returns."""
timestep = tf.range(reward.shape[1].value)
mask = tf.cast(timestep[None, :] < length[:, None], tf.float32)
- return_ = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur + discount * agg,
- tf.transpose(tf.reverse(mask * reward, [1]), [1, 0]),
- tf.zeros_like(reward[:, -1]), 1, False), [1, 0]), [1])
+ return_ = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur + discount * agg,
+ tf.transpose(tf.reverse(mask * reward, [1]), [1, 0]),
+ tf.zeros_like(reward[:, -1]), 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(return_), 'return')
@@ -85,9 +83,8 @@ def fixed_step_return(reward, value, length, discount, window):
return_ = tf.zeros_like(reward)
for _ in range(window):
return_ += reward
- reward = discount * tf.concat(
- [reward[:, 1:], tf.zeros_like(reward[:, -1:])], 1)
- return_ += discount ** window * tf.concat(
+ reward = discount * tf.concat([reward[:, 1:], tf.zeros_like(reward[:, -1:])], 1)
+ return_ += discount**window * tf.concat(
[value[:, window:], tf.zeros_like(value[:, -window:]), 1])
return tf.check_numerics(tf.stop_gradient(mask * return_), 'return')
@@ -99,10 +96,11 @@ def lambda_return(reward, value, length, discount, lambda_):
sequence = mask * reward + discount * value * (1 - lambda_)
discount = mask * discount * lambda_
sequence = tf.stack([sequence, discount], 2)
- return_ = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur[0] + cur[1] * agg,
- tf.transpose(tf.reverse(sequence, [1]), [1, 2, 0]),
- tf.zeros_like(value[:, -1]), 1, False), [1, 0]), [1])
+ return_ = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur[0] + cur[1] * agg,
+ tf.transpose(tf.reverse(sequence, [1]), [1, 2, 0]), tf.zeros_like(value[:, -1]),
+ 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(return_), 'return')
@@ -112,27 +110,26 @@ def lambda_advantage(reward, value, length, discount):
mask = tf.cast(timestep[None, :] < length[:, None], tf.float32)
next_value = tf.concat([value[:, 1:], tf.zeros_like(value[:, -1:])], 1)
delta = reward + discount * next_value - value
- advantage = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur + discount * agg,
- tf.transpose(tf.reverse(mask * delta, [1]), [1, 0]),
- tf.zeros_like(delta[:, -1]), 1, False), [1, 0]), [1])
+ advantage = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur + discount * agg,
+ tf.transpose(tf.reverse(mask * delta, [1]), [1, 0]), tf.zeros_like(delta[:, -1]),
+ 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(advantage), 'advantage')
def diag_normal_kl(mean0, logstd0, mean1, logstd1):
"""Epirical KL divergence of two normals with diagonal covariance."""
logstd0_2, logstd1_2 = 2 * logstd0, 2 * logstd1
- return 0.5 * (
- tf.reduce_sum(tf.exp(logstd0_2 - logstd1_2), -1) +
- tf.reduce_sum((mean1 - mean0) ** 2 / tf.exp(logstd1_2), -1) +
- tf.reduce_sum(logstd1_2, -1) - tf.reduce_sum(logstd0_2, -1) -
- mean0.shape[-1].value)
+ return 0.5 * (tf.reduce_sum(tf.exp(logstd0_2 - logstd1_2), -1) + tf.reduce_sum(
+ (mean1 - mean0)**2 / tf.exp(logstd1_2), -1) + tf.reduce_sum(logstd1_2, -1) -
+ tf.reduce_sum(logstd0_2, -1) - mean0.shape[-1].value)
def diag_normal_logpdf(mean, logstd, loc):
"""Log density of a normal with diagonal covariance."""
constant = -0.5 * math.log(2 * math.pi) - logstd
- value = -0.5 * ((loc - mean) / tf.exp(logstd)) ** 2
+ value = -0.5 * ((loc - mean) / tf.exp(logstd))**2
return tf.reduce_sum(constant + value, -1)
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/__init__.py b/examples/pybullet/gym/pybullet_envs/agents/tools/__init__.py
index 0201de98f..3baf78ae0 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tools for reinforcement learning."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/attr_dict.py b/examples/pybullet/gym/pybullet_envs/agents/tools/attr_dict.py
index 1707486d8..fbb08290f 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/attr_dict.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/attr_dict.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Wrap a dictionary to access keys as attributes."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/batch_env.py b/examples/pybullet/gym/pybullet_envs/agents/tools/batch_env.py
index 946fd7211..ef8b7430e 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/batch_env.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/batch_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Combine multiple environments to step them in batch."""
from __future__ import absolute_import
@@ -83,13 +82,9 @@ class BatchEnv(object):
message = 'Invalid action at index {}: {}'
raise ValueError(message.format(index, action))
if self._blocking:
- transitions = [
- env.step(action)
- for env, action in zip(self._envs, actions)]
+ transitions = [env.step(action) for env, action in zip(self._envs, actions)]
else:
- transitions = [
- env.step(action, blocking=False)
- for env, action in zip(self._envs, actions)]
+ transitions = [env.step(action, blocking=False) for env, action in zip(self._envs, actions)]
transitions = [transition() for transition in transitions]
observs, rewards, dones, infos = zip(*transitions)
observ = np.stack(observs)
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/count_weights.py b/examples/pybullet/gym/pybullet_envs/agents/tools/count_weights.py
index dd0d870f6..279df82a0 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/count_weights.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/count_weights.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Count learnable parameters."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_batch_env.py b/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_batch_env.py
index d4e1644d3..a4709f0a5 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_batch_env.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_batch_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Batch of environments inside the TensorFlow graph."""
from __future__ import absolute_import
@@ -42,18 +41,18 @@ class InGraphBatchEnv(object):
action_shape = self._parse_shape(self._batch_env.action_space)
action_dtype = self._parse_dtype(self._batch_env.action_space)
with tf.variable_scope('env_temporary'):
- self._observ = tf.Variable(
- tf.zeros((len(self._batch_env),) + observ_shape, observ_dtype),
- name='observ', trainable=False)
- self._action = tf.Variable(
- tf.zeros((len(self._batch_env),) + action_shape, action_dtype),
- name='action', trainable=False)
- self._reward = tf.Variable(
- tf.zeros((len(self._batch_env),), tf.float32),
- name='reward', trainable=False)
- self._done = tf.Variable(
- tf.cast(tf.ones((len(self._batch_env),)), tf.bool),
- name='done', trainable=False)
+ self._observ = tf.Variable(tf.zeros((len(self._batch_env),) + observ_shape, observ_dtype),
+ name='observ',
+ trainable=False)
+ self._action = tf.Variable(tf.zeros((len(self._batch_env),) + action_shape, action_dtype),
+ name='action',
+ trainable=False)
+ self._reward = tf.Variable(tf.zeros((len(self._batch_env),), tf.float32),
+ name='reward',
+ trainable=False)
+ self._done = tf.Variable(tf.cast(tf.ones((len(self._batch_env),)), tf.bool),
+ name='done',
+ trainable=False)
def __getattr__(self, name):
"""Forward unimplemented attributes to one of the original environments.
@@ -89,16 +88,13 @@ class InGraphBatchEnv(object):
if action.dtype in (tf.float16, tf.float32, tf.float64):
action = tf.check_numerics(action, 'action')
observ_dtype = self._parse_dtype(self._batch_env.observation_space)
- observ, reward, done = tf.py_func(
- lambda a: self._batch_env.step(a)[:3], [action],
- [observ_dtype, tf.float32, tf.bool], name='step')
+ observ, reward, done = tf.py_func(lambda a: self._batch_env.step(a)[:3], [action],
+ [observ_dtype, tf.float32, tf.bool],
+ name='step')
observ = tf.check_numerics(observ, 'observ')
reward = tf.check_numerics(reward, 'reward')
- return tf.group(
- self._observ.assign(observ),
- self._action.assign(action),
- self._reward.assign(reward),
- self._done.assign(done))
+ return tf.group(self._observ.assign(observ), self._action.assign(action),
+ self._reward.assign(reward), self._done.assign(done))
def reset(self, indices=None):
"""Reset the batch of environments.
@@ -112,15 +108,15 @@ class InGraphBatchEnv(object):
if indices is None:
indices = tf.range(len(self._batch_env))
observ_dtype = self._parse_dtype(self._batch_env.observation_space)
- observ = tf.py_func(
- self._batch_env.reset, [indices], observ_dtype, name='reset')
+ observ = tf.py_func(self._batch_env.reset, [indices], observ_dtype, name='reset')
observ = tf.check_numerics(observ, 'observ')
reward = tf.zeros_like(indices, tf.float32)
done = tf.zeros_like(indices, tf.bool)
with tf.control_dependencies([
tf.scatter_update(self._observ, indices, observ),
tf.scatter_update(self._reward, indices, reward),
- tf.scatter_update(self._done, indices, done)]):
+ tf.scatter_update(self._done, indices, done)
+ ]):
return tf.identity(observ)
@property
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_env.py b/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_env.py
index 33ff31d07..6a71f4516 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_env.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/in_graph_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Put an OpenAI Gym environment into the TensorFlow graph."""
from __future__ import absolute_import
@@ -42,16 +41,15 @@ class InGraphEnv(object):
action_shape = self._parse_shape(self._env.action_space)
action_dtype = self._parse_dtype(self._env.action_space)
with tf.name_scope('environment'):
- self._observ = tf.Variable(
- tf.zeros(observ_shape, observ_dtype), name='observ', trainable=False)
- self._action = tf.Variable(
- tf.zeros(action_shape, action_dtype), name='action', trainable=False)
- self._reward = tf.Variable(
- 0.0, dtype=tf.float32, name='reward', trainable=False)
- self._done = tf.Variable(
- True, dtype=tf.bool, name='done', trainable=False)
- self._step = tf.Variable(
- 0, dtype=tf.int32, name='step', trainable=False)
+ self._observ = tf.Variable(tf.zeros(observ_shape, observ_dtype),
+ name='observ',
+ trainable=False)
+ self._action = tf.Variable(tf.zeros(action_shape, action_dtype),
+ name='action',
+ trainable=False)
+ self._reward = tf.Variable(0.0, dtype=tf.float32, name='reward', trainable=False)
+ self._done = tf.Variable(True, dtype=tf.bool, name='done', trainable=False)
+ self._step = tf.Variable(0, dtype=tf.int32, name='step', trainable=False)
def __getattr__(self, name):
"""Forward unimplemented attributes to the original environment.
@@ -79,17 +77,14 @@ class InGraphEnv(object):
if action.dtype in (tf.float16, tf.float32, tf.float64):
action = tf.check_numerics(action, 'action')
observ_dtype = self._parse_dtype(self._env.observation_space)
- observ, reward, done = tf.py_func(
- lambda a: self._env.step(a)[:3], [action],
- [observ_dtype, tf.float32, tf.bool], name='step')
+ observ, reward, done = tf.py_func(lambda a: self._env.step(a)[:3], [action],
+ [observ_dtype, tf.float32, tf.bool],
+ name='step')
observ = tf.check_numerics(observ, 'observ')
reward = tf.check_numerics(reward, 'reward')
- return tf.group(
- self._observ.assign(observ),
- self._action.assign(action),
- self._reward.assign(reward),
- self._done.assign(done),
- self._step.assign_add(1))
+ return tf.group(self._observ.assign(observ), self._action.assign(action),
+ self._reward.assign(reward), self._done.assign(done),
+ self._step.assign_add(1))
def reset(self):
"""Reset the environment.
@@ -100,10 +95,10 @@ class InGraphEnv(object):
observ_dtype = self._parse_dtype(self._env.observation_space)
observ = tf.py_func(self._env.reset, [], observ_dtype, name='reset')
observ = tf.check_numerics(observ, 'observ')
- with tf.control_dependencies([
- self._observ.assign(observ),
- self._reward.assign(0),
- self._done.assign(False)]):
+ with tf.control_dependencies(
+ [self._observ.assign(observ),
+ self._reward.assign(0),
+ self._done.assign(False)]):
return tf.identity(observ)
@property
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/loop.py b/examples/pybullet/gym/pybullet_envs/agents/tools/loop.py
index b8f118c85..b70798c18 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/loop.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/loop.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Execute operations in a loop and coordinate logging and checkpoints."""
from __future__ import absolute_import
@@ -25,10 +24,8 @@ import tensorflow as tf
from . import streaming_mean
-
_Phase = collections.namedtuple(
- 'Phase',
- 'name, writer, op, batch, steps, feed, report_every, log_every,'
+ 'Phase', 'name, writer, op, batch, steps, feed, report_every, log_every,'
'checkpoint_every')
@@ -56,16 +53,22 @@ class Loop(object):
reset: Tensor indicating to the model to start a new computation.
"""
self._logdir = logdir
- self._step = (
- tf.Variable(0, False, name='global_step') if step is None else step)
+ self._step = (tf.Variable(0, False, name='global_step') if step is None else step)
self._log = tf.placeholder(tf.bool) if log is None else log
self._report = tf.placeholder(tf.bool) if report is None else report
self._reset = tf.placeholder(tf.bool) if reset is None else reset
self._phases = []
- def add_phase(
- self, name, done, score, summary, steps,
- report_every=None, log_every=None, checkpoint_every=None, feed=None):
+ def add_phase(self,
+ name,
+ done,
+ score,
+ summary,
+ steps,
+ report_every=None,
+ log_every=None,
+ checkpoint_every=None,
+ feed=None):
"""Add a phase to the loop protocol.
If the model breaks long computation into multiple steps, the done tensor
@@ -97,13 +100,12 @@ class Loop(object):
if done.shape.ndims is None or score.shape.ndims is None:
raise ValueError("Rank of 'done' and 'score' tensors must be known.")
writer = self._logdir and tf.summary.FileWriter(
- os.path.join(self._logdir, name), tf.get_default_graph(),
- flush_secs=60)
+ os.path.join(self._logdir, name), tf.get_default_graph(), flush_secs=60)
op = self._define_step(done, score, summary)
batch = 1 if score.shape.ndims == 0 else score.shape[0].value
- self._phases.append(_Phase(
- name, writer, op, batch, int(steps), feed, report_every,
- log_every, checkpoint_every))
+ self._phases.append(
+ _Phase(name, writer, op, batch, int(steps), feed, report_every, log_every,
+ checkpoint_every))
def run(self, sess, saver, max_step=None):
"""Run the loop schedule for a specified number of steps.
@@ -133,13 +135,11 @@ class Loop(object):
tf.logging.info(message.format(phase.name, phase_step, global_step))
# Populate book keeping tensors.
phase.feed[self._reset] = (steps_in < steps_made)
- phase.feed[self._log] = (
- phase.writer and
- self._is_every_steps(phase_step, phase.batch, phase.log_every))
- phase.feed[self._report] = (
- self._is_every_steps(phase_step, phase.batch, phase.report_every))
- summary, mean_score, global_step, steps_made = sess.run(
- phase.op, phase.feed)
+ phase.feed[self._log] = (phase.writer and
+ self._is_every_steps(phase_step, phase.batch, phase.log_every))
+ phase.feed[self._report] = (self._is_every_steps(phase_step, phase.batch,
+ phase.report_every))
+ summary, mean_score, global_step, steps_made = sess.run(phase.op, phase.feed)
if self._is_every_steps(phase_step, phase.batch, phase.checkpoint_every):
self._store_checkpoint(sess, saver, global_step)
if self._is_every_steps(phase_step, phase.batch, phase.report_every):
@@ -207,8 +207,7 @@ class Loop(object):
score_mean = streaming_mean.StreamingMean((), tf.float32)
with tf.control_dependencies([done, score, summary]):
done_score = tf.gather(score, tf.where(done)[:, 0])
- submit_score = tf.cond(
- tf.reduce_any(done), lambda: score_mean.submit(done_score), tf.no_op)
+ submit_score = tf.cond(tf.reduce_any(done), lambda: score_mean.submit(done_score), tf.no_op)
with tf.control_dependencies([submit_score]):
mean_score = tf.cond(self._report, score_mean.clear, float)
steps_made = tf.shape(score)[0]
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/mock_algorithm.py b/examples/pybullet/gym/pybullet_envs/agents/tools/mock_algorithm.py
index c60712d8b..c9c55ac60 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/mock_algorithm.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/mock_algorithm.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Mock algorithm for testing reinforcement learning code."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/mock_environment.py b/examples/pybullet/gym/pybullet_envs/agents/tools/mock_environment.py
index 248f515b1..9db14d56c 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/mock_environment.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/mock_environment.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Mock environment for testing reinforcement learning code."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/simulate.py b/examples/pybullet/gym/pybullet_envs/agents/tools/simulate.py
index ebe9a898b..128b83f00 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/simulate.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/simulate.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""In-graph simulation step of a vectorized algorithm with environments."""
from __future__ import absolute_import
@@ -55,7 +54,8 @@ def simulate(batch_env, algo, log=True, reset=False):
reset_ops = [
batch_env.reset(agent_indices),
tf.scatter_update(score, agent_indices, zero_scores),
- tf.scatter_update(length, agent_indices, zero_durations)]
+ tf.scatter_update(length, agent_indices, zero_durations)
+ ]
with tf.control_dependencies(reset_ops):
return algo.begin_episode(agent_indices)
@@ -78,9 +78,8 @@ def simulate(batch_env, algo, log=True, reset=False):
inc_length = length.assign_add(tf.ones(len(batch_env), tf.int32))
with tf.control_dependencies([add_score, inc_length]):
agent_indices = tf.range(len(batch_env))
- experience_summary = algo.experience(
- agent_indices, prevob, batch_env.action, batch_env.reward,
- batch_env.done, batch_env.observ)
+ experience_summary = algo.experience(agent_indices, prevob, batch_env.action,
+ batch_env.reward, batch_env.done, batch_env.observ)
return tf.summary.merge([step_summary, experience_summary])
def _define_end_episode(agent_indices):
@@ -96,8 +95,7 @@ def simulate(batch_env, algo, log=True, reset=False):
"""
assert agent_indices.shape.ndims == 1
submit_score = mean_score.submit(tf.gather(score, agent_indices))
- submit_length = mean_length.submit(
- tf.cast(tf.gather(length, agent_indices), tf.float32))
+ submit_length = mean_length.submit(tf.cast(tf.gather(length, agent_indices), tf.float32))
with tf.control_dependencies([submit_score, submit_length]):
return algo.end_episode(agent_indices)
@@ -107,41 +105,34 @@ def simulate(batch_env, algo, log=True, reset=False):
Returns:
Summary string.
"""
- score_summary = tf.cond(
- tf.logical_and(log, tf.cast(mean_score.count, tf.bool)),
- lambda: tf.summary.scalar('mean_score', mean_score.clear()), str)
- length_summary = tf.cond(
- tf.logical_and(log, tf.cast(mean_length.count, tf.bool)),
- lambda: tf.summary.scalar('mean_length', mean_length.clear()), str)
+ score_summary = tf.cond(tf.logical_and(log, tf.cast(
+ mean_score.count, tf.bool)), lambda: tf.summary.scalar('mean_score', mean_score.clear()),
+ str)
+ length_summary = tf.cond(tf.logical_and(
+ log, tf.cast(mean_length.count,
+ tf.bool)), lambda: tf.summary.scalar('mean_length', mean_length.clear()), str)
return tf.summary.merge([score_summary, length_summary])
with tf.name_scope('simulate'):
log = tf.convert_to_tensor(log)
reset = tf.convert_to_tensor(reset)
with tf.variable_scope('simulate_temporary'):
- score = tf.Variable(
- tf.zeros(len(batch_env), dtype=tf.float32), False, name='score')
- length = tf.Variable(
- tf.zeros(len(batch_env), dtype=tf.int32), False, name='length')
+ score = tf.Variable(tf.zeros(len(batch_env), dtype=tf.float32), False, name='score')
+ length = tf.Variable(tf.zeros(len(batch_env), dtype=tf.int32), False, name='length')
mean_score = streaming_mean.StreamingMean((), tf.float32)
mean_length = streaming_mean.StreamingMean((), tf.float32)
- agent_indices = tf.cond(
- reset,
- lambda: tf.range(len(batch_env)),
- lambda: tf.cast(tf.where(batch_env.done)[:, 0], tf.int32))
- begin_episode = tf.cond(
- tf.cast(tf.shape(agent_indices)[0], tf.bool),
- lambda: _define_begin_episode(agent_indices), str)
+ agent_indices = tf.cond(reset, lambda: tf.range(len(batch_env)), lambda: tf.cast(
+ tf.where(batch_env.done)[:, 0], tf.int32))
+ begin_episode = tf.cond(tf.cast(tf.shape(agent_indices)[0],
+ tf.bool), lambda: _define_begin_episode(agent_indices), str)
with tf.control_dependencies([begin_episode]):
step = _define_step()
with tf.control_dependencies([step]):
agent_indices = tf.cast(tf.where(batch_env.done)[:, 0], tf.int32)
- end_episode = tf.cond(
- tf.cast(tf.shape(agent_indices)[0], tf.bool),
- lambda: _define_end_episode(agent_indices), str)
+ end_episode = tf.cond(tf.cast(tf.shape(agent_indices)[0],
+ tf.bool), lambda: _define_end_episode(agent_indices), str)
with tf.control_dependencies([end_episode]):
- summary = tf.summary.merge([
- _define_summaries(), begin_episode, step, end_episode])
+ summary = tf.summary.merge([_define_summaries(), begin_episode, step, end_episode])
with tf.control_dependencies([summary]):
done, score = tf.identity(batch_env.done), tf.identity(score)
return done, score, summary
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/streaming_mean.py b/examples/pybullet/gym/pybullet_envs/agents/tools/streaming_mean.py
index 3f620fe37..5992eaa6b 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/streaming_mean.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/streaming_mean.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Compute a streaming estimation of the mean of submitted tensors."""
from __future__ import absolute_import
@@ -53,9 +52,8 @@ class StreamingMean(object):
# Add a batch dimension if necessary.
if value.shape.ndims == self._sum.shape.ndims:
value = value[None, ...]
- return tf.group(
- self._sum.assign_add(tf.reduce_sum(value, 0)),
- self._count.assign_add(tf.shape(value)[0]))
+ return tf.group(self._sum.assign_add(tf.reduce_sum(value, 0)),
+ self._count.assign_add(tf.shape(value)[0]))
def clear(self):
"""Return the mean estimate and reset the streaming statistics."""
diff --git a/examples/pybullet/gym/pybullet_envs/agents/tools/wrappers.py b/examples/pybullet/gym/pybullet_envs/agents/tools/wrappers.py
index e7c7543e3..0c3ff47b6 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/tools/wrappers.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/tools/wrappers.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Wrappers for OpenAI Gym environments."""
from __future__ import absolute_import
@@ -149,8 +148,7 @@ class FrameHistory(object):
return self._select_frames()
def _select_frames(self):
- indices = [
- (self._step - index) % self._capacity for index in self._past_indices]
+ indices = [(self._step - index) % self._capacity for index in self._past_indices]
observ = self._buffer[indices]
if self._flatten:
observ = np.reshape(observ, (-1,) + observ.shape[2:])
@@ -191,14 +189,14 @@ class RangeNormalize(object):
def __init__(self, env, observ=None, action=None):
self._env = env
- self._should_normalize_observ = (
- observ is not False and self._is_finite(self._env.observation_space))
+ self._should_normalize_observ = (observ is not False and
+ self._is_finite(self._env.observation_space))
if observ is True and not self._should_normalize_observ:
raise ValueError('Cannot normalize infinite observation range.')
if observ is None and not self._should_normalize_observ:
tf.logging.info('Not normalizing infinite observation range.')
- self._should_normalize_action = (
- action is not False and self._is_finite(self._env.action_space))
+ self._should_normalize_action = (action is not False and
+ self._is_finite(self._env.action_space))
if action is True and not self._should_normalize_action:
raise ValueError('Cannot normalize infinite action range.')
if action is None and not self._should_normalize_action:
@@ -323,8 +321,7 @@ class ExternalProcess(object):
action_space: The cached action space of the environment.
"""
self._conn, conn = multiprocessing.Pipe()
- self._process = multiprocessing.Process(
- target=self._worker, args=(constructor, conn))
+ self._process = multiprocessing.Process(target=self._worker, args=(constructor, conn))
atexit.register(self.close)
self._process.start()
self._observ_space = None
diff --git a/examples/pybullet/gym/pybullet_envs/agents/train_ppo.py b/examples/pybullet/gym/pybullet_envs/agents/train_ppo.py
index e2f3b4114..aa41634a2 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/train_ppo.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/train_ppo.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
r"""Script to train a batch reinforcement learning algorithm.
Command line:
@@ -67,21 +66,25 @@ def _define_loop(graph, logdir, train_steps, eval_steps):
Returns:
Loop object.
"""
- loop = tools.Loop(
- logdir, graph.step, graph.should_log, graph.do_report,
- graph.force_reset)
- loop.add_phase(
- 'train', graph.done, graph.score, graph.summary, train_steps,
- report_every=train_steps,
- log_every=train_steps // 2,
- checkpoint_every=None,
- feed={graph.is_training: True})
- loop.add_phase(
- 'eval', graph.done, graph.score, graph.summary, eval_steps,
- report_every=eval_steps,
- log_every=eval_steps // 2,
- checkpoint_every=10 * eval_steps,
- feed={graph.is_training: False})
+ loop = tools.Loop(logdir, graph.step, graph.should_log, graph.do_report, graph.force_reset)
+ loop.add_phase('train',
+ graph.done,
+ graph.score,
+ graph.summary,
+ train_steps,
+ report_every=train_steps,
+ log_every=train_steps // 2,
+ checkpoint_every=None,
+ feed={graph.is_training: True})
+ loop.add_phase('eval',
+ graph.done,
+ graph.score,
+ graph.summary,
+ eval_steps,
+ report_every=eval_steps,
+ log_every=eval_steps // 2,
+ checkpoint_every=10 * eval_steps,
+ feed={graph.is_training: False})
return loop
@@ -102,18 +105,13 @@ def train(config, env_processes):
if config.update_every % config.num_agents:
tf.logging.warn('Number of agents should divide episodes per update.')
with tf.device('/cpu:0'):
- batch_env = utility.define_batch_env(
- lambda: _create_environment(config),
- config.num_agents, env_processes)
- graph = utility.define_simulation_graph(
- batch_env, config.algorithm, config)
- loop = _define_loop(
- graph, config.logdir,
- config.update_every * config.max_length,
- config.eval_episodes * config.max_length)
- total_steps = int(
- config.steps / config.update_every *
- (config.update_every + config.eval_episodes))
+ batch_env = utility.define_batch_env(lambda: _create_environment(config), config.num_agents,
+ env_processes)
+ graph = utility.define_simulation_graph(batch_env, config.algorithm, config)
+ loop = _define_loop(graph, config.logdir, config.update_every * config.max_length,
+ config.eval_episodes * config.max_length)
+ total_steps = int(config.steps / config.update_every *
+ (config.update_every + config.eval_episodes))
# Exclude episode related variables since the Python state of environments is
# not checkpointed and thus new episodes start after resuming.
saver = utility.define_saver(exclude=(r'.*_temporary/.*',))
@@ -131,8 +129,8 @@ def main(_):
utility.set_up_logging()
if not FLAGS.config:
raise KeyError('You must specify a configuration.')
- logdir = FLAGS.logdir and os.path.expanduser(os.path.join(
- FLAGS.logdir, '{}-{}'.format(FLAGS.timestamp, FLAGS.config)))
+ logdir = FLAGS.logdir and os.path.expanduser(
+ os.path.join(FLAGS.logdir, '{}-{}'.format(FLAGS.timestamp, FLAGS.config)))
try:
config = utility.load_config(logdir)
except IOError:
@@ -144,16 +142,11 @@ def main(_):
if __name__ == '__main__':
FLAGS = tf.app.flags.FLAGS
- tf.app.flags.DEFINE_string(
- 'logdir', None,
- 'Base directory to store logs.')
- tf.app.flags.DEFINE_string(
- 'timestamp', datetime.datetime.now().strftime('%Y%m%dT%H%M%S'),
- 'Sub directory to store logs.')
- tf.app.flags.DEFINE_string(
- 'config', None,
- 'Configuration to execute.')
- tf.app.flags.DEFINE_boolean(
- 'env_processes', True,
- 'Step environments in separate processes to circumvent the GIL.')
+ tf.app.flags.DEFINE_string('logdir', None, 'Base directory to store logs.')
+ tf.app.flags.DEFINE_string('timestamp',
+ datetime.datetime.now().strftime('%Y%m%dT%H%M%S'),
+ 'Sub directory to store logs.')
+ tf.app.flags.DEFINE_string('config', None, 'Configuration to execute.')
+ tf.app.flags.DEFINE_boolean('env_processes', True,
+ 'Step environments in separate processes to circumvent the GIL.')
tf.app.run()
diff --git a/examples/pybullet/gym/pybullet_envs/agents/utility.py b/examples/pybullet/gym/pybullet_envs/agents/utility.py
index 0836a2ed2..1ccebbd10 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/utility.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/utility.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Utilities for using reinforcement learning algorithms."""
from __future__ import absolute_import
@@ -46,8 +45,7 @@ def define_simulation_graph(batch_env, algo_cls, config):
do_report = tf.placeholder(tf.bool, name='do_report')
force_reset = tf.placeholder(tf.bool, name='force_reset')
algo = algo_cls(batch_env, step, is_training, should_log, config)
- done, score, summary = tools.simulate(
- batch_env, algo, should_log, force_reset)
+ done, score, summary = tools.simulate(batch_env, algo, should_log, force_reset)
message = 'Graph contains {} trainable variables.'
tf.logging.info(message.format(tools.count_weights()))
# pylint: enable=unused-variable
@@ -67,9 +65,7 @@ def define_batch_env(constructor, num_agents, env_processes):
"""
with tf.variable_scope('environments'):
if env_processes:
- envs = [
- tools.wrappers.ExternalProcess(constructor)
- for _ in range(num_agents)]
+ envs = [tools.wrappers.ExternalProcess(constructor) for _ in range(num_agents)]
else:
envs = [constructor() for _ in range(num_agents)]
batch_env = tools.BatchEnv(envs, blocking=not env_processes)
@@ -111,9 +107,7 @@ def initialize_variables(sess, saver, logdir, checkpoint=None, resume=None):
ValueError: If resume expected but no log directory specified.
RuntimeError: If no resume expected but a checkpoint was found.
"""
- sess.run(tf.group(
- tf.local_variables_initializer(),
- tf.global_variables_initializer()))
+ sess.run(tf.group(tf.local_variables_initializer(), tf.global_variables_initializer()))
if resume and not (logdir or checkpoint):
raise ValueError('Need to specify logdir to resume a checkpoint.')
if logdir:
@@ -152,9 +146,8 @@ def save_config(config, logdir=None):
with tf.gfile.GFile(config_path, 'w') as file_:
yaml.dump(config, file_, default_flow_style=False)
else:
- message = (
- 'Start a new run without storing summaries and checkpoints since no '
- 'logging directory was specified.')
+ message = ('Start a new run without storing summaries and checkpoints since no '
+ 'logging directory was specified.')
tf.logging.info(message)
return config
@@ -173,9 +166,8 @@ def load_config(logdir):
"""
config_path = logdir and os.path.join(logdir, 'config.yaml')
if not config_path or not tf.gfile.Exists(config_path):
- message = (
- 'Cannot resume an existing run since the logging directory does not '
- 'contain a configuration file.')
+ message = ('Cannot resume an existing run since the logging directory does not '
+ 'contain a configuration file.')
raise IOError(message)
with tf.gfile.FastGFile(config_path, 'r') as file_:
config = yaml.load(file_, Loader=yaml.Loader)
diff --git a/examples/pybullet/gym/pybullet_envs/agents/visualize_ppo.py b/examples/pybullet/gym/pybullet_envs/agents/visualize_ppo.py
index dd27a546d..8524b6311 100644
--- a/examples/pybullet/gym/pybullet_envs/agents/visualize_ppo.py
+++ b/examples/pybullet/gym/pybullet_envs/agents/visualize_ppo.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
r"""Script to render videos of the Proximal Policy Gradient algorithm.
Command line:
@@ -53,8 +52,7 @@ def _create_environment(config, outdir):
setattr(env, 'spec', getattr(env, 'spec', None))
if config.max_length:
env = tools.wrappers.LimitDuration(env, config.max_length)
- env = gym.wrappers.Monitor(
- env, outdir, lambda unused_episode_number: True)
+ env = gym.wrappers.Monitor(env, outdir, lambda unused_episode_number: True)
env = tools.wrappers.RangeNormalize(env)
env = tools.wrappers.ClipAction(env)
env = tools.wrappers.ConvertTo32Bit(env)
@@ -71,20 +69,20 @@ def _define_loop(graph, eval_steps):
Returns:
Loop object.
"""
- loop = tools.Loop(
- None, graph.step, graph.should_log, graph.do_report, graph.force_reset)
- loop.add_phase(
- 'eval', graph.done, graph.score, graph.summary, eval_steps,
- report_every=eval_steps,
- log_every=None,
- checkpoint_every=None,
- feed={graph.is_training: False})
+ loop = tools.Loop(None, graph.step, graph.should_log, graph.do_report, graph.force_reset)
+ loop.add_phase('eval',
+ graph.done,
+ graph.score,
+ graph.summary,
+ eval_steps,
+ report_every=eval_steps,
+ log_every=None,
+ checkpoint_every=None,
+ feed={graph.is_training: False})
return loop
-def visualize(
- logdir, outdir, num_agents, num_episodes, checkpoint=None,
- env_processes=True):
+def visualize(logdir, outdir, num_agents, num_episodes, checkpoint=None, env_processes=True):
"""Recover checkpoint and render videos from it.
Args:
@@ -97,20 +95,16 @@ def visualize(
"""
config = utility.load_config(logdir)
with tf.device('/cpu:0'):
- batch_env = utility.define_batch_env(
- lambda: _create_environment(config, outdir),
- num_agents, env_processes)
- graph = utility.define_simulation_graph(
- batch_env, config.algorithm, config)
+ batch_env = utility.define_batch_env(lambda: _create_environment(config, outdir), num_agents,
+ env_processes)
+ graph = utility.define_simulation_graph(batch_env, config.algorithm, config)
total_steps = num_episodes * config.max_length
loop = _define_loop(graph, total_steps)
- saver = utility.define_saver(
- exclude=(r'.*_temporary/.*', r'global_step'))
+ saver = utility.define_saver(exclude=(r'.*_temporary/.*', r'global_step'))
sess_config = tf.ConfigProto(allow_soft_placement=True)
sess_config.gpu_options.allow_growth = True
with tf.Session(config=sess_config) as sess:
- utility.initialize_variables(
- sess, saver, config.logdir, checkpoint, resume=True)
+ utility.initialize_variables(sess, saver, config.logdir, checkpoint, resume=True)
for unused_score in loop.run(sess, saver, total_steps):
pass
batch_env.close()
@@ -123,29 +117,18 @@ def main(_):
raise KeyError('You must specify logging and outdirs directories.')
FLAGS.logdir = os.path.expanduser(FLAGS.logdir)
FLAGS.outdir = os.path.expanduser(FLAGS.outdir)
- visualize(
- FLAGS.logdir, FLAGS.outdir, FLAGS.num_agents, FLAGS.num_episodes,
- FLAGS.checkpoint, FLAGS.env_processes)
+ visualize(FLAGS.logdir, FLAGS.outdir, FLAGS.num_agents, FLAGS.num_episodes, FLAGS.checkpoint,
+ FLAGS.env_processes)
if __name__ == '__main__':
FLAGS = tf.app.flags.FLAGS
- tf.app.flags.DEFINE_string(
- 'logdir', None,
- 'Directory to the checkpoint of a training run.')
- tf.app.flags.DEFINE_string(
- 'outdir', None,
- 'Local directory for storing the monitoring outdir.')
- tf.app.flags.DEFINE_string(
- 'checkpoint', None,
- 'Checkpoint name to load; defaults to most recent.')
- tf.app.flags.DEFINE_integer(
- 'num_agents', 1,
- 'How many environments to step in parallel.')
- tf.app.flags.DEFINE_integer(
- 'num_episodes', 5,
- 'Minimum number of episodes to render.')
- tf.app.flags.DEFINE_boolean(
- 'env_processes', True,
- 'Step environments in separate processes to circumvent the GIL.')
+ tf.app.flags.DEFINE_string('logdir', None, 'Directory to the checkpoint of a training run.')
+ tf.app.flags.DEFINE_string('outdir', None, 'Local directory for storing the monitoring outdir.')
+ tf.app.flags.DEFINE_string('checkpoint', None,
+ 'Checkpoint name to load; defaults to most recent.')
+ tf.app.flags.DEFINE_integer('num_agents', 1, 'How many environments to step in parallel.')
+ tf.app.flags.DEFINE_integer('num_episodes', 5, 'Minimum number of episodes to render.')
+ tf.app.flags.DEFINE_boolean('env_processes', True,
+ 'Step environments in separate processes to circumvent the GIL.')
tf.app.run()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/__init__.py b/examples/pybullet/gym/pybullet_envs/baselines/__init__.py
index b67603479..e7d027b19 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/__init__.py
@@ -7,4 +7,3 @@ from . import train_kuka_grasping
from . import train_pybullet_cartpole
from . import train_pybullet_racecar
from . import train_pybullet_zed_racecar
-
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_diverse_object_grasping.py b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_diverse_object_grasping.py
index da40d6e94..509e33d1f 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_diverse_object_grasping.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_diverse_object_grasping.py
@@ -6,17 +6,17 @@ import numpy as np
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
from pybullet_envs.bullet.kuka_diverse_object_gym_env import KukaDiverseObjectEnv
from gym import spaces
-
class ContinuousDownwardBiasPolicy(object):
"""Policy which takes continuous actions, and is biased to move down.
"""
+
def __init__(self, height_hack_prob=0.9):
"""Initializes the DownwardBiasPolicy.
@@ -36,25 +36,25 @@ class ContinuousDownwardBiasPolicy(object):
def main():
-
- env = KukaDiverseObjectEnv(renders=True, isDiscrete=False)
- policy = ContinuousDownwardBiasPolicy()
-
- while True:
- obs, done = env.reset(), False
- print("===================================")
- print("obs")
- print(obs)
- episode_rew = 0
- while not done:
- env.render(mode='human')
- act = policy.sample_action(obs, .1)
- print("Action")
- print(act)
- obs, rew, done, _ = env.step([0, 0, 0, 0, 0])
- episode_rew += rew
- print("Episode reward", episode_rew)
+
+ env = KukaDiverseObjectEnv(renders=True, isDiscrete=False)
+ policy = ContinuousDownwardBiasPolicy()
+
+ while True:
+ obs, done = env.reset(), False
+ print("===================================")
+ print("obs")
+ print(obs)
+ episode_rew = 0
+ while not done:
+ env.render(mode='human')
+ act = policy.sample_action(obs, .1)
+ print("Action")
+ print(act)
+ obs, rew, done, _ = env.step([0, 0, 0, 0, 0])
+ episode_rew += rew
+ print("Episode reward", episode_rew)
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_grasping.py b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_grasping.py
index 1a5b7c2a8..422a7a621 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_grasping.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_kuka_grasping.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
@@ -11,22 +11,22 @@ from baselines import deepq
def main():
-
- env = KukaGymEnv(renders=True, isDiscrete=True)
- act = deepq.load("kuka_model.pkl")
- print(act)
- while True:
- obs, done = env.reset(), False
- print("===================================")
- print("obs")
- print(obs)
- episode_rew = 0
- while not done:
- env.render()
- obs, rew, done, _ = env.step(act(obs[None])[0])
- episode_rew += rew
- print("Episode reward", episode_rew)
+
+ env = KukaGymEnv(renders=True, isDiscrete=True)
+ act = deepq.load("kuka_model.pkl")
+ print(act)
+ while True:
+ obs, done = env.reset(), False
+ print("===================================")
+ print("obs")
+ print(obs)
+ episode_rew = 0
+ while not done:
+ env.render()
+ obs, rew, done, _ = env.step(act(obs[None])[0])
+ episode_rew += rew
+ print("Episode reward", episode_rew)
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_cartpole.py b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_cartpole.py
index 0de7dc074..341029dd4 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_cartpole.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_cartpole.py
@@ -2,7 +2,7 @@
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 time
@@ -10,28 +10,29 @@ import time
from baselines import deepq
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
+
def main():
- env = gym.make('CartPoleBulletEnv-v1')
- act = deepq.load("cartpole_model.pkl")
-
- while True:
- obs, done = env.reset(), False
- print("obs")
- print(obs)
- print("type(obs)")
- print(type(obs))
- episode_rew = 0
- while not done:
- env.render()
-
- o = obs[None]
- aa = act(o)
- a = aa[0]
- obs, rew, done, _ = env.step(a)
- episode_rew += rew
- time.sleep(1./240.)
- print("Episode reward", episode_rew)
+ env = gym.make('CartPoleBulletEnv-v1')
+ act = deepq.load("cartpole_model.pkl")
+
+ while True:
+ obs, done = env.reset(), False
+ print("obs")
+ print(obs)
+ print("type(obs)")
+ print(type(obs))
+ episode_rew = 0
+ while not done:
+ env.render()
+
+ o = obs[None]
+ aa = act(o)
+ a = aa[0]
+ obs, rew, done, _ = env.step(a)
+ episode_rew += rew
+ time.sleep(1. / 240.)
+ print("Episode reward", episode_rew)
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_racecar.py b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_racecar.py
index ce3e74358..64936dd9a 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_racecar.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_racecar.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
@@ -11,22 +11,22 @@ from baselines import deepq
def main():
-
- env = RacecarGymEnv(renders=True,isDiscrete=True)
- act = deepq.load("racecar_model.pkl")
- print(act)
- while True:
- obs, done = env.reset(), False
- print("===================================")
- print("obs")
- print(obs)
- episode_rew = 0
- while not done:
- env.render()
- obs, rew, done, _ = env.step(act(obs[None])[0])
- episode_rew += rew
- print("Episode reward", episode_rew)
+
+ env = RacecarGymEnv(renders=True, isDiscrete=True)
+ act = deepq.load("racecar_model.pkl")
+ print(act)
+ while True:
+ obs, done = env.reset(), False
+ print("===================================")
+ print("obs")
+ print(obs)
+ episode_rew = 0
+ while not done:
+ env.render()
+ obs, rew, done, _ = env.step(act(obs[None])[0])
+ episode_rew += rew
+ print("Episode reward", episode_rew)
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_zed_racecar.py b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_zed_racecar.py
index acf6cf0f3..a8bcaa987 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_zed_racecar.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/enjoy_pybullet_zed_racecar.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
@@ -11,22 +11,22 @@ from baselines import deepq
def main():
-
- env = RacecarZEDGymEnv(renders=True)
- act = deepq.load("racecar_zed_model.pkl")
- print(act)
- while True:
- obs, done = env.reset(), False
- print("===================================")
- print("obs")
- print(obs)
- episode_rew = 0
- while not done:
- env.render()
- obs, rew, done, _ = env.step(act(obs[None])[0])
- episode_rew += rew
- print("Episode reward", episode_rew)
+
+ env = RacecarZEDGymEnv(renders=True)
+ act = deepq.load("racecar_zed_model.pkl")
+ print(act)
+ while True:
+ obs, done = env.reset(), False
+ print("===================================")
+ print("obs")
+ print(obs)
+ episode_rew = 0
+ while not done:
+ env.render()
+ obs, rew, done, _ = env.step(act(obs[None])[0])
+ episode_rew += rew
+ print("Episode reward", episode_rew)
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_cam_grasping.py b/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_cam_grasping.py
index 4fd9f5a48..804be59f6 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_cam_grasping.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_cam_grasping.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.kukaCamGymEnv import KukaCamGymEnv
@@ -12,39 +12,34 @@ from baselines import deepq
import datetime
-
def callback(lcl, glb):
- # stop training if reward exceeds 199
- total = sum(lcl['episode_rewards'][-101:-1]) / 100
- totalt = lcl['t']
- #print("totalt")
- #print(totalt)
- is_solved = totalt > 2000 and total >= 10
- return is_solved
+ # stop training if reward exceeds 199
+ total = sum(lcl['episode_rewards'][-101:-1]) / 100
+ totalt = lcl['t']
+ #print("totalt")
+ #print(totalt)
+ is_solved = totalt > 2000 and total >= 10
+ return is_solved
def main():
-
- env = KukaCamGymEnv(renders=False, isDiscrete=True)
- model = deepq.models.cnn_to_mlp(
- convs=[(32, 8, 4), (64, 4, 2), (64, 3, 1)],
- hiddens=[256],
- dueling=False
- )
- act = deepq.learn(
- env,
- q_func=model,
- lr=1e-3,
- max_timesteps=10000000,
- buffer_size=50000,
- exploration_fraction=0.1,
- exploration_final_eps=0.02,
- print_freq=10,
- callback=callback
- )
- print("Saving model to kuka_cam_model.pkl")
- act.save("kuka_cam_model.pkl")
+
+ env = KukaCamGymEnv(renders=False, isDiscrete=True)
+ model = deepq.models.cnn_to_mlp(convs=[(32, 8, 4), (64, 4, 2), (64, 3, 1)],
+ hiddens=[256],
+ dueling=False)
+ act = deepq.learn(env,
+ q_func=model,
+ lr=1e-3,
+ max_timesteps=10000000,
+ buffer_size=50000,
+ exploration_fraction=0.1,
+ exploration_final_eps=0.02,
+ print_freq=10,
+ callback=callback)
+ print("Saving model to kuka_cam_model.pkl")
+ act.save("kuka_cam_model.pkl")
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_grasping.py b/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_grasping.py
index 932a08e77..10225a194 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_grasping.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/train_kuka_grasping.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.kukaGymEnv import KukaGymEnv
@@ -12,35 +12,32 @@ from baselines import deepq
import datetime
-
def callback(lcl, glb):
- # stop training if reward exceeds 199
- total = sum(lcl['episode_rewards'][-101:-1]) / 100
- totalt = lcl['t']
- #print("totalt")
- #print(totalt)
- is_solved = totalt > 2000 and total >= 10
- return is_solved
+ # stop training if reward exceeds 199
+ total = sum(lcl['episode_rewards'][-101:-1]) / 100
+ totalt = lcl['t']
+ #print("totalt")
+ #print(totalt)
+ is_solved = totalt > 2000 and total >= 10
+ return is_solved
def main():
-
- env = KukaGymEnv(renders=False, isDiscrete=True)
- model = deepq.models.mlp([64])
- act = deepq.learn(
- env,
- q_func=model,
- lr=1e-3,
- max_timesteps=10000000,
- buffer_size=50000,
- exploration_fraction=0.1,
- exploration_final_eps=0.02,
- print_freq=10,
- callback=callback
- )
- print("Saving model to kuka_model.pkl")
- act.save("kuka_model.pkl")
+
+ env = KukaGymEnv(renders=False, isDiscrete=True)
+ model = deepq.models.mlp([64])
+ act = deepq.learn(env,
+ q_func=model,
+ lr=1e-3,
+ max_timesteps=10000000,
+ buffer_size=50000,
+ exploration_fraction=0.1,
+ exploration_final_eps=0.02,
+ print_freq=10,
+ callback=callback)
+ print("Saving model to kuka_model.pkl")
+ act.save("kuka_model.pkl")
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_cartpole.py b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_cartpole.py
index f730d9154..9c369a3a2 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_cartpole.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_cartpole.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.cartpole_bullet import CartPoleBulletEnv
@@ -11,29 +11,27 @@ from baselines import deepq
def callback(lcl, glb):
- # stop training if reward exceeds 199
- is_solved = lcl['t'] > 100 and sum(lcl['episode_rewards'][-101:-1]) / 100 >= 199
- return is_solved
+ # stop training if reward exceeds 199
+ is_solved = lcl['t'] > 100 and sum(lcl['episode_rewards'][-101:-1]) / 100 >= 199
+ return is_solved
def main():
-
- env = CartPoleBulletEnv(renders=False)
- model = deepq.models.mlp([64])
- act = deepq.learn(
- env,
- q_func=model,
- lr=1e-3,
- max_timesteps=100000,
- buffer_size=50000,
- exploration_fraction=0.1,
- exploration_final_eps=0.02,
- print_freq=10,
- callback=callback
- )
- print("Saving model to cartpole_model.pkl")
- act.save("cartpole_model.pkl")
+
+ env = CartPoleBulletEnv(renders=False)
+ model = deepq.models.mlp([64])
+ act = deepq.learn(env,
+ q_func=model,
+ lr=1e-3,
+ max_timesteps=100000,
+ buffer_size=50000,
+ exploration_fraction=0.1,
+ exploration_final_eps=0.02,
+ print_freq=10,
+ callback=callback)
+ print("Saving model to cartpole_model.pkl")
+ act.save("cartpole_model.pkl")
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_racecar.py b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_racecar.py
index c17bc11c4..9b06bcfb2 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_racecar.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_racecar.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.racecarGymEnv import RacecarGymEnv
@@ -12,33 +12,30 @@ from baselines import deepq
import datetime
-
def callback(lcl, glb):
- # stop training if reward exceeds 199
- total = sum(lcl['episode_rewards'][-101:-1]) / 100
- totalt = lcl['t']
- is_solved = totalt > 2000 and total >= -50
- return is_solved
+ # stop training if reward exceeds 199
+ total = sum(lcl['episode_rewards'][-101:-1]) / 100
+ totalt = lcl['t']
+ is_solved = totalt > 2000 and total >= -50
+ return is_solved
def main():
-
- env = RacecarGymEnv(renders=False,isDiscrete=True)
- model = deepq.models.mlp([64])
- act = deepq.learn(
- env,
- q_func=model,
- lr=1e-3,
- max_timesteps=10000,
- buffer_size=50000,
- exploration_fraction=0.1,
- exploration_final_eps=0.02,
- print_freq=10,
- callback=callback
- )
- print("Saving model to racecar_model.pkl")
- act.save("racecar_model.pkl")
+
+ env = RacecarGymEnv(renders=False, isDiscrete=True)
+ model = deepq.models.mlp([64])
+ act = deepq.learn(env,
+ q_func=model,
+ lr=1e-3,
+ max_timesteps=10000,
+ buffer_size=50000,
+ exploration_fraction=0.1,
+ exploration_final_eps=0.02,
+ print_freq=10,
+ callback=callback)
+ print("Saving model to racecar_model.pkl")
+ act.save("racecar_model.pkl")
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_zed_racecar.py b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_zed_racecar.py
index 68c5b0046..825197b79 100644
--- a/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_zed_racecar.py
+++ b/examples/pybullet/gym/pybullet_envs/baselines/train_pybullet_zed_racecar.py
@@ -2,7 +2,7 @@
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
from pybullet_envs.bullet.racecarZEDGymEnv import RacecarZEDGymEnv
@@ -12,36 +12,32 @@ from baselines import deepq
import datetime
-
def callback(lcl, glb):
- # stop training if reward exceeds 199
- total = sum(lcl['episode_rewards'][-101:-1]) / 100
- totalt = lcl['t']
- is_solved = totalt > 2000 and total >= -50
- return is_solved
+ # stop training if reward exceeds 199
+ total = sum(lcl['episode_rewards'][-101:-1]) / 100
+ totalt = lcl['t']
+ is_solved = totalt > 2000 and total >= -50
+ return is_solved
+
def main():
-
- env = RacecarZEDGymEnv(renders=False, isDiscrete=True)
- model = deepq.models.cnn_to_mlp(
- convs=[(32, 8, 4), (64, 4, 2), (64, 3, 1)],
- hiddens=[256],
- dueling=False
- )
- act = deepq.learn(
- env,
- q_func=model,
- lr=1e-3,
- max_timesteps=10000,
- buffer_size=50000,
- exploration_fraction=0.1,
- exploration_final_eps=0.02,
- print_freq=10,
- callback=callback
- )
- print("Saving model to racecar_zed_model.pkl")
- act.save("racecar_zed_model.pkl")
+
+ env = RacecarZEDGymEnv(renders=False, isDiscrete=True)
+ model = deepq.models.cnn_to_mlp(convs=[(32, 8, 4), (64, 4, 2), (64, 3, 1)],
+ hiddens=[256],
+ dueling=False)
+ act = deepq.learn(env,
+ q_func=model,
+ lr=1e-3,
+ max_timesteps=10000,
+ buffer_size=50000,
+ exploration_fraction=0.1,
+ exploration_final_eps=0.02,
+ print_freq=10,
+ callback=callback)
+ print("Saving model to racecar_zed_model.pkl")
+ act.save("racecar_zed_model.pkl")
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/bullet_client.py b/examples/pybullet/gym/pybullet_envs/bullet/bullet_client.py
index 13a82eef5..bd248f1d8 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/bullet_client.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/bullet_client.py
@@ -9,9 +9,9 @@ class BulletClient(object):
def __init__(self, connection_mode=pybullet.DIRECT, options=""):
"""Create a simulation and connect to it."""
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
- if(self._client<0):
- print("options=",options)
- self._client = pybullet.connect(connection_mode,options=options)
+ if (self._client < 0):
+ print("options=", options)
+ self._client = pybullet.connect(connection_mode, options=options)
self._shapes = {}
def __del__(self):
@@ -25,5 +25,5 @@ class BulletClient(object):
"""Inject the client id into Bullet functions."""
attribute = getattr(pybullet, name)
if inspect.isbuiltin(attribute):
- attribute = functools.partial(attribute, physicsClientId=self._client)
+ attribute = functools.partial(attribute, physicsClientId=self._client)
return attribute
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py b/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py
index d3e945b1a..f1b594cde 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/cartpole_bullet.py
@@ -2,10 +2,10 @@
Classic cart-pole system implemented by Rich Sutton et al.
Copied from https://webdocs.cs.ualberta.ca/~sutton/book/code/pole.c
"""
-import os, inspect
+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 logging
import math
@@ -21,26 +21,24 @@ from pkg_resources import parse_version
logger = logging.getLogger(__name__)
+
class CartPoleBulletEnv(gym.Env):
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second' : 50
- }
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
def __init__(self, renders=True):
# start the bullet physics server
self._renders = renders
if (renders):
- p.connect(p.GUI)
+ p.connect(p.GUI)
else:
- p.connect(p.DIRECT)
+ p.connect(p.DIRECT)
self.theta_threshold_radians = 12 * 2 * math.pi / 360
- self.x_threshold = 0.4 #2.4
+ self.x_threshold = 0.4 #2.4
high = np.array([
- self.x_threshold * 2,
- np.finfo(np.float32).max,
- self.theta_threshold_radians * 2,
- np.finfo(np.float32).max])
+ self.x_threshold * 2,
+ np.finfo(np.float32).max, self.theta_threshold_radians * 2,
+ np.finfo(np.float32).max
+ ])
self.force_mag = 10
@@ -60,7 +58,7 @@ class CartPoleBulletEnv(gym.Env):
return [seed]
def step(self, action):
- force = self.force_mag if action==1 else -self.force_mag
+ force = self.force_mag if action == 1 else -self.force_mag
p.setJointMotorControl2(self.cartpole, 0, p.TORQUE_CONTROL, force=force)
p.stepSimulation()
@@ -78,16 +76,17 @@ class CartPoleBulletEnv(gym.Env):
return np.array(self.state), reward, done, {}
def reset(self):
-# print("-----------reset simulation---------------")
+ # print("-----------reset simulation---------------")
p.resetSimulation()
- self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cartpole.urdf"),[0,0,0])
+ self.cartpole = p.loadURDF(os.path.join(pybullet_data.getDataPath(), "cartpole.urdf"),
+ [0, 0, 0])
p.changeDynamics(self.cartpole, -1, linearDamping=0, angularDamping=0)
p.changeDynamics(self.cartpole, 0, linearDamping=0, angularDamping=0)
p.changeDynamics(self.cartpole, 1, linearDamping=0, angularDamping=0)
self.timeStep = 0.02
p.setJointMotorControl2(self.cartpole, 1, p.VELOCITY_CONTROL, force=0)
p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, force=0)
- p.setGravity(0,0, -9.8)
+ p.setGravity(0, 0, -9.8)
p.setTimeStep(self.timeStep)
p.setRealTimeSimulation(0)
@@ -100,4 +99,4 @@ class CartPoleBulletEnv(gym.Env):
return np.array(self.state)
def render(self, mode='human', close=False):
- return
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/env_randomizer_base.py b/examples/pybullet/gym/pybullet_envs/bullet/env_randomizer_base.py
index c39f3b888..49dfc5372 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/env_randomizer_base.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/env_randomizer_base.py
@@ -22,4 +22,3 @@ class EnvRandomizerBase(object):
env: The environment to be randomized.
"""
pass
-
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/kuka.py b/examples/pybullet/gym/pybullet_envs/bullet/kuka.py
index f9752760d..b2a4ffb30 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/kuka.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/kuka.py
@@ -1,7 +1,7 @@
-import os, inspect
+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 pybullet as p
import numpy as np
@@ -17,49 +17,60 @@ class Kuka:
self.timeStep = timeStep
self.maxVelocity = .35
self.maxForce = 200.
- self.fingerAForce = 2
+ self.fingerAForce = 2
self.fingerBForce = 2.5
self.fingerTipForce = 2
self.useInverseKinematics = 1
self.useSimulation = 1
- self.useNullSpace =21
+ self.useNullSpace = 21
self.useOrientation = 1
self.kukaEndEffectorIndex = 6
self.kukaGripperIndex = 7
#lower limits for null space
- self.ll=[-.967,-2 ,-2.96,0.19,-2.96,-2.09,-3.05]
+ self.ll = [-.967, -2, -2.96, 0.19, -2.96, -2.09, -3.05]
#upper limits for null space
- self.ul=[.967,2 ,2.96,2.29,2.96,2.09,3.05]
+ self.ul = [.967, 2, 2.96, 2.29, 2.96, 2.09, 3.05]
#joint ranges for null space
- self.jr=[5.8,4,5.8,4,5.8,4,6]
+ self.jr = [5.8, 4, 5.8, 4, 5.8, 4, 6]
#restposes for null space
- self.rp=[0,0,0,0.5*math.pi,0,-math.pi*0.5*0.66,0]
+ self.rp = [0, 0, 0, 0.5 * math.pi, 0, -math.pi * 0.5 * 0.66, 0]
#joint damping coefficents
- self.jd=[0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001,0.00001]
+ self.jd = [
+ 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001, 0.00001,
+ 0.00001, 0.00001, 0.00001, 0.00001
+ ]
self.reset()
-
+
def reset(self):
- objects = p.loadSDF(os.path.join(self.urdfRootPath,"kuka_iiwa/kuka_with_gripper2.sdf"))
+ objects = p.loadSDF(os.path.join(self.urdfRootPath, "kuka_iiwa/kuka_with_gripper2.sdf"))
self.kukaUid = objects[0]
#for i in range (p.getNumJoints(self.kukaUid)):
# print(p.getJointInfo(self.kukaUid,i))
- p.resetBasePositionAndOrientation(self.kukaUid,[-0.100000,0.000000,0.070000],[0.000000,0.000000,0.000000,1.000000])
- self.jointPositions=[ 0.006418, 0.413184, -0.011401, -1.589317, 0.005379, 1.137684, -0.006539, 0.000048, -0.299912, 0.000000, -0.000043, 0.299960, 0.000000, -0.000200 ]
+ p.resetBasePositionAndOrientation(self.kukaUid, [-0.100000, 0.000000, 0.070000],
+ [0.000000, 0.000000, 0.000000, 1.000000])
+ self.jointPositions = [
+ 0.006418, 0.413184, -0.011401, -1.589317, 0.005379, 1.137684, -0.006539, 0.000048,
+ -0.299912, 0.000000, -0.000043, 0.299960, 0.000000, -0.000200
+ ]
self.numJoints = p.getNumJoints(self.kukaUid)
- for jointIndex in range (self.numJoints):
- p.resetJointState(self.kukaUid,jointIndex,self.jointPositions[jointIndex])
- p.setJointMotorControl2(self.kukaUid,jointIndex,p.POSITION_CONTROL,targetPosition=self.jointPositions[jointIndex],force=self.maxForce)
-
- self.trayUid = p.loadURDF(os.path.join(self.urdfRootPath,"tray/tray.urdf"), 0.640000,0.075000,-0.190000,0.000000,0.000000,1.000000,0.000000)
- self.endEffectorPos = [0.537,0.0,0.5]
+ for jointIndex in range(self.numJoints):
+ p.resetJointState(self.kukaUid, jointIndex, self.jointPositions[jointIndex])
+ p.setJointMotorControl2(self.kukaUid,
+ jointIndex,
+ p.POSITION_CONTROL,
+ targetPosition=self.jointPositions[jointIndex],
+ force=self.maxForce)
+
+ self.trayUid = p.loadURDF(os.path.join(self.urdfRootPath, "tray/tray.urdf"), 0.640000,
+ 0.075000, -0.190000, 0.000000, 0.000000, 1.000000, 0.000000)
+ self.endEffectorPos = [0.537, 0.0, 0.5]
self.endEffectorAngle = 0
-
-
+
self.motorNames = []
self.motorIndices = []
-
- for i in range (self.numJoints):
- jointInfo = p.getJointInfo(self.kukaUid,i)
+
+ for i in range(self.numJoints):
+ jointInfo = p.getJointInfo(self.kukaUid, i)
qIndex = jointInfo[3]
if qIndex > -1:
#print("motorname")
@@ -70,98 +81,136 @@ class Kuka:
def getActionDimension(self):
if (self.useInverseKinematics):
return len(self.motorIndices)
- return 6 #position x,y,z and roll/pitch/yaw euler angles of end effector
+ return 6 #position x,y,z and roll/pitch/yaw euler angles of end effector
def getObservationDimension(self):
return len(self.getObservation())
def getObservation(self):
observation = []
- state = p.getLinkState(self.kukaUid,self.kukaGripperIndex)
+ state = p.getLinkState(self.kukaUid, self.kukaGripperIndex)
pos = state[0]
orn = state[1]
euler = p.getEulerFromQuaternion(orn)
-
+
observation.extend(list(pos))
observation.extend(list(euler))
-
+
return observation
def applyAction(self, motorCommands):
-
+
#print ("self.numJoints")
#print (self.numJoints)
if (self.useInverseKinematics):
-
+
dx = motorCommands[0]
dy = motorCommands[1]
dz = motorCommands[2]
da = motorCommands[3]
fingerAngle = motorCommands[4]
-
- state = p.getLinkState(self.kukaUid,self.kukaEndEffectorIndex)
+
+ state = p.getLinkState(self.kukaUid, self.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
#print("pos[2] (getLinkState(kukaEndEffectorIndex)")
#print(actualEndEffectorPos[2])
-
-
-
- self.endEffectorPos[0] = self.endEffectorPos[0]+dx
- if (self.endEffectorPos[0]>0.65):
- self.endEffectorPos[0]=0.65
- if (self.endEffectorPos[0]<0.50):
- self.endEffectorPos[0]=0.50
- self.endEffectorPos[1] = self.endEffectorPos[1]+dy
- if (self.endEffectorPos[1]<-0.17):
- self.endEffectorPos[1]=-0.17
- if (self.endEffectorPos[1]>0.22):
- self.endEffectorPos[1]=0.22
-
+
+ self.endEffectorPos[0] = self.endEffectorPos[0] + dx
+ if (self.endEffectorPos[0] > 0.65):
+ self.endEffectorPos[0] = 0.65
+ if (self.endEffectorPos[0] < 0.50):
+ self.endEffectorPos[0] = 0.50
+ self.endEffectorPos[1] = self.endEffectorPos[1] + dy
+ if (self.endEffectorPos[1] < -0.17):
+ self.endEffectorPos[1] = -0.17
+ if (self.endEffectorPos[1] > 0.22):
+ self.endEffectorPos[1] = 0.22
+
#print ("self.endEffectorPos[2]")
#print (self.endEffectorPos[2])
#print("actualEndEffectorPos[2]")
#print(actualEndEffectorPos[2])
#if (dz<0 or actualEndEffectorPos[2]<0.5):
- self.endEffectorPos[2] = self.endEffectorPos[2]+dz
-
-
+ self.endEffectorPos[2] = self.endEffectorPos[2] + dz
+
self.endEffectorAngle = self.endEffectorAngle + da
pos = self.endEffectorPos
- orn = p.getQuaternionFromEuler([0,-math.pi,0]) # -math.pi,yaw])
- if (self.useNullSpace==1):
- if (self.useOrientation==1):
- jointPoses = p.calculateInverseKinematics(self.kukaUid,self.kukaEndEffectorIndex,pos,orn,self.ll,self.ul,self.jr,self.rp)
+ orn = p.getQuaternionFromEuler([0, -math.pi, 0]) # -math.pi,yaw])
+ if (self.useNullSpace == 1):
+ if (self.useOrientation == 1):
+ jointPoses = p.calculateInverseKinematics(self.kukaUid, self.kukaEndEffectorIndex, pos,
+ orn, self.ll, self.ul, self.jr, self.rp)
else:
- jointPoses = p.calculateInverseKinematics(self.kukaUid,self.kukaEndEffectorIndex,pos,lowerLimits=self.ll, upperLimits=self.ul, jointRanges=self.jr, restPoses=self.rp)
+ jointPoses = p.calculateInverseKinematics(self.kukaUid,
+ self.kukaEndEffectorIndex,
+ pos,
+ lowerLimits=self.ll,
+ upperLimits=self.ul,
+ jointRanges=self.jr,
+ restPoses=self.rp)
else:
- if (self.useOrientation==1):
- jointPoses = p.calculateInverseKinematics(self.kukaUid,self.kukaEndEffectorIndex,pos,orn,jointDamping=self.jd)
+ if (self.useOrientation == 1):
+ jointPoses = p.calculateInverseKinematics(self.kukaUid,
+ self.kukaEndEffectorIndex,
+ pos,
+ orn,
+ jointDamping=self.jd)
else:
- jointPoses = p.calculateInverseKinematics(self.kukaUid,self.kukaEndEffectorIndex,pos)
-
+ jointPoses = p.calculateInverseKinematics(self.kukaUid, self.kukaEndEffectorIndex, pos)
+
#print("jointPoses")
#print(jointPoses)
#print("self.kukaEndEffectorIndex")
#print(self.kukaEndEffectorIndex)
if (self.useSimulation):
- for i in range (self.kukaEndEffectorIndex+1):
+ for i in range(self.kukaEndEffectorIndex + 1):
#print(i)
- p.setJointMotorControl2(bodyUniqueId=self.kukaUid,jointIndex=i,controlMode=p.POSITION_CONTROL,targetPosition=jointPoses[i],targetVelocity=0,force=self.maxForce,maxVelocity=self.maxVelocity, positionGain=0.3,velocityGain=1)
+ p.setJointMotorControl2(bodyUniqueId=self.kukaUid,
+ jointIndex=i,
+ controlMode=p.POSITION_CONTROL,
+ targetPosition=jointPoses[i],
+ targetVelocity=0,
+ force=self.maxForce,
+ maxVelocity=self.maxVelocity,
+ positionGain=0.3,
+ velocityGain=1)
else:
#reset the joint state (ignoring all dynamics, not recommended to use during simulation)
- for i in range (self.numJoints):
- p.resetJointState(self.kukaUid,i,jointPoses[i])
+ for i in range(self.numJoints):
+ p.resetJointState(self.kukaUid, i, jointPoses[i])
#fingers
- p.setJointMotorControl2(self.kukaUid,7,p.POSITION_CONTROL,targetPosition=self.endEffectorAngle,force=self.maxForce)
- p.setJointMotorControl2(self.kukaUid,8,p.POSITION_CONTROL,targetPosition=-fingerAngle,force=self.fingerAForce)
- p.setJointMotorControl2(self.kukaUid,11,p.POSITION_CONTROL,targetPosition=fingerAngle,force=self.fingerBForce)
-
- p.setJointMotorControl2(self.kukaUid,10,p.POSITION_CONTROL,targetPosition=0,force=self.fingerTipForce)
- p.setJointMotorControl2(self.kukaUid,13,p.POSITION_CONTROL,targetPosition=0,force=self.fingerTipForce)
-
-
+ p.setJointMotorControl2(self.kukaUid,
+ 7,
+ p.POSITION_CONTROL,
+ targetPosition=self.endEffectorAngle,
+ force=self.maxForce)
+ p.setJointMotorControl2(self.kukaUid,
+ 8,
+ p.POSITION_CONTROL,
+ targetPosition=-fingerAngle,
+ force=self.fingerAForce)
+ p.setJointMotorControl2(self.kukaUid,
+ 11,
+ p.POSITION_CONTROL,
+ targetPosition=fingerAngle,
+ force=self.fingerBForce)
+
+ p.setJointMotorControl2(self.kukaUid,
+ 10,
+ p.POSITION_CONTROL,
+ targetPosition=0,
+ force=self.fingerTipForce)
+ p.setJointMotorControl2(self.kukaUid,
+ 13,
+ p.POSITION_CONTROL,
+ targetPosition=0,
+ force=self.fingerTipForce)
+
else:
- for action in range (len(motorCommands)):
+ for action in range(len(motorCommands)):
motor = self.motorIndices[action]
- p.setJointMotorControl2(self.kukaUid,motor,p.POSITION_CONTROL,targetPosition=motorCommands[action],force=self.maxForce)
-
+ p.setJointMotorControl2(self.kukaUid,
+ motor,
+ p.POSITION_CONTROL,
+ targetPosition=motorCommands[action],
+ force=self.maxForce)
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/kukaCamGymEnv.py b/examples/pybullet/gym/pybullet_envs/bullet/kukaCamGymEnv.py
index d7c0cac51..235bfa42d 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/kukaCamGymEnv.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/kukaCamGymEnv.py
@@ -1,8 +1,7 @@
-import os, inspect
+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 math
import gym
@@ -21,11 +20,9 @@ maxSteps = 1000
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
+
class KukaCamGymEnv(gym.Env):
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second' : 50
- }
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
def __init__(self,
urdfRoot=pybullet_data.getDataPath(),
@@ -33,7 +30,7 @@ class KukaCamGymEnv(gym.Env):
isEnableSelfCollision=True,
renders=False,
isDiscrete=False):
- self._timeStep = 1./240.
+ self._timeStep = 1. / 240.
self._urdfRoot = urdfRoot
self._actionRepeat = actionRepeat
self._isEnableSelfCollision = isEnableSelfCollision
@@ -42,14 +39,14 @@ class KukaCamGymEnv(gym.Env):
self._renders = renders
self._width = 341
self._height = 256
- self._isDiscrete=isDiscrete
+ self._isDiscrete = isDiscrete
self.terminated = 0
self._p = p
if self._renders:
cid = p.connect(p.SHARED_MEMORY)
- if (cid<0):
- p.connect(p.GUI)
- p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
+ if (cid < 0):
+ p.connect(p.GUI)
+ p.resetDebugVisualizerCamera(1.3, 180, -41, [0.52, -0.2, -0.33])
else:
p.connect(p.DIRECT)
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
@@ -67,7 +64,10 @@ class KukaCamGymEnv(gym.Env):
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
- self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
+ self.observation_space = spaces.Box(low=0,
+ high=255,
+ shape=(self._height, self._width, 4),
+ dtype=np.uint8)
self.viewer = None
def reset(self):
@@ -75,17 +75,19 @@ class KukaCamGymEnv(gym.Env):
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
- p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
+ p.loadURDF(os.path.join(self._urdfRoot, "plane.urdf"), [0, 0, -1])
- p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
+ p.loadURDF(os.path.join(self._urdfRoot, "table/table.urdf"), 0.5000000, 0.00000, -.820000,
+ 0.000000, 0.000000, 0.0, 1.0)
- xpos = 0.5 +0.2*random.random()
- ypos = 0 +0.25*random.random()
- ang = 3.1415925438*random.random()
- orn = p.getQuaternionFromEuler([0,0,ang])
- self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
+ xpos = 0.5 + 0.2 * random.random()
+ ypos = 0 + 0.25 * random.random()
+ ang = 3.1415925438 * random.random()
+ orn = p.getQuaternionFromEuler([0, 0, ang])
+ self.blockUid = p.loadURDF(os.path.join(self._urdfRoot, "block.urdf"), xpos, ypos, -0.1,
+ orn[0], orn[1], orn[2], orn[3])
- p.setGravity(0,0,-10)
+ p.setGravity(0, 0, -10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
p.stepSimulation()
@@ -101,49 +103,59 @@ class KukaCamGymEnv(gym.Env):
def getExtendedObservation(self):
- #camEyePos = [0.03,0.236,0.54]
- #distance = 1.06
- #pitch=-56
- #yaw = 258
- #roll=0
- #upAxisIndex = 2
- #camInfo = p.getDebugVisualizerCamera()
- #print("width,height")
- #print(camInfo[0])
- #print(camInfo[1])
- #print("viewMatrix")
- #print(camInfo[2])
- #print("projectionMatrix")
- #print(camInfo[3])
- #viewMat = camInfo[2]
- #viewMat = p.computeViewMatrixFromYawPitchRoll(camEyePos,distance,yaw, pitch,roll,upAxisIndex)
- viewMat = [-0.5120397806167603, 0.7171027660369873, -0.47284144163131714, 0.0, -0.8589617609977722, -0.42747554183006287, 0.28186774253845215, 0.0, 0.0, 0.5504802465438843, 0.8348482847213745, 0.0, 0.1925382763147354, -0.24935829639434814, -0.4401884973049164, 1.0]
- #projMatrix = camInfo[3]#[0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
- projMatrix = [0.75, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
-
- img_arr = p.getCameraImage(width=self._width,height=self._height,viewMatrix=viewMat,projectionMatrix=projMatrix)
- rgb=img_arr[2]
- np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
- self._observation = np_img_arr
- return self._observation
+ #camEyePos = [0.03,0.236,0.54]
+ #distance = 1.06
+ #pitch=-56
+ #yaw = 258
+ #roll=0
+ #upAxisIndex = 2
+ #camInfo = p.getDebugVisualizerCamera()
+ #print("width,height")
+ #print(camInfo[0])
+ #print(camInfo[1])
+ #print("viewMatrix")
+ #print(camInfo[2])
+ #print("projectionMatrix")
+ #print(camInfo[3])
+ #viewMat = camInfo[2]
+ #viewMat = p.computeViewMatrixFromYawPitchRoll(camEyePos,distance,yaw, pitch,roll,upAxisIndex)
+ viewMat = [
+ -0.5120397806167603, 0.7171027660369873, -0.47284144163131714, 0.0, -0.8589617609977722,
+ -0.42747554183006287, 0.28186774253845215, 0.0, 0.0, 0.5504802465438843,
+ 0.8348482847213745, 0.0, 0.1925382763147354, -0.24935829639434814, -0.4401884973049164, 1.0
+ ]
+ #projMatrix = camInfo[3]#[0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
+ projMatrix = [
+ 0.75, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0,
+ -0.02000020071864128, 0.0
+ ]
+
+ img_arr = p.getCameraImage(width=self._width,
+ height=self._height,
+ viewMatrix=viewMat,
+ projectionMatrix=projMatrix)
+ rgb = img_arr[2]
+ np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
+ self._observation = np_img_arr
+ return self._observation
def step(self, action):
if (self._isDiscrete):
dv = 0.01
- dx = [0,-dv,dv,0,0,0,0][action]
- dy = [0,0,0,-dv,dv,0,0][action]
- da = [0,0,0,0,0,-0.1,0.1][action]
+ dx = [0, -dv, dv, 0, 0, 0, 0][action]
+ dy = [0, 0, 0, -dv, dv, 0, 0][action]
+ da = [0, 0, 0, 0, 0, -0.1, 0.1][action]
f = 0.3
- realAction = [dx,dy,-0.002,da,f]
+ realAction = [dx, dy, -0.002, da, f]
else:
dv = 0.01
dx = action[0] * dv
dy = action[1] * dv
da = action[2] * 0.1
f = 0.3
- realAction = [dx,dy,-0.002,da,f]
+ realAction = [dx, dy, -0.002, da, f]
- return self.step2( realAction)
+ return self.step2(realAction)
def step2(self, action):
for i in range(self._actionRepeat):
@@ -156,7 +168,7 @@ class KukaCamGymEnv(gym.Env):
self._observation = self.getExtendedObservation()
if self._renders:
- time.sleep(self._timeStep)
+ time.sleep(self._timeStep)
#print("self._envStepCounter")
#print(self._envStepCounter)
@@ -170,66 +182,67 @@ class KukaCamGymEnv(gym.Env):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
- base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
- view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
- cameraTargetPosition=base_pos,
- distance=self._cam_dist,
- yaw=self._cam_yaw,
- pitch=self._cam_pitch,
- roll=0,
- upAxisIndex=2)
- proj_matrix = self._p.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._p.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ base_pos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ view_matrix = self._p.computeViewMatrixFromYawPitchRoll(cameraTargetPosition=base_pos,
+ distance=self._cam_dist,
+ yaw=self._cam_yaw,
+ pitch=self._cam_pitch,
+ roll=0,
+ upAxisIndex=2)
+ proj_matrix = self._p.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) / RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _, _) = self._p.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3]
return rgb_array
def _termination(self):
#print (self._kuka.endEffectorPos[2])
- state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
+ state = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
#print("self._envStepCounter")
#print(self._envStepCounter)
- if (self.terminated or self._envStepCounter>maxSteps):
+ if (self.terminated or self._envStepCounter > maxSteps):
self._observation = self.getExtendedObservation()
return True
maxDist = 0.005
- closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid,maxDist)
+ closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid, maxDist)
- if (len(closestPoints)):#(actualEndEffectorPos[2] <= -0.43):
+ if (len(closestPoints)): #(actualEndEffectorPos[2] <= -0.43):
self.terminated = 1
#print("closing gripper, attempting grasp")
#start grasp and terminate
fingerAngle = 0.3
- for i in range (100):
- graspAction = [0,0,0.0001,0,fingerAngle]
+ for i in range(100):
+ graspAction = [0, 0, 0.0001, 0, fingerAngle]
self._kuka.applyAction(graspAction)
p.stepSimulation()
- fingerAngle = fingerAngle-(0.3/100.)
- if (fingerAngle<0):
- fingerAngle=0
+ fingerAngle = fingerAngle - (0.3 / 100.)
+ if (fingerAngle < 0):
+ fingerAngle = 0
- for i in range (1000):
- graspAction = [0,0,0.001,0,fingerAngle]
+ for i in range(1000):
+ graspAction = [0, 0, 0.001, 0, fingerAngle]
self._kuka.applyAction(graspAction)
p.stepSimulation()
- blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
+ blockPos, blockOrn = p.getBasePositionAndOrientation(self.blockUid)
if (blockPos[2] > 0.23):
#print("BLOCKPOS!")
#print(blockPos[2])
break
- state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
+ state = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
- if (actualEndEffectorPos[2]>0.5):
+ if (actualEndEffectorPos[2] > 0.5):
break
-
self._observation = self.getExtendedObservation()
return True
return False
@@ -237,20 +250,21 @@ class KukaCamGymEnv(gym.Env):
def _reward(self):
#rewards is height of target object
- blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
- closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
+ blockPos, blockOrn = p.getBasePositionAndOrientation(self.blockUid)
+ closestPoints = p.getClosestPoints(self.blockUid, self._kuka.kukaUid, 1000, -1,
+ self._kuka.kukaEndEffectorIndex)
reward = -1000
numPt = len(closestPoints)
#print(numPt)
- if (numPt>0):
+ if (numPt > 0):
#print("reward:")
- reward = -closestPoints[0][8]*10
- if (blockPos[2] >0.2):
+ reward = -closestPoints[0][8] * 10
+ if (blockPos[2] > 0.2):
#print("grasped a block!!!")
#print("self._envStepCounter")
#print(self._envStepCounter)
- reward = reward+1000
+ reward = reward + 1000
#print("reward")
#print(reward)
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/kukaGymEnv.py b/examples/pybullet/gym/pybullet_envs/bullet/kukaGymEnv.py
index e1310c861..f47a0dd13 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/kukaGymEnv.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/kukaGymEnv.py
@@ -1,7 +1,7 @@
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
-print ("current_dir=" + currentdir)
-os.sys.path.insert(0,currentdir)
+print("current_dir=" + currentdir)
+os.sys.path.insert(0, currentdir)
import math
import gym
@@ -20,11 +20,9 @@ largeValObservation = 100
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
+
class KukaGymEnv(gym.Env):
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second' : 50
- }
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
def __init__(self,
urdfRoot=pybullet_data.getDataPath(),
@@ -32,10 +30,10 @@ class KukaGymEnv(gym.Env):
isEnableSelfCollision=True,
renders=False,
isDiscrete=False,
- maxSteps = 1000):
+ maxSteps=1000):
#print("KukaGymEnv __init__")
self._isDiscrete = isDiscrete
- self._timeStep = 1./240.
+ self._timeStep = 1. / 240.
self._urdfRoot = urdfRoot
self._actionRepeat = actionRepeat
self._isEnableSelfCollision = isEnableSelfCollision
@@ -51,9 +49,9 @@ class KukaGymEnv(gym.Env):
self._p = p
if self._renders:
cid = p.connect(p.SHARED_MEMORY)
- if (cid<0):
- cid = p.connect(p.GUI)
- p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
+ if (cid < 0):
+ cid = p.connect(p.GUI)
+ p.resetDebugVisualizerCamera(1.3, 180, -41, [0.52, -0.2, -0.33])
else:
p.connect(p.DIRECT)
#timinglog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "kukaTimings.json")
@@ -67,10 +65,10 @@ class KukaGymEnv(gym.Env):
if (self._isDiscrete):
self.action_space = spaces.Discrete(7)
else:
- action_dim = 3
- self._action_bound = 1
- action_high = np.array([self._action_bound] * action_dim)
- self.action_space = spaces.Box(-action_high, action_high)
+ action_dim = 3
+ self._action_bound = 1
+ action_high = np.array([self._action_bound] * action_dim)
+ self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(-observation_high, observation_high)
self.viewer = None
@@ -80,17 +78,19 @@ class KukaGymEnv(gym.Env):
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
- p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
+ p.loadURDF(os.path.join(self._urdfRoot, "plane.urdf"), [0, 0, -1])
- p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
+ p.loadURDF(os.path.join(self._urdfRoot, "table/table.urdf"), 0.5000000, 0.00000, -.820000,
+ 0.000000, 0.000000, 0.0, 1.0)
- xpos = 0.55 +0.12*random.random()
- ypos = 0 +0.2*random.random()
- ang = 3.14*0.5+3.1415925438*random.random()
- orn = p.getQuaternionFromEuler([0,0,ang])
- self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.15,orn[0],orn[1],orn[2],orn[3])
+ xpos = 0.55 + 0.12 * random.random()
+ ypos = 0 + 0.2 * random.random()
+ ang = 3.14 * 0.5 + 3.1415925438 * random.random()
+ orn = p.getQuaternionFromEuler([0, 0, ang])
+ self.blockUid = p.loadURDF(os.path.join(self._urdfRoot, "block.urdf"), xpos, ypos, -0.15,
+ orn[0], orn[1], orn[2], orn[3])
- p.setGravity(0,0,-10)
+ p.setGravity(0, 0, -10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
p.stepSimulation()
@@ -105,47 +105,48 @@ class KukaGymEnv(gym.Env):
return [seed]
def getExtendedObservation(self):
- self._observation = self._kuka.getObservation()
- gripperState = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaGripperIndex)
- gripperPos = gripperState[0]
- gripperOrn = gripperState[1]
- blockPos,blockOrn = p.getBasePositionAndOrientation(self.blockUid)
-
- invGripperPos,invGripperOrn = p.invertTransform(gripperPos,gripperOrn)
- gripperMat = p.getMatrixFromQuaternion(gripperOrn)
- dir0 = [gripperMat[0],gripperMat[3],gripperMat[6]]
- dir1 = [gripperMat[1],gripperMat[4],gripperMat[7]]
- dir2 = [gripperMat[2],gripperMat[5],gripperMat[8]]
-
- gripperEul = p.getEulerFromQuaternion(gripperOrn)
- #print("gripperEul")
- #print(gripperEul)
- blockPosInGripper,blockOrnInGripper = p.multiplyTransforms(invGripperPos,invGripperOrn,blockPos,blockOrn)
- projectedBlockPos2D =[blockPosInGripper[0],blockPosInGripper[1]]
- blockEulerInGripper = p.getEulerFromQuaternion(blockOrnInGripper)
- #print("projectedBlockPos2D")
- #print(projectedBlockPos2D)
- #print("blockEulerInGripper")
- #print(blockEulerInGripper)
-
- #we return the relative x,y position and euler angle of block in gripper space
- blockInGripperPosXYEulZ =[blockPosInGripper[0],blockPosInGripper[1],blockEulerInGripper[2]]
-
- #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir0[0],gripperPos[1]+dir0[1],gripperPos[2]+dir0[2]],[1,0,0],lifeTime=1)
- #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir1[0],gripperPos[1]+dir1[1],gripperPos[2]+dir1[2]],[0,1,0],lifeTime=1)
- #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir2[0],gripperPos[1]+dir2[1],gripperPos[2]+dir2[2]],[0,0,1],lifeTime=1)
-
- self._observation.extend(list(blockInGripperPosXYEulZ))
- return self._observation
+ self._observation = self._kuka.getObservation()
+ gripperState = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaGripperIndex)
+ gripperPos = gripperState[0]
+ gripperOrn = gripperState[1]
+ blockPos, blockOrn = p.getBasePositionAndOrientation(self.blockUid)
+
+ invGripperPos, invGripperOrn = p.invertTransform(gripperPos, gripperOrn)
+ gripperMat = p.getMatrixFromQuaternion(gripperOrn)
+ dir0 = [gripperMat[0], gripperMat[3], gripperMat[6]]
+ dir1 = [gripperMat[1], gripperMat[4], gripperMat[7]]
+ dir2 = [gripperMat[2], gripperMat[5], gripperMat[8]]
+
+ gripperEul = p.getEulerFromQuaternion(gripperOrn)
+ #print("gripperEul")
+ #print(gripperEul)
+ blockPosInGripper, blockOrnInGripper = p.multiplyTransforms(invGripperPos, invGripperOrn,
+ blockPos, blockOrn)
+ projectedBlockPos2D = [blockPosInGripper[0], blockPosInGripper[1]]
+ blockEulerInGripper = p.getEulerFromQuaternion(blockOrnInGripper)
+ #print("projectedBlockPos2D")
+ #print(projectedBlockPos2D)
+ #print("blockEulerInGripper")
+ #print(blockEulerInGripper)
+
+ #we return the relative x,y position and euler angle of block in gripper space
+ blockInGripperPosXYEulZ = [blockPosInGripper[0], blockPosInGripper[1], blockEulerInGripper[2]]
+
+ #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir0[0],gripperPos[1]+dir0[1],gripperPos[2]+dir0[2]],[1,0,0],lifeTime=1)
+ #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir1[0],gripperPos[1]+dir1[1],gripperPos[2]+dir1[2]],[0,1,0],lifeTime=1)
+ #p.addUserDebugLine(gripperPos,[gripperPos[0]+dir2[0],gripperPos[1]+dir2[1],gripperPos[2]+dir2[2]],[0,0,1],lifeTime=1)
+
+ self._observation.extend(list(blockInGripperPosXYEulZ))
+ return self._observation
def step(self, action):
if (self._isDiscrete):
dv = 0.005
- dx = [0,-dv,dv,0,0,0,0][action]
- dy = [0,0,0,-dv,dv,0,0][action]
- da = [0,0,0,0,0,-0.05,0.05][action]
+ dx = [0, -dv, dv, 0, 0, 0, 0][action]
+ dy = [0, 0, 0, -dv, dv, 0, 0][action]
+ da = [0, 0, 0, 0, 0, -0.05, 0.05][action]
f = 0.3
- realAction = [dx,dy,-0.002,da,f]
+ realAction = [dx, dy, -0.002, da, f]
else:
#print("action[0]=", str(action[0]))
dv = 0.005
@@ -153,8 +154,8 @@ class KukaGymEnv(gym.Env):
dy = action[1] * dv
da = action[2] * 0.05
f = 0.3
- realAction = [dx,dy,-0.002,da,f]
- return self.step2( realAction)
+ realAction = [dx, dy, -0.002, da, f]
+ return self.step2(realAction)
def step2(self, action):
for i in range(self._actionRepeat):
@@ -171,11 +172,13 @@ class KukaGymEnv(gym.Env):
#print(self._envStepCounter)
done = self._termination()
- npaction = np.array([action[3]]) #only penalize rotation until learning works well [action[0],action[1],action[3]])
- actionCost = np.linalg.norm(npaction)*10.
+ npaction = np.array([
+ action[3]
+ ]) #only penalize rotation until learning works well [action[0],action[1],action[3]])
+ actionCost = np.linalg.norm(npaction) * 10.
#print("actionCost")
#print(actionCost)
- reward = self._reward()-actionCost
+ reward = self._reward() - actionCost
#print("reward")
#print(reward)
@@ -187,22 +190,23 @@ class KukaGymEnv(gym.Env):
if mode != "rgb_array":
return np.array([])
- base_pos,orn = self._p.getBasePositionAndOrientation(self._kuka.kukaUid)
- view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
- cameraTargetPosition=base_pos,
- distance=self._cam_dist,
- yaw=self._cam_yaw,
- pitch=self._cam_pitch,
- roll=0,
- upAxisIndex=2)
- proj_matrix = self._p.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._p.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=self._p.ER_BULLET_HARDWARE_OPENGL)
- #renderer=self._p.ER_TINY_RENDERER)
-
+ base_pos, orn = self._p.getBasePositionAndOrientation(self._kuka.kukaUid)
+ view_matrix = self._p.computeViewMatrixFromYawPitchRoll(cameraTargetPosition=base_pos,
+ distance=self._cam_dist,
+ yaw=self._cam_yaw,
+ pitch=self._cam_pitch,
+ roll=0,
+ upAxisIndex=2)
+ proj_matrix = self._p.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) / RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _, _) = self._p.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=self._p.ER_BULLET_HARDWARE_OPENGL)
+ #renderer=self._p.ER_TINY_RENDERER)
rgb_array = np.array(px, dtype=np.uint8)
rgb_array = np.reshape(rgb_array, (RENDER_HEIGHT, RENDER_WIDTH, 4))
@@ -210,49 +214,47 @@ class KukaGymEnv(gym.Env):
rgb_array = rgb_array[:, :, :3]
return rgb_array
-
def _termination(self):
#print (self._kuka.endEffectorPos[2])
- state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
+ state = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
#print("self._envStepCounter")
#print(self._envStepCounter)
- if (self.terminated or self._envStepCounter>self._maxSteps):
+ if (self.terminated or self._envStepCounter > self._maxSteps):
self._observation = self.getExtendedObservation()
return True
maxDist = 0.005
- closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid,maxDist)
+ closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid, maxDist)
- if (len(closestPoints)):#(actualEndEffectorPos[2] <= -0.43):
+ if (len(closestPoints)): #(actualEndEffectorPos[2] <= -0.43):
self.terminated = 1
#print("terminating, closing gripper, attempting grasp")
#start grasp and terminate
fingerAngle = 0.3
- for i in range (100):
- graspAction = [0,0,0.0001,0,fingerAngle]
+ for i in range(100):
+ graspAction = [0, 0, 0.0001, 0, fingerAngle]
self._kuka.applyAction(graspAction)
p.stepSimulation()
- fingerAngle = fingerAngle-(0.3/100.)
- if (fingerAngle<0):
- fingerAngle=0
+ fingerAngle = fingerAngle - (0.3 / 100.)
+ if (fingerAngle < 0):
+ fingerAngle = 0
- for i in range (1000):
- graspAction = [0,0,0.001,0,fingerAngle]
+ for i in range(1000):
+ graspAction = [0, 0, 0.001, 0, fingerAngle]
self._kuka.applyAction(graspAction)
p.stepSimulation()
- blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
+ blockPos, blockOrn = p.getBasePositionAndOrientation(self.blockUid)
if (blockPos[2] > 0.23):
#print("BLOCKPOS!")
#print(blockPos[2])
break
- state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
+ state = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
- if (actualEndEffectorPos[2]>0.5):
+ if (actualEndEffectorPos[2] > 0.5):
break
-
self._observation = self.getExtendedObservation()
return True
return False
@@ -260,18 +262,19 @@ class KukaGymEnv(gym.Env):
def _reward(self):
#rewards is height of target object
- blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
- closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
+ blockPos, blockOrn = p.getBasePositionAndOrientation(self.blockUid)
+ closestPoints = p.getClosestPoints(self.blockUid, self._kuka.kukaUid, 1000, -1,
+ self._kuka.kukaEndEffectorIndex)
reward = -1000
numPt = len(closestPoints)
#print(numPt)
- if (numPt>0):
+ if (numPt > 0):
#print("reward:")
- reward = -closestPoints[0][8]*10
- if (blockPos[2] >0.2):
- reward = reward+10000
+ reward = -closestPoints[0][8] * 10
+ if (blockPos[2] > 0.2):
+ reward = reward + 10000
print("successfully grasped a block!!!")
#print("self._envStepCounter")
#print(self._envStepCounter)
@@ -279,7 +282,7 @@ class KukaGymEnv(gym.Env):
#print(self._envStepCounter)
#print("reward")
#print(reward)
- #print("reward")
+ #print("reward")
#print(reward)
return reward
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/kuka_diverse_object_gym_env.py b/examples/pybullet/gym/pybullet_envs/bullet/kuka_diverse_object_gym_env.py
index c2c4d2acc..696dc268a 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/kuka_diverse_object_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/kuka_diverse_object_gym_env.py
@@ -13,6 +13,7 @@ import glob
from pkg_resources import parse_version
import gym
+
class KukaDiverseObjectEnv(KukaGymEnv):
"""Class for Kuka environment with diverse objects.
@@ -61,7 +62,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
"""
self._isDiscrete = isDiscrete
- self._timeStep = 1./240.
+ self._timeStep = 1. / 240.
self._urdfRoot = urdfRoot
self._actionRepeat = actionRepeat
self._isEnableSelfCollision = isEnableSelfCollision
@@ -85,9 +86,9 @@ class KukaDiverseObjectEnv(KukaGymEnv):
if self._renders:
self.cid = p.connect(p.SHARED_MEMORY)
- if (self.cid<0):
- self.cid = p.connect(p.GUI)
- p.resetDebugVisualizerCamera(1.3,180,-41,[0.52,-0.2,-0.33])
+ if (self.cid < 0):
+ self.cid = p.connect(p.GUI)
+ p.resetDebugVisualizerCamera(1.3, 180, -41, [0.52, -0.2, -0.33])
else:
self.cid = p.connect(p.DIRECT)
self.seed()
@@ -100,9 +101,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
else:
self.action_space = spaces.Box(low=-1, high=1, shape=(3,)) # dx, dy, da
if self._removeHeightHack:
- self.action_space = spaces.Box(low=-1,
- high=1,
- shape=(4,)) # dx, dy, dz, da
+ self.action_space = spaces.Box(low=-1, high=1, shape=(4,)) # dx, dy, dz, da
self.viewer = None
def reset(self):
@@ -111,17 +110,15 @@ class KukaDiverseObjectEnv(KukaGymEnv):
# Set the camera settings.
look = [0.23, 0.2, 0.54]
distance = 1.
- pitch = -56 + self._cameraRandom*np.random.uniform(-3, 3)
- yaw = 245 + self._cameraRandom*np.random.uniform(-3, 3)
+ pitch = -56 + self._cameraRandom * np.random.uniform(-3, 3)
+ yaw = 245 + self._cameraRandom * np.random.uniform(-3, 3)
roll = 0
- self._view_matrix = p.computeViewMatrixFromYawPitchRoll(
- look, distance, yaw, pitch, roll, 2)
- fov = 20. + self._cameraRandom*np.random.uniform(-2, 2)
+ self._view_matrix = p.computeViewMatrixFromYawPitchRoll(look, distance, yaw, pitch, roll, 2)
+ fov = 20. + self._cameraRandom * np.random.uniform(-2, 2)
aspect = self._width / self._height
near = 0.01
far = 10
- self._proj_matrix = p.computeProjectionMatrixFOV(
- fov, aspect, near, far)
+ self._proj_matrix = p.computeProjectionMatrixFOV(fov, aspect, near, far)
self._attempted_grasp = False
self._env_step = 0
@@ -130,18 +127,18 @@ class KukaDiverseObjectEnv(KukaGymEnv):
p.resetSimulation()
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
- p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
+ p.loadURDF(os.path.join(self._urdfRoot, "plane.urdf"), [0, 0, -1])
- p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
+ p.loadURDF(os.path.join(self._urdfRoot, "table/table.urdf"), 0.5000000, 0.00000, -.820000,
+ 0.000000, 0.000000, 0.0, 1.0)
- p.setGravity(0,0,-10)
+ p.setGravity(0, 0, -10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
p.stepSimulation()
# Choose the objects in the bin.
- urdfList = self._get_random_object(
- self._numObjects, self._isTest)
+ urdfList = self._get_random_object(self._numObjects, self._isTest)
self._objectUids = self._randomly_place_objects(urdfList)
self._observation = self._get_observation()
return np.array(self._observation)
@@ -156,17 +153,15 @@ class KukaDiverseObjectEnv(KukaGymEnv):
The list of object unique ID's.
"""
-
# Randomize positions of each object urdf.
objectUids = []
for urdf_name in urdfList:
- xpos = 0.4 +self._blockRandom*random.random()
- ypos = self._blockRandom*(random.random()-.5)
- angle = np.pi/2 + self._blockRandom * np.pi * random.random()
+ xpos = 0.4 + self._blockRandom * random.random()
+ ypos = self._blockRandom * (random.random() - .5)
+ angle = np.pi / 2 + self._blockRandom * np.pi * random.random()
orn = p.getQuaternionFromEuler([0, 0, angle])
urdf_path = os.path.join(self._urdfRoot, urdf_name)
- uid = p.loadURDF(urdf_path, [xpos, ypos, .15],
- [orn[0], orn[1], orn[2], orn[3]])
+ uid = p.loadURDF(urdf_path, [xpos, ypos, .15], [orn[0], orn[1], orn[2], orn[3]])
objectUids.append(uid)
# Let each object fall to the tray individual, to prevent object
# intersection.
@@ -178,9 +173,9 @@ class KukaDiverseObjectEnv(KukaGymEnv):
"""Return the observation as an image.
"""
img_arr = p.getCameraImage(width=self._width,
- height=self._height,
- viewMatrix=self._view_matrix,
- projectionMatrix=self._proj_matrix)
+ height=self._height,
+ viewMatrix=self._view_matrix,
+ projectionMatrix=self._proj_matrix)
rgb = img_arr[2]
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
return np_img_arr[:, :, :3]
@@ -246,8 +241,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
break
# If we are close to the bin, attempt grasp.
- state = p.getLinkState(self._kuka.kukaUid,
- self._kuka.kukaEndEffectorIndex)
+ state = p.getLinkState(self._kuka.kukaUid, self._kuka.kukaEndEffectorIndex)
end_effector_pos = state[0]
if end_effector_pos[2] <= 0.1:
finger_angle = 0.3
@@ -257,7 +251,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
p.stepSimulation()
#if self._renders:
# time.sleep(self._timeStep)
- finger_angle -= 0.3/100.
+ finger_angle -= 0.3 / 100.
if finger_angle < 0:
finger_angle = 0
for _ in range(500):
@@ -266,7 +260,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
p.stepSimulation()
if self._renders:
time.sleep(self._timeStep)
- finger_angle -= 0.3/100.
+ finger_angle -= 0.3 / 100.
if finger_angle < 0:
finger_angle = 0
self._attempted_grasp = True
@@ -274,9 +268,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
done = self._termination()
reward = self._reward()
- debug = {
- 'grasp_success': self._graspSuccess
- }
+ debug = {'grasp_success': self._graspSuccess}
return observation, reward, done, debug
def _reward(self):
@@ -288,8 +280,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
reward = 0
self._graspSuccess = 0
for uid in self._objectUids:
- pos, _ = p.getBasePositionAndOrientation(
- uid)
+ pos, _ = p.getBasePositionAndOrientation(uid)
# If any block is above height, provide reward.
if pos[2] > 0.2:
self._graspSuccess += 1
@@ -319,8 +310,7 @@ class KukaDiverseObjectEnv(KukaGymEnv):
urdf_pattern = os.path.join(self._urdfRoot, 'random_urdfs/*[1-9]/*.urdf')
found_object_directories = glob.glob(urdf_pattern)
total_num_objects = len(found_object_directories)
- selected_objects = np.random.choice(np.arange(total_num_objects),
- num_objects)
+ selected_objects = np.random.choice(np.arange(total_num_objects), num_objects)
selected_objects_filenames = []
for object_index in selected_objects:
selected_objects_filenames += [found_object_directories[object_index]]
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur.py
index 046370040..3f1c50a1f 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur.py
@@ -15,9 +15,8 @@ OVERHEAT_SHUTDOWN_TORQUE = 2.45
OVERHEAT_SHUTDOWN_TIME = 1.0
LEG_POSITION = ["front_left", "back_left", "front_right", "back_right"]
MOTOR_NAMES = [
- "motor_front_leftL_joint", "motor_front_leftR_joint",
- "motor_back_leftL_joint", "motor_back_leftR_joint",
- "motor_front_rightL_joint", "motor_front_rightR_joint",
+ "motor_front_leftL_joint", "motor_front_leftR_joint", "motor_back_leftL_joint",
+ "motor_back_leftR_joint", "motor_front_rightL_joint", "motor_front_rightR_joint",
"motor_back_rightL_joint", "motor_back_rightR_joint"
]
LEG_LINK_ID = [2, 3, 5, 6, 8, 9, 11, 12, 15, 16, 18, 19, 21, 22, 24, 25]
@@ -33,7 +32,7 @@ class Minitaur(object):
def __init__(self,
pybullet_client,
- urdf_root= os.path.join(os.path.dirname(__file__),"../data"),
+ urdf_root=os.path.join(os.path.dirname(__file__), "../data"),
time_step=0.01,
self_collision_enabled=False,
motor_velocity_limit=np.inf,
@@ -87,10 +86,9 @@ class Minitaur(object):
if self._accurate_motor_model_enabled:
self._kp = motor_kp
self._kd = motor_kd
- self._motor_model = motor.MotorModel(
- torque_control_enabled=self._torque_control_enabled,
- kp=self._kp,
- kd=self._kd)
+ self._motor_model = motor.MotorModel(torque_control_enabled=self._torque_control_enabled,
+ kp=self._kp,
+ kd=self._kd)
elif self._pd_control_enabled:
self._kp = 8
self._kd = kd_for_pd_controllers
@@ -101,15 +99,12 @@ class Minitaur(object):
self.Reset()
def _RecordMassInfoFromURDF(self):
- self._base_mass_urdf = self._pybullet_client.getDynamicsInfo(
- self.quadruped, BASE_LINK_ID)[0]
+ self._base_mass_urdf = self._pybullet_client.getDynamicsInfo(self.quadruped, BASE_LINK_ID)[0]
self._leg_masses_urdf = []
self._leg_masses_urdf.append(
- self._pybullet_client.getDynamicsInfo(self.quadruped, LEG_LINK_ID[0])[
- 0])
+ self._pybullet_client.getDynamicsInfo(self.quadruped, LEG_LINK_ID[0])[0])
self._leg_masses_urdf.append(
- self._pybullet_client.getDynamicsInfo(self.quadruped, MOTOR_LINK_ID[0])[
- 0])
+ self._pybullet_client.getDynamicsInfo(self.quadruped, MOTOR_LINK_ID[0])[0])
def _BuildJointNameToIdDict(self):
num_joints = self._pybullet_client.getNumJoints(self.quadruped)
@@ -119,9 +114,7 @@ class Minitaur(object):
self._joint_name_to_id[joint_info[1].decode("UTF-8")] = joint_info[0]
def _BuildMotorIdList(self):
- self._motor_id_list = [
- self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES
- ]
+ self._motor_id_list = [self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES]
def Reset(self, reload_urdf=True):
"""Reset the minitaur to its initial states.
@@ -144,39 +137,35 @@ class Minitaur(object):
self._RecordMassInfoFromURDF()
self.ResetPose(add_constraint=True)
if self._on_rack:
- self._pybullet_client.createConstraint(
- self.quadruped, -1, -1, -1, self._pybullet_client.JOINT_FIXED,
- [0, 0, 0], [0, 0, 0], [0, 0, 1])
+ self._pybullet_client.createConstraint(self.quadruped, -1, -1, -1,
+ self._pybullet_client.JOINT_FIXED, [0, 0, 0],
+ [0, 0, 0], [0, 0, 1])
else:
- self._pybullet_client.resetBasePositionAndOrientation(
- self.quadruped, INIT_POSITION, INIT_ORIENTATION)
- self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
- [0, 0, 0])
+ self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, INIT_POSITION,
+ INIT_ORIENTATION)
+ self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
self.ResetPose(add_constraint=False)
self._overheat_counter = np.zeros(self.num_motors)
self._motor_enabled_list = [True] * self.num_motors
def _SetMotorTorqueById(self, motor_id, torque):
- self._pybullet_client.setJointMotorControl2(
- bodyIndex=self.quadruped,
- jointIndex=motor_id,
- controlMode=self._pybullet_client.TORQUE_CONTROL,
- force=torque)
+ self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
+ jointIndex=motor_id,
+ controlMode=self._pybullet_client.TORQUE_CONTROL,
+ force=torque)
def _SetDesiredMotorAngleById(self, motor_id, desired_angle):
- self._pybullet_client.setJointMotorControl2(
- bodyIndex=self.quadruped,
- jointIndex=motor_id,
- controlMode=self._pybullet_client.POSITION_CONTROL,
- targetPosition=desired_angle,
- positionGain=self._kp,
- velocityGain=self._kd,
- force=self._max_force)
+ self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
+ jointIndex=motor_id,
+ controlMode=self._pybullet_client.POSITION_CONTROL,
+ targetPosition=desired_angle,
+ positionGain=self._kp,
+ velocityGain=self._kd,
+ force=self._max_force)
def _SetDesiredMotorAngleByName(self, motor_name, desired_angle):
- self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name],
- desired_angle)
+ self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name], desired_angle)
def ResetPose(self, add_constraint):
"""Reset the pose of the minitaur.
@@ -200,59 +189,53 @@ class Minitaur(object):
knee_angle = -2.1834
leg_position = LEG_POSITION[leg_id]
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_link"],
- self._motor_direction[2 * leg_id] * knee_angle,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_link"],
- self._motor_direction[2 * leg_id + 1] * knee_angle,
- targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "L_link"],
+ self._motor_direction[2 * leg_id] * knee_angle,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "R_link"],
+ self._motor_direction[2 * leg_id + 1] * knee_angle,
+ targetVelocity=0)
if add_constraint:
self._pybullet_client.createConstraint(
- self.quadruped, self._joint_name_to_id["knee_"
- + leg_position + "R_link"],
- self.quadruped, self._joint_name_to_id["knee_"
- + leg_position + "L_link"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_RIGHT, KNEE_CONSTRAINT_POINT_LEFT)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_link"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_link"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_RIGHT,
+ KNEE_CONSTRAINT_POINT_LEFT)
if self._accurate_motor_model_enabled or self._pd_control_enabled:
# Disable the default motor in pybullet.
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(self._joint_name_to_id["motor_"
- + leg_position + "L_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(self._joint_name_to_id["motor_"
- + leg_position + "R_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
else:
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "L_joint",
- self._motor_direction[2 * leg_id] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
+ self._motor_direction[2 * leg_id] * half_pi)
self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
- self._motor_direction[2 * leg_id
- + 1] * half_pi)
+ self._motor_direction[2 * leg_id + 1] * half_pi)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
@@ -273,8 +256,7 @@ class Minitaur(object):
Returns:
The position of minitaur's base.
"""
- position, _ = (
- self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
+ position, _ = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
return position
def GetBaseOrientation(self):
@@ -283,8 +265,7 @@ class Minitaur(object):
Returns:
The orientation of minitaur's base.
"""
- _, orientation = (
- self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
+ _, orientation = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
return orientation
def GetActionDimension(self):
@@ -304,10 +285,9 @@ class Minitaur(object):
"""
upper_bound = np.array([0.0] * self.GetObservationDimension())
upper_bound[0:self.num_motors] = math.pi # Joint angle.
- upper_bound[self.num_motors:2 * self.num_motors] = (
- motor.MOTOR_SPEED_LIMIT) # Joint velocity.
- upper_bound[2 * self.num_motors:3 * self.num_motors] = (
- motor.OBSERVED_TORQUE_LIMIT) # Joint torque.
+ upper_bound[self.num_motors:2 * self.num_motors] = (motor.MOTOR_SPEED_LIMIT) # Joint velocity.
+ upper_bound[2 * self.num_motors:3 * self.num_motors] = (motor.OBSERVED_TORQUE_LIMIT
+ ) # Joint torque.
upper_bound[3 * self.num_motors:] = 1.0 # Quaternion of base orientation.
return upper_bound
@@ -354,12 +334,9 @@ class Minitaur(object):
"""
if self._motor_velocity_limit < np.inf:
current_motor_angle = self.GetMotorAngles()
- motor_commands_max = (
- current_motor_angle + self.time_step * self._motor_velocity_limit)
- motor_commands_min = (
- current_motor_angle - self.time_step * self._motor_velocity_limit)
- motor_commands = np.clip(motor_commands, motor_commands_min,
- motor_commands_max)
+ motor_commands_max = (current_motor_angle + self.time_step * self._motor_velocity_limit)
+ motor_commands_min = (current_motor_angle - self.time_step * self._motor_velocity_limit)
+ motor_commands = np.clip(motor_commands, motor_commands_min, motor_commands_max)
if self._accurate_motor_model_enabled or self._pd_control_enabled:
q = self.GetMotorAngles()
@@ -373,8 +350,7 @@ class Minitaur(object):
self._overheat_counter[i] += 1
else:
self._overheat_counter[i] = 0
- if (self._overheat_counter[i] >
- OVERHEAT_SHUTDOWN_TIME / self.time_step):
+ if (self._overheat_counter[i] > OVERHEAT_SHUTDOWN_TIME / self.time_step):
self._motor_enabled_list[i] = False
# The torque is already in the observation space because we use
@@ -382,12 +358,11 @@ class Minitaur(object):
self._observed_motor_torques = observed_torque
# Transform into the motor space when applying the torque.
- self._applied_motor_torque = np.multiply(actual_torque,
- self._motor_direction)
+ self._applied_motor_torque = np.multiply(actual_torque, self._motor_direction)
- for motor_id, motor_torque, motor_enabled in zip(
- self._motor_id_list, self._applied_motor_torque,
- self._motor_enabled_list):
+ for motor_id, motor_torque, motor_enabled in zip(self._motor_id_list,
+ self._applied_motor_torque,
+ self._motor_enabled_list):
if motor_enabled:
self._SetMotorTorqueById(motor_id, motor_torque)
else:
@@ -403,14 +378,12 @@ class Minitaur(object):
self._applied_motor_torques = np.multiply(self._observed_motor_torques,
self._motor_direction)
- for motor_id, motor_torque in zip(self._motor_id_list,
- self._applied_motor_torques):
+ for motor_id, motor_torque in zip(self._motor_id_list, self._applied_motor_torques):
self._SetMotorTorqueById(motor_id, motor_torque)
else:
- motor_commands_with_direction = np.multiply(motor_commands,
- self._motor_direction)
- for motor_id, motor_command_with_direction in zip(
- self._motor_id_list, motor_commands_with_direction):
+ motor_commands_with_direction = np.multiply(motor_commands, self._motor_direction)
+ for motor_id, motor_command_with_direction in zip(self._motor_id_list,
+ motor_commands_with_direction):
self._SetDesiredMotorAngleById(motor_id, motor_command_with_direction)
def GetMotorAngles(self):
@@ -471,13 +444,13 @@ class Minitaur(object):
quater_pi = math.pi / 4
for i in range(self.num_motors):
action_idx = i // 2
- forward_backward_component = (-scale_for_singularity * quater_pi * (
- actions[action_idx + half_num_motors] + offset_for_singularity))
+ forward_backward_component = (
+ -scale_for_singularity * quater_pi *
+ (actions[action_idx + half_num_motors] + offset_for_singularity))
extension_component = (-1)**i * quater_pi * actions[action_idx]
if i >= half_num_motors:
extension_component = -extension_component
- motor_angle[i] = (
- math.pi + forward_backward_component + extension_component)
+ motor_angle[i] = (math.pi + forward_backward_component + extension_component)
return motor_angle
def GetBaseMassFromURDF(self):
@@ -489,8 +462,7 @@ class Minitaur(object):
return self._leg_masses_urdf
def SetBaseMass(self, base_mass):
- self._pybullet_client.changeDynamics(
- self.quadruped, BASE_LINK_ID, mass=base_mass)
+ self._pybullet_client.changeDynamics(self.quadruped, BASE_LINK_ID, mass=base_mass)
def SetLegMasses(self, leg_masses):
"""Set the mass of the legs.
@@ -504,11 +476,9 @@ class Minitaur(object):
leg_masses[1] is the mass of the motor.
"""
for link_id in LEG_LINK_ID:
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, mass=leg_masses[0])
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, mass=leg_masses[0])
for link_id in MOTOR_LINK_ID:
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, mass=leg_masses[1])
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, mass=leg_masses[1])
def SetFootFriction(self, foot_friction):
"""Set the lateral friction of the feet.
@@ -518,8 +488,7 @@ class Minitaur(object):
shared by all four feet.
"""
for link_id in FOOT_LINK_ID:
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, lateralFriction=foot_friction)
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, lateralFriction=foot_friction)
def SetBatteryVoltage(self, voltage):
if self._accurate_motor_model_enabled:
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_duck_gym_env.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_duck_gym_env.py
index d2fb0c859..88d605f11 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_duck_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_duck_gym_env.py
@@ -6,8 +6,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 time
@@ -34,8 +33,9 @@ OBSERVATION_EPS = 0.01
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
-duckStartPos = [0,0,0.25]
-duckStartOrn = [0.5,0.5,0.5,0.5]
+duckStartPos = [0, 0, 0.25]
+duckStartOrn = [0.5, 0.5, 0.5, 0.5]
+
class MinitaurBulletDuckEnv(gym.Env):
"""The gym environment for the minitaur.
@@ -47,34 +47,32 @@ class MinitaurBulletDuckEnv(gym.Env):
expenditure.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 50
- }
-
- def __init__(self,
- urdf_root=pybullet_data.getDataPath(),
- action_repeat=1,
- distance_weight=1.0,
- energy_weight=0.005,
- shake_weight=0.0,
- drift_weight=0.0,
- distance_limit=float("inf"),
- observation_noise_stdev=0.0,
- self_collision_enabled=True,
- motor_velocity_limit=np.inf,
- pd_control_enabled=False,#not needed to be true if accurate motor model is enabled (has its own better PD)
- leg_model_enabled=True,
- accurate_motor_model_enabled=True,
- motor_kp=1.0,
- motor_kd=0.02,
- torque_control_enabled=False,
- motor_overheat_protection=True,
- hard_reset=True,
- on_rack=False,
- render=False,
- kd_for_pd_controllers=0.3,
- env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()):
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
+
+ def __init__(
+ self,
+ urdf_root=pybullet_data.getDataPath(),
+ action_repeat=1,
+ distance_weight=1.0,
+ energy_weight=0.005,
+ shake_weight=0.0,
+ drift_weight=0.0,
+ distance_limit=float("inf"),
+ observation_noise_stdev=0.0,
+ self_collision_enabled=True,
+ motor_velocity_limit=np.inf,
+ pd_control_enabled=False, #not needed to be true if accurate motor model is enabled (has its own better PD)
+ leg_model_enabled=True,
+ accurate_motor_model_enabled=True,
+ motor_kp=1.0,
+ motor_kd=0.02,
+ torque_control_enabled=False,
+ motor_overheat_protection=True,
+ hard_reset=True,
+ on_rack=False,
+ render=False,
+ kd_for_pd_controllers=0.3,
+ env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()):
"""Initialize the minitaur gym environment.
Args:
@@ -152,17 +150,14 @@ class MinitaurBulletDuckEnv(gym.Env):
self._action_repeat *= NUM_SUBSTEPS
if self._is_render:
- self._pybullet_client = bullet_client.BulletClient(
- connection_mode=pybullet.GUI)
+ self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
self._pybullet_client = bullet_client.BulletClient()
self.seed()
self.reset()
- observation_high = (
- self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
- observation_low = (
- self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
+ observation_high = (self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
+ observation_low = (self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
action_dim = 8
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
@@ -183,35 +178,36 @@ class MinitaurBulletDuckEnv(gym.Env):
numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step)
self._groundId = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
- self._duckId = self._pybullet_client.loadURDF("%s/duck_vhacd.urdf" % self._urdf_root,duckStartPos,duckStartOrn)
+ self._duckId = self._pybullet_client.loadURDF("%s/duck_vhacd.urdf" % self._urdf_root,
+ duckStartPos, duckStartOrn)
self._pybullet_client.setGravity(0, 0, -10)
acc_motor = self._accurate_motor_model_enabled
motor_protect = self._motor_overheat_protection
- self.minitaur = (minitaur.Minitaur(
- pybullet_client=self._pybullet_client,
- urdf_root=self._urdf_root,
- time_step=self._time_step,
- self_collision_enabled=self._self_collision_enabled,
- motor_velocity_limit=self._motor_velocity_limit,
- pd_control_enabled=self._pd_control_enabled,
- accurate_motor_model_enabled=acc_motor,
- motor_kp=self._motor_kp,
- motor_kd=self._motor_kd,
- torque_control_enabled=self._torque_control_enabled,
- motor_overheat_protection=motor_protect,
- on_rack=self._on_rack,
- kd_for_pd_controllers=self._kd_for_pd_controllers))
+ self.minitaur = (minitaur.Minitaur(pybullet_client=self._pybullet_client,
+ urdf_root=self._urdf_root,
+ time_step=self._time_step,
+ self_collision_enabled=self._self_collision_enabled,
+ motor_velocity_limit=self._motor_velocity_limit,
+ pd_control_enabled=self._pd_control_enabled,
+ accurate_motor_model_enabled=acc_motor,
+ motor_kp=self._motor_kp,
+ motor_kd=self._motor_kd,
+ torque_control_enabled=self._torque_control_enabled,
+ motor_overheat_protection=motor_protect,
+ on_rack=self._on_rack,
+ kd_for_pd_controllers=self._kd_for_pd_controllers))
else:
self.minitaur.Reset(reload_urdf=False)
- self._pybullet_client.resetBasePositionAndOrientation(self._duckId,duckStartPos,duckStartOrn)
+ self._pybullet_client.resetBasePositionAndOrientation(self._duckId, duckStartPos,
+ duckStartOrn)
if self._env_randomizer is not None:
self._env_randomizer.randomize_env(self)
self._env_step_counter = 0
self._last_base_position = [0, 0, 0]
self._objectives = []
- self._pybullet_client.resetDebugVisualizerCamera(
- self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0])
+ self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
+ self._cam_pitch, [0, 0, 0])
if not self._torque_control_enabled:
for _ in range(100):
if self._pd_control_enabled or self._accurate_motor_model_enabled:
@@ -228,8 +224,7 @@ class MinitaurBulletDuckEnv(gym.Env):
for i, action_component in enumerate(action):
if not (-self._action_bound - ACTION_EPS <= action_component <=
self._action_bound + ACTION_EPS):
- raise ValueError(
- "{}th action {} out of bounds.".format(i, action_component))
+ raise ValueError("{}th action {} out of bounds.".format(i, action_component))
action = self.minitaur.ConvertFromLegModel(action)
return action
@@ -258,8 +253,8 @@ class MinitaurBulletDuckEnv(gym.Env):
if time_to_sleep > 0:
time.sleep(time_to_sleep)
base_pos = self.minitaur.GetBasePosition()
- self._pybullet_client.resetDebugVisualizerCamera(
- self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
+ self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
+ self._cam_pitch, base_pos)
action = self._transform_action_to_motor_command(action)
for _ in range(self._action_repeat):
self.minitaur.ApplyAction(action)
@@ -281,12 +276,17 @@ class MinitaurBulletDuckEnv(gym.Env):
pitch=self._cam_pitch,
roll=0,
upAxisIndex=2)
- proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._pybullet_client.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) /
+ RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _,
+ _) = self._pybullet_client.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3]
return rgb_array
@@ -297,9 +297,8 @@ class MinitaurBulletDuckEnv(gym.Env):
Returns:
A numpy array of motor angles.
"""
- return np.array(
- self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:
- MOTOR_ANGLE_OBSERVATION_INDEX + NUM_MOTORS])
+ return np.array(self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:MOTOR_ANGLE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_velocities(self):
"""Get the minitaur's motor velocities.
@@ -308,8 +307,8 @@ class MinitaurBulletDuckEnv(gym.Env):
A numpy array of motor velocities.
"""
return np.array(
- self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:
- MOTOR_VELOCITY_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:MOTOR_VELOCITY_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_torques(self):
"""Get the minitaur's motor torques.
@@ -318,8 +317,8 @@ class MinitaurBulletDuckEnv(gym.Env):
A numpy array of motor torques.
"""
return np.array(
- self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:
- MOTOR_TORQUE_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:MOTOR_TORQUE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_base_orientation(self):
"""Get the minitaur's base orientation, represented by a quaternion.
@@ -330,8 +329,8 @@ class MinitaurBulletDuckEnv(gym.Env):
return np.array(self._observation[BASE_ORIENTATION_OBSERVATION_INDEX:])
def lost_duck(self):
- points = self._pybullet_client.getContactPoints(self._duckId, self._groundId);
- return len(points)>0
+ points = self._pybullet_client.getContactPoints(self._duckId, self._groundId)
+ return len(points) > 0
def is_fallen(self):
"""Decide whether the minitaur has fallen.
@@ -347,8 +346,7 @@ class MinitaurBulletDuckEnv(gym.Env):
rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation)
local_up = rot_mat[6:]
pos = self.minitaur.GetBasePosition()
- return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or
- pos[2] < 0.13)
+ return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or pos[2] < 0.13)
def _termination(self):
position = self.minitaur.GetBasePosition()
@@ -364,12 +362,9 @@ class MinitaurBulletDuckEnv(gym.Env):
energy_reward = np.abs(
np.dot(self.minitaur.GetMotorTorques(),
self.minitaur.GetMotorVelocities())) * self._time_step
- reward = (
- self._distance_weight * forward_reward -
- self._energy_weight * energy_reward + self._drift_weight * drift_reward
- + self._shake_weight * shake_reward)
- self._objectives.append(
- [forward_reward, energy_reward, drift_reward, shake_reward])
+ reward = (self._distance_weight * forward_reward - self._energy_weight * energy_reward +
+ self._drift_weight * drift_reward + self._shake_weight * shake_reward)
+ self._objectives.append([forward_reward, energy_reward, drift_reward, shake_reward])
return reward
def get_objectives(self):
@@ -383,9 +378,9 @@ class MinitaurBulletDuckEnv(gym.Env):
self._get_observation()
observation = np.array(self._observation)
if self._observation_noise_stdev > 0:
- observation += (np.random.normal(
- scale=self._observation_noise_stdev, size=observation.shape) *
- self.minitaur.GetObservationUpperBound())
+ observation += (
+ np.random.normal(scale=self._observation_noise_stdev, size=observation.shape) *
+ self.minitaur.GetObservationUpperBound())
return observation
if parse_version(gym.__version__) < parse_version('0.9.6'):
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_env_randomizer.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_env_randomizer.py
index db139f3b0..cf2646683 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_env_randomizer.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_env_randomizer.py
@@ -45,24 +45,20 @@ class MinitaurEnvRandomizer(env_randomizer_base.EnvRandomizerBase):
minitaur.SetBaseMass(randomized_base_mass)
leg_masses = minitaur.GetLegMassesFromURDF()
- leg_masses_lower_bound = np.array(leg_masses) * (
- 1.0 + self._minitaur_leg_mass_err_range[0])
- leg_masses_upper_bound = np.array(leg_masses) * (
- 1.0 + self._minitaur_leg_mass_err_range[1])
+ leg_masses_lower_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[0])
+ leg_masses_upper_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[1])
randomized_leg_masses = [
np.random.uniform(leg_masses_lower_bound[i], leg_masses_upper_bound[i])
for i in range(len(leg_masses))
]
minitaur.SetLegMasses(randomized_leg_masses)
- randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0],
- BATTERY_VOLTAGE_RANGE[1])
+ randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0], BATTERY_VOLTAGE_RANGE[1])
minitaur.SetBatteryVoltage(randomized_battery_voltage)
randomized_motor_damping = random.uniform(MOTOR_VISCOUS_DAMPING_RANGE[0],
MOTOR_VISCOUS_DAMPING_RANGE[1])
minitaur.SetMotorViscousDamping(randomized_motor_damping)
- randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0],
- MINITAUR_LEG_FRICTION[1])
+ randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0], MINITAUR_LEG_FRICTION[1])
minitaur.SetFootFriction(randomized_foot_friction)
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py
index 030840640..7a595b47d 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/minitaur_gym_env.py
@@ -5,8 +5,7 @@
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 math
import time
@@ -33,6 +32,7 @@ OBSERVATION_EPS = 0.01
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
+
class MinitaurBulletEnv(gym.Env):
"""The gym environment for the minitaur.
@@ -43,34 +43,32 @@ class MinitaurBulletEnv(gym.Env):
expenditure.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 50
- }
-
- def __init__(self,
- urdf_root=pybullet_data.getDataPath(),
- action_repeat=1,
- distance_weight=1.0,
- energy_weight=0.005,
- shake_weight=0.0,
- drift_weight=0.0,
- distance_limit=float("inf"),
- observation_noise_stdev=0.0,
- self_collision_enabled=True,
- motor_velocity_limit=np.inf,
- pd_control_enabled=False,#not needed to be true if accurate motor model is enabled (has its own better PD)
- leg_model_enabled=True,
- accurate_motor_model_enabled=True,
- motor_kp=1.0,
- motor_kd=0.02,
- torque_control_enabled=False,
- motor_overheat_protection=True,
- hard_reset=True,
- on_rack=False,
- render=False,
- kd_for_pd_controllers=0.3,
- env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()):
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
+
+ def __init__(
+ self,
+ urdf_root=pybullet_data.getDataPath(),
+ action_repeat=1,
+ distance_weight=1.0,
+ energy_weight=0.005,
+ shake_weight=0.0,
+ drift_weight=0.0,
+ distance_limit=float("inf"),
+ observation_noise_stdev=0.0,
+ self_collision_enabled=True,
+ motor_velocity_limit=np.inf,
+ pd_control_enabled=False, #not needed to be true if accurate motor model is enabled (has its own better PD)
+ leg_model_enabled=True,
+ accurate_motor_model_enabled=True,
+ motor_kp=1.0,
+ motor_kd=0.02,
+ torque_control_enabled=False,
+ motor_overheat_protection=True,
+ hard_reset=True,
+ on_rack=False,
+ render=False,
+ kd_for_pd_controllers=0.3,
+ env_randomizer=minitaur_env_randomizer.MinitaurEnvRandomizer()):
"""Initialize the minitaur gym environment.
Args:
@@ -147,17 +145,14 @@ class MinitaurBulletEnv(gym.Env):
self._action_repeat *= NUM_SUBSTEPS
if self._is_render:
- self._pybullet_client = bullet_client.BulletClient(
- connection_mode=pybullet.GUI)
+ self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
self._pybullet_client = bullet_client.BulletClient()
self.seed()
self.reset()
- observation_high = (
- self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
- observation_low = (
- self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
+ observation_high = (self.minitaur.GetObservationUpperBound() + OBSERVATION_EPS)
+ observation_low = (self.minitaur.GetObservationLowerBound() - OBSERVATION_EPS)
action_dim = 8
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
@@ -178,25 +173,25 @@ class MinitaurBulletEnv(gym.Env):
numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step)
plane = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
- self._pybullet_client.changeVisualShape(plane,-1,rgbaColor=[1,1,1,0.9])
- self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,0)
+ self._pybullet_client.changeVisualShape(plane, -1, rgbaColor=[1, 1, 1, 0.9])
+ self._pybullet_client.configureDebugVisualizer(
+ self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION, 0)
self._pybullet_client.setGravity(0, 0, -10)
acc_motor = self._accurate_motor_model_enabled
motor_protect = self._motor_overheat_protection
- self.minitaur = (minitaur.Minitaur(
- pybullet_client=self._pybullet_client,
- urdf_root=self._urdf_root,
- time_step=self._time_step,
- self_collision_enabled=self._self_collision_enabled,
- motor_velocity_limit=self._motor_velocity_limit,
- pd_control_enabled=self._pd_control_enabled,
- accurate_motor_model_enabled=acc_motor,
- motor_kp=self._motor_kp,
- motor_kd=self._motor_kd,
- torque_control_enabled=self._torque_control_enabled,
- motor_overheat_protection=motor_protect,
- on_rack=self._on_rack,
- kd_for_pd_controllers=self._kd_for_pd_controllers))
+ self.minitaur = (minitaur.Minitaur(pybullet_client=self._pybullet_client,
+ urdf_root=self._urdf_root,
+ time_step=self._time_step,
+ self_collision_enabled=self._self_collision_enabled,
+ motor_velocity_limit=self._motor_velocity_limit,
+ pd_control_enabled=self._pd_control_enabled,
+ accurate_motor_model_enabled=acc_motor,
+ motor_kp=self._motor_kp,
+ motor_kd=self._motor_kd,
+ torque_control_enabled=self._torque_control_enabled,
+ motor_overheat_protection=motor_protect,
+ on_rack=self._on_rack,
+ kd_for_pd_controllers=self._kd_for_pd_controllers))
else:
self.minitaur.Reset(reload_urdf=False)
@@ -206,8 +201,8 @@ class MinitaurBulletEnv(gym.Env):
self._env_step_counter = 0
self._last_base_position = [0, 0, 0]
self._objectives = []
- self._pybullet_client.resetDebugVisualizerCamera(
- self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0])
+ self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
+ self._cam_pitch, [0, 0, 0])
if not self._torque_control_enabled:
for _ in range(100):
if self._pd_control_enabled or self._accurate_motor_model_enabled:
@@ -224,8 +219,7 @@ class MinitaurBulletEnv(gym.Env):
for i, action_component in enumerate(action):
if not (-self._action_bound - ACTION_EPS <= action_component <=
self._action_bound + ACTION_EPS):
- raise ValueError(
- "{}th action {} out of bounds.".format(i, action_component))
+ raise ValueError("{}th action {} out of bounds.".format(i, action_component))
action = self.minitaur.ConvertFromLegModel(action)
return action
@@ -256,14 +250,15 @@ class MinitaurBulletEnv(gym.Env):
base_pos = self.minitaur.GetBasePosition()
camInfo = self._pybullet_client.getDebugVisualizerCamera()
curTargetPos = camInfo[11]
- distance=camInfo[10]
+ distance = camInfo[10]
yaw = camInfo[8]
- pitch=camInfo[9]
- targetPos = [0.95*curTargetPos[0]+0.05*base_pos[0],0.95*curTargetPos[1]+0.05*base_pos[1],curTargetPos[2]]
+ pitch = camInfo[9]
+ targetPos = [
+ 0.95 * curTargetPos[0] + 0.05 * base_pos[0], 0.95 * curTargetPos[1] + 0.05 * base_pos[1],
+ curTargetPos[2]
+ ]
-
- self._pybullet_client.resetDebugVisualizerCamera(
- distance, yaw, pitch, base_pos)
+ self._pybullet_client.resetDebugVisualizerCamera(distance, yaw, pitch, base_pos)
action = self._transform_action_to_motor_command(action)
for _ in range(self._action_repeat):
self.minitaur.ApplyAction(action)
@@ -285,12 +280,17 @@ class MinitaurBulletEnv(gym.Env):
pitch=self._cam_pitch,
roll=0,
upAxisIndex=2)
- proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._pybullet_client.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) /
+ RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _,
+ _) = self._pybullet_client.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3]
return rgb_array
@@ -301,9 +301,8 @@ class MinitaurBulletEnv(gym.Env):
Returns:
A numpy array of motor angles.
"""
- return np.array(
- self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:
- MOTOR_ANGLE_OBSERVATION_INDEX + NUM_MOTORS])
+ return np.array(self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:MOTOR_ANGLE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_velocities(self):
"""Get the minitaur's motor velocities.
@@ -312,8 +311,8 @@ class MinitaurBulletEnv(gym.Env):
A numpy array of motor velocities.
"""
return np.array(
- self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:
- MOTOR_VELOCITY_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:MOTOR_VELOCITY_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_torques(self):
"""Get the minitaur's motor torques.
@@ -322,8 +321,8 @@ class MinitaurBulletEnv(gym.Env):
A numpy array of motor torques.
"""
return np.array(
- self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:
- MOTOR_TORQUE_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:MOTOR_TORQUE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_base_orientation(self):
"""Get the minitaur's base orientation, represented by a quaternion.
@@ -347,8 +346,7 @@ class MinitaurBulletEnv(gym.Env):
rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation)
local_up = rot_mat[6:]
pos = self.minitaur.GetBasePosition()
- return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or
- pos[2] < 0.13)
+ return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or pos[2] < 0.13)
def _termination(self):
position = self.minitaur.GetBasePosition()
@@ -364,12 +362,9 @@ class MinitaurBulletEnv(gym.Env):
energy_reward = np.abs(
np.dot(self.minitaur.GetMotorTorques(),
self.minitaur.GetMotorVelocities())) * self._time_step
- reward = (
- self._distance_weight * forward_reward -
- self._energy_weight * energy_reward + self._drift_weight * drift_reward
- + self._shake_weight * shake_reward)
- self._objectives.append(
- [forward_reward, energy_reward, drift_reward, shake_reward])
+ reward = (self._distance_weight * forward_reward - self._energy_weight * energy_reward +
+ self._drift_weight * drift_reward + self._shake_weight * shake_reward)
+ self._objectives.append([forward_reward, energy_reward, drift_reward, shake_reward])
return reward
def get_objectives(self):
@@ -383,9 +378,9 @@ class MinitaurBulletEnv(gym.Env):
self._get_observation()
observation = np.array(self._observation)
if self._observation_noise_stdev > 0:
- observation += (np.random.normal(
- scale=self._observation_noise_stdev, size=observation.shape) *
- self.minitaur.GetObservationUpperBound())
+ observation += (
+ np.random.normal(scale=self._observation_noise_stdev, size=observation.shape) *
+ self.minitaur.GetObservationUpperBound())
return observation
if parse_version(gym.__version__) < parse_version('0.9.6'):
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/motor.py b/examples/pybullet/gym/pybullet_envs/bullet/motor.py
index fa6b4f2da..db048c487 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/motor.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/motor.py
@@ -7,8 +7,7 @@ MOTOR_VOLTAGE = 16.0
MOTOR_RESISTANCE = 0.186
MOTOR_TORQUE_CONSTANT = 0.0954
MOTOR_VISCOUS_DAMPING = 0
-MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (MOTOR_VISCOUS_DAMPING
- + MOTOR_TORQUE_CONSTANT)
+MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT)
class MotorModel(object):
@@ -24,10 +23,7 @@ class MotorModel(object):
pd gains, viscous friction, back-EMF voltage and current-torque profile.
"""
- def __init__(self,
- torque_control_enabled=False,
- kp=1.2,
- kd=0):
+ def __init__(self, torque_control_enabled=False, kp=1.2, kd=0):
self._torque_control_enabled = torque_control_enabled
self._kp = kp
self._kd = kd
@@ -50,8 +46,7 @@ class MotorModel(object):
def get_viscous_dampling(self):
return self._viscous_damping
- def convert_to_torque(self, motor_commands, current_motor_angle,
- current_motor_velocity):
+ def convert_to_torque(self, motor_commands, current_motor_angle, current_motor_velocity):
"""Convert the commands (position control or torque control) to torque.
Args:
@@ -66,8 +61,8 @@ class MotorModel(object):
if self._torque_control_enabled:
pwm = motor_commands
else:
- pwm = (-self._kp * (current_motor_angle - motor_commands)
- - self._kd * current_motor_velocity)
+ pwm = (-self._kp * (current_motor_angle - motor_commands) -
+ self._kd * current_motor_velocity)
pwm = np.clip(pwm, -1.0, 1.0)
return self._convert_to_torque_from_pwm(pwm, current_motor_velocity)
@@ -81,21 +76,19 @@ class MotorModel(object):
actual_torque: The torque that needs to be applied to the motor.
observed_torque: The torque observed by the sensor.
"""
- observed_torque = np.clip(
- self._torque_constant * (pwm * self._voltage / self._resistance),
- -OBSERVED_TORQUE_LIMIT, OBSERVED_TORQUE_LIMIT)
+ observed_torque = np.clip(self._torque_constant * (pwm * self._voltage / self._resistance),
+ -OBSERVED_TORQUE_LIMIT, OBSERVED_TORQUE_LIMIT)
# Net voltage is clipped at 50V by diodes on the motor controller.
- voltage_net = np.clip(pwm * self._voltage -
- (self._torque_constant + self._viscous_damping)
- * current_motor_velocity,
- -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
+ voltage_net = np.clip(
+ pwm * self._voltage -
+ (self._torque_constant + self._viscous_damping) * current_motor_velocity,
+ -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
current = voltage_net / self._resistance
current_sign = np.sign(current)
current_magnitude = np.absolute(current)
# Saturate torque based on empirical current relation.
- actual_torque = np.interp(current_magnitude, self._current_table,
- self._torque_table)
+ actual_torque = np.interp(current_magnitude, self._current_table, self._torque_table)
actual_torque = np.multiply(current_sign, actual_torque)
return actual_torque, observed_torque
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/racecar.py b/examples/pybullet/gym/pybullet_envs/bullet/racecar.py
index c4a47208a..7c1908f4f 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/racecar.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/racecar.py
@@ -4,80 +4,150 @@ import math
import numpy as np
+
class Racecar:
- def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
- self.urdfRootPath = urdfRootPath
- self.timeStep = timeStep
- self._p = bullet_client
- self.reset()
-
- def reset(self):
- car = self._p.loadURDF(os.path.join(self.urdfRootPath,"racecar/racecar_differential.urdf"), [0,0,.2],useFixedBase=False)
- self.racecarUniqueId = car
- #for i in range (self._p.getNumJoints(car)):
- # print (self._p.getJointInfo(car,i))
- for wheel in range(self._p.getNumJoints(car)):
- self._p.setJointMotorControl2(car,wheel,self._p.VELOCITY_CONTROL,targetVelocity=0,force=0)
- self._p.getJointInfo(car,wheel)
-
- #self._p.setJointMotorControl2(car,10,self._p.VELOCITY_CONTROL,targetVelocity=1,force=10)
- c = self._p.createConstraint(car,9,car,11,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=1, maxForce=10000)
-
- c = self._p.createConstraint(car,10,car,13,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, maxForce=10000)
-
- c = self._p.createConstraint(car,9,car,13,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, maxForce=10000)
-
- c = self._p.createConstraint(car,16,car,18,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=1, maxForce=10000)
-
- c = self._p.createConstraint(car,16,car,19,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, maxForce=10000)
-
- c = self._p.createConstraint(car,17,car,19,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, maxForce=10000)
-
- c = self._p.createConstraint(car,1,car,18,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15, maxForce=10000)
- c = self._p.createConstraint(car,3,car,19,jointType=self._p.JOINT_GEAR,jointAxis =[0,1,0],parentFramePosition=[0,0,0],childFramePosition=[0,0,0])
- self._p.changeConstraint(c,gearRatio=-1, gearAuxLink = 15,maxForce=10000)
-
- self.steeringLinks = [0,2]
- self.maxForce = 20
- self.nMotors = 2
- self.motorizedwheels=[8,15]
- self.speedMultiplier = 20.
- self.steeringMultiplier = 0.5
-
- def getActionDimension(self):
- return self.nMotors
-
- def getObservationDimension(self):
- return len(self.getObservation())
-
- def getObservation(self):
- observation = []
- pos,orn=self._p.getBasePositionAndOrientation(self.racecarUniqueId)
-
- observation.extend(list(pos))
- observation.extend(list(orn))
-
- return observation
-
- def applyAction(self, motorCommands):
- targetVelocity=motorCommands[0]*self.speedMultiplier
- #print("targetVelocity")
- #print(targetVelocity)
- steeringAngle = motorCommands[1]*self.steeringMultiplier
- #print("steeringAngle")
- #print(steeringAngle)
- #print("maxForce")
- #print(self.maxForce)
-
- for motor in self.motorizedwheels:
- self._p.setJointMotorControl2(self.racecarUniqueId,motor,self._p.VELOCITY_CONTROL,targetVelocity=targetVelocity,force=self.maxForce)
- for steer in self.steeringLinks:
- self._p.setJointMotorControl2(self.racecarUniqueId,steer,self._p.POSITION_CONTROL,targetPosition=steeringAngle)
+ def __init__(self, bullet_client, urdfRootPath='', timeStep=0.01):
+ self.urdfRootPath = urdfRootPath
+ self.timeStep = timeStep
+ self._p = bullet_client
+ self.reset()
+
+ def reset(self):
+ car = self._p.loadURDF(os.path.join(self.urdfRootPath, "racecar/racecar_differential.urdf"),
+ [0, 0, .2],
+ useFixedBase=False)
+ self.racecarUniqueId = car
+ #for i in range (self._p.getNumJoints(car)):
+ # print (self._p.getJointInfo(car,i))
+ for wheel in range(self._p.getNumJoints(car)):
+ self._p.setJointMotorControl2(car,
+ wheel,
+ self._p.VELOCITY_CONTROL,
+ targetVelocity=0,
+ force=0)
+ self._p.getJointInfo(car, wheel)
+
+ #self._p.setJointMotorControl2(car,10,self._p.VELOCITY_CONTROL,targetVelocity=1,force=10)
+ c = self._p.createConstraint(car,
+ 9,
+ car,
+ 11,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 10,
+ car,
+ 13,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 9,
+ car,
+ 13,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 16,
+ car,
+ 18,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 16,
+ car,
+ 19,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 17,
+ car,
+ 19,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, maxForce=10000)
+
+ c = self._p.createConstraint(car,
+ 1,
+ car,
+ 18,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, gearAuxLink=15, maxForce=10000)
+ c = self._p.createConstraint(car,
+ 3,
+ car,
+ 19,
+ jointType=self._p.JOINT_GEAR,
+ jointAxis=[0, 1, 0],
+ parentFramePosition=[0, 0, 0],
+ childFramePosition=[0, 0, 0])
+ self._p.changeConstraint(c, gearRatio=-1, gearAuxLink=15, maxForce=10000)
+
+ self.steeringLinks = [0, 2]
+ self.maxForce = 20
+ self.nMotors = 2
+ self.motorizedwheels = [8, 15]
+ self.speedMultiplier = 20.
+ self.steeringMultiplier = 0.5
+
+ def getActionDimension(self):
+ return self.nMotors
+
+ def getObservationDimension(self):
+ return len(self.getObservation())
+
+ def getObservation(self):
+ observation = []
+ pos, orn = self._p.getBasePositionAndOrientation(self.racecarUniqueId)
+
+ observation.extend(list(pos))
+ observation.extend(list(orn))
+
+ return observation
+
+ def applyAction(self, motorCommands):
+ targetVelocity = motorCommands[0] * self.speedMultiplier
+ #print("targetVelocity")
+ #print(targetVelocity)
+ steeringAngle = motorCommands[1] * self.steeringMultiplier
+ #print("steeringAngle")
+ #print(steeringAngle)
+ #print("maxForce")
+ #print(self.maxForce)
+
+ for motor in self.motorizedwheels:
+ self._p.setJointMotorControl2(self.racecarUniqueId,
+ motor,
+ self._p.VELOCITY_CONTROL,
+ targetVelocity=targetVelocity,
+ force=self.maxForce)
+ for steer in self.steeringLinks:
+ self._p.setJointMotorControl2(self.racecarUniqueId,
+ steer,
+ self._p.POSITION_CONTROL,
+ targetPosition=steeringAngle)
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py b/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py
index 63d9148d3..a0118d668 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/racecarGymEnv.py
@@ -1,7 +1,7 @@
-import os, inspect
+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 math
import gym
@@ -19,11 +19,9 @@ from pkg_resources import parse_version
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
+
class RacecarGymEnv(gym.Env):
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second' : 50
- }
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
def __init__(self,
urdfRoot=pybullet_data.getDataPath(),
@@ -42,25 +40,24 @@ class RacecarGymEnv(gym.Env):
self._renders = renders
self._isDiscrete = isDiscrete
if self._renders:
- self._p = bullet_client.BulletClient(
- connection_mode=pybullet.GUI)
+ self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
self._p = bullet_client.BulletClient()
self.seed()
#self.reset()
- observationDim = 2 #len(self.getExtendedObservation())
+ observationDim = 2 #len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
# observation_high = np.array([np.finfo(np.float32).max] * observationDim)
- observation_high = np.ones(observationDim) * 1000 #np.inf
+ observation_high = np.ones(observationDim) * 1000 #np.inf
if (isDiscrete):
self.action_space = spaces.Discrete(9)
else:
- action_dim = 2
- self._action_bound = 1
- action_high = np.array([self._action_bound] * action_dim)
- self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
+ action_dim = 2
+ self._action_bound = 1
+ action_high = np.array([self._action_bound] * action_dim)
+ self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
self.observation_space = spaces.Box(-observation_high, observation_high, dtype=np.float32)
self.viewer = None
@@ -69,23 +66,24 @@ class RacecarGymEnv(gym.Env):
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
#self._p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
- stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot,"stadium.sdf"))
+ stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot, "stadium.sdf"))
#move the stadium objects slightly above 0
#for i in stadiumobjects:
# pos,orn = self._p.getBasePositionAndOrientation(i)
# newpos = [pos[0],pos[1],pos[2]-0.1]
# self._p.resetBasePositionAndOrientation(i,newpos,orn)
- dist = 5 +2.*random.random()
- ang = 2.*3.1415925438*random.random()
+ dist = 5 + 2. * random.random()
+ ang = 2. * 3.1415925438 * random.random()
ballx = dist * math.sin(ang)
bally = dist * math.cos(ang)
ballz = 1
- self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2.urdf"),[ballx,bally,ballz])
- self._p.setGravity(0,0,-10)
- self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
+ self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot, "sphere2.urdf"),
+ [ballx, bally, ballz])
+ self._p.setGravity(0, 0, -10)
+ self._racecar = racecar.Racecar(self._p, urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
for i in range(100):
self._p.stepSimulation()
@@ -100,26 +98,26 @@ class RacecarGymEnv(gym.Env):
return [seed]
def getExtendedObservation(self):
- self._observation = [] #self._racecar.getObservation()
- carpos,carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
- ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
- invCarPos,invCarOrn = self._p.invertTransform(carpos,carorn)
- ballPosInCar,ballOrnInCar = self._p.multiplyTransforms(invCarPos,invCarOrn,ballpos,ballorn)
+ self._observation = [] #self._racecar.getObservation()
+ carpos, carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ ballpos, ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
+ invCarPos, invCarOrn = self._p.invertTransform(carpos, carorn)
+ ballPosInCar, ballOrnInCar = self._p.multiplyTransforms(invCarPos, invCarOrn, ballpos, ballorn)
- self._observation.extend([ballPosInCar[0],ballPosInCar[1]])
- return self._observation
+ self._observation.extend([ballPosInCar[0], ballPosInCar[1]])
+ return self._observation
def step(self, action):
if (self._renders):
- basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ basePos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
if (self._isDiscrete):
- fwd = [-1,-1,-1,0,0,0,1,1,1]
- steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
- forward = fwd[action]
- steer = steerings[action]
- realaction = [forward,steer]
+ fwd = [-1, -1, -1, 0, 0, 0, 1, 1, 1]
+ steerings = [-0.6, 0, 0.6, -0.6, 0, 0.6, -0.6, 0, 0.6]
+ forward = fwd[action]
+ steer = steerings[action]
+ realaction = [forward, steer]
else:
realaction = action
@@ -142,35 +140,37 @@ class RacecarGymEnv(gym.Env):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
- base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
- view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
- cameraTargetPosition=base_pos,
- distance=self._cam_dist,
- yaw=self._cam_yaw,
- pitch=self._cam_pitch,
- roll=0,
- upAxisIndex=2)
- proj_matrix = self._p.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._p.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ base_pos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ view_matrix = self._p.computeViewMatrixFromYawPitchRoll(cameraTargetPosition=base_pos,
+ distance=self._cam_dist,
+ yaw=self._cam_yaw,
+ pitch=self._cam_pitch,
+ roll=0,
+ upAxisIndex=2)
+ proj_matrix = self._p.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) / RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _, _) = self._p.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3]
return rgb_array
-
def _termination(self):
- return self._envStepCounter>1000
+ return self._envStepCounter > 1000
def _reward(self):
- closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
+ closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId, self._ballUniqueId,
+ 10000)
numPt = len(closestPoints)
- reward=-1000
+ reward = -1000
#print(numPt)
- if (numPt>0):
+ if (numPt > 0):
#print("reward:")
reward = -closestPoints[0][8]
#print(reward)
diff --git a/examples/pybullet/gym/pybullet_envs/bullet/racecarZEDGymEnv.py b/examples/pybullet/gym/pybullet_envs/bullet/racecarZEDGymEnv.py
index 6a7ce3400..8137708ba 100644
--- a/examples/pybullet/gym/pybullet_envs/bullet/racecarZEDGymEnv.py
+++ b/examples/pybullet/gym/pybullet_envs/bullet/racecarZEDGymEnv.py
@@ -1,7 +1,7 @@
-import os, inspect
+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 math
import gym
@@ -19,11 +19,9 @@ from pkg_resources import parse_version
RENDER_HEIGHT = 720
RENDER_WIDTH = 960
+
class RacecarZEDGymEnv(gym.Env):
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second' : 50
- }
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 50}
def __init__(self,
urdfRoot=pybullet_data.getDataPath(),
@@ -44,8 +42,7 @@ class RacecarZEDGymEnv(gym.Env):
self._isDiscrete = isDiscrete
if self._renders:
- self._p = bullet_client.BulletClient(
- connection_mode=pybullet.GUI)
+ self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
self._p = bullet_client.BulletClient()
@@ -59,11 +56,14 @@ class RacecarZEDGymEnv(gym.Env):
if (isDiscrete):
self.action_space = spaces.Discrete(9)
else:
- action_dim = 2
- self._action_bound = 1
- action_high = np.array([self._action_bound] * action_dim)
- self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
- self.observation_space = spaces.Box(low=0, high=255, shape=(self._height, self._width, 4), dtype=np.uint8)
+ action_dim = 2
+ self._action_bound = 1
+ action_high = np.array([self._action_bound] * action_dim)
+ self.action_space = spaces.Box(-action_high, action_high, dtype=np.float32)
+ self.observation_space = spaces.Box(low=0,
+ high=255,
+ shape=(self._height, self._width, 4),
+ dtype=np.uint8)
self.viewer = None
@@ -72,23 +72,24 @@ class RacecarZEDGymEnv(gym.Env):
#p.setPhysicsEngineParameter(numSolverIterations=300)
self._p.setTimeStep(self._timeStep)
#self._p.loadURDF(os.path.join(os.path.dirname(__file__),"../data","plane.urdf"))
- stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot,"stadium.sdf"))
+ stadiumobjects = self._p.loadSDF(os.path.join(self._urdfRoot, "stadium.sdf"))
#move the stadium objects slightly above 0
for i in stadiumobjects:
- pos,orn = self._p.getBasePositionAndOrientation(i)
- newpos = [pos[0],pos[1],pos[2]+0.1]
- self._p.resetBasePositionAndOrientation(i,newpos,orn)
+ pos, orn = self._p.getBasePositionAndOrientation(i)
+ newpos = [pos[0], pos[1], pos[2] + 0.1]
+ self._p.resetBasePositionAndOrientation(i, newpos, orn)
- dist = 5 +2.*random.random()
- ang = 2.*3.1415925438*random.random()
+ dist = 5 + 2. * random.random()
+ ang = 2. * 3.1415925438 * random.random()
ballx = dist * math.sin(ang)
bally = dist * math.cos(ang)
ballz = 1
- self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2red.urdf"),[ballx,bally,ballz])
- self._p.setGravity(0,0,-10)
- self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
+ self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot, "sphere2red.urdf"),
+ [ballx, bally, ballz])
+ self._p.setGravity(0, 0, -10)
+ self._racecar = racecar.Racecar(self._p, urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
for i in range(100):
self._p.stepSimulation()
@@ -103,38 +104,50 @@ class RacecarZEDGymEnv(gym.Env):
return [seed]
def getExtendedObservation(self):
- carpos,carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
- carmat = self._p.getMatrixFromQuaternion(carorn)
- ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
- invCarPos,invCarOrn = self._p.invertTransform(carpos,carorn)
- ballPosInCar,ballOrnInCar = self._p.multiplyTransforms(invCarPos,invCarOrn,ballpos,ballorn)
- dist0 = 0.3
- dist1 = 1.
- eyePos = [carpos[0]+dist0*carmat[0],carpos[1]+dist0*carmat[3],carpos[2]+dist0*carmat[6]+0.3]
- targetPos = [carpos[0]+dist1*carmat[0],carpos[1]+dist1*carmat[3],carpos[2]+dist1*carmat[6]+0.3]
- up = [carmat[2],carmat[5],carmat[8]]
- viewMat = self._p.computeViewMatrix(eyePos,targetPos,up)
- #viewMat = self._p.computeViewMatrixFromYawPitchRoll(carpos,1,0,0,0,2)
- #print("projectionMatrix:")
- #print(self._p.getDebugVisualizerCamera()[3])
- projMatrix = [0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
- img_arr = self._p.getCameraImage(width=self._width,height=self._height,viewMatrix=viewMat,projectionMatrix=projMatrix)
- rgb=img_arr[2]
- np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
- self._observation = np_img_arr
- return self._observation
+ carpos, carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ carmat = self._p.getMatrixFromQuaternion(carorn)
+ ballpos, ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
+ invCarPos, invCarOrn = self._p.invertTransform(carpos, carorn)
+ ballPosInCar, ballOrnInCar = self._p.multiplyTransforms(invCarPos, invCarOrn, ballpos, ballorn)
+ dist0 = 0.3
+ dist1 = 1.
+ eyePos = [
+ carpos[0] + dist0 * carmat[0], carpos[1] + dist0 * carmat[3],
+ carpos[2] + dist0 * carmat[6] + 0.3
+ ]
+ targetPos = [
+ carpos[0] + dist1 * carmat[0], carpos[1] + dist1 * carmat[3],
+ carpos[2] + dist1 * carmat[6] + 0.3
+ ]
+ up = [carmat[2], carmat[5], carmat[8]]
+ viewMat = self._p.computeViewMatrix(eyePos, targetPos, up)
+ #viewMat = self._p.computeViewMatrixFromYawPitchRoll(carpos,1,0,0,0,2)
+ #print("projectionMatrix:")
+ #print(self._p.getDebugVisualizerCamera()[3])
+ projMatrix = [
+ 0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0,
+ 0.0, 0.0, -0.02000020071864128, 0.0
+ ]
+ img_arr = self._p.getCameraImage(width=self._width,
+ height=self._height,
+ viewMatrix=viewMat,
+ projectionMatrix=projMatrix)
+ rgb = img_arr[2]
+ np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
+ self._observation = np_img_arr
+ return self._observation
def step(self, action):
if (self._renders):
- basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ basePos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
if (self._isDiscrete):
- fwd = [-1,-1,-1,0,0,0,1,1,1]
- steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
- forward = fwd[action]
- steer = steerings[action]
- realaction = [forward,steer]
+ fwd = [-1, -1, -1, 0, 0, 0, 1, 1, 1]
+ steerings = [-0.6, 0, 0.6, -0.6, 0, 0.6, -0.6, 0, 0.6]
+ forward = fwd[action]
+ steer = steerings[action]
+ realaction = [forward, steer]
else:
realaction = action
@@ -157,35 +170,37 @@ class RacecarZEDGymEnv(gym.Env):
def render(self, mode='human', close=False):
if mode != "rgb_array":
return np.array([])
- base_pos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
- view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
- cameraTargetPosition=base_pos,
- distance=self._cam_dist,
- yaw=self._cam_yaw,
- pitch=self._cam_pitch,
- roll=0,
- upAxisIndex=2)
- proj_matrix = self._p.computeProjectionMatrixFOV(
- fov=60, aspect=float(RENDER_WIDTH)/RENDER_HEIGHT,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._p.getCameraImage(
- width=RENDER_WIDTH, height=RENDER_HEIGHT, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ base_pos, orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
+ view_matrix = self._p.computeViewMatrixFromYawPitchRoll(cameraTargetPosition=base_pos,
+ distance=self._cam_dist,
+ yaw=self._cam_yaw,
+ pitch=self._cam_pitch,
+ roll=0,
+ upAxisIndex=2)
+ proj_matrix = self._p.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) / RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _, _) = self._p.getCameraImage(width=RENDER_WIDTH,
+ height=RENDER_HEIGHT,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
rgb_array = np.array(px)
rgb_array = rgb_array[:, :, :3]
return rgb_array
-
def _termination(self):
- return self._envStepCounter>1000
+ return self._envStepCounter > 1000
def _reward(self):
- closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
+ closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId, self._ballUniqueId,
+ 10000)
numPt = len(closestPoints)
- reward=-1000
+ reward = -1000
#print(numPt)
- if (numPt>0):
+ if (numPt > 0):
#print("reward:")
reward = -closestPoints[0][8]
#print(reward)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/DeepMimic_Optimizer.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/DeepMimic_Optimizer.py
index 9aaeb2b90..b6e9e6607 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/DeepMimic_Optimizer.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/DeepMimic_Optimizer.py
@@ -4,11 +4,10 @@ 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)
-print("parentdir=",parentdir)
+os.sys.path.insert(0, parentdir)
+print("parentdir=", parentdir)
-
-from pybullet_envs.deep_mimic.env.pybullet_deep_mimic_env import PyBulletDeepMimicEnv
+from pybullet_envs.deep_mimic.env.pybullet_deep_mimic_env import PyBulletDeepMimicEnv
from pybullet_envs.deep_mimic.learning.rl_world import RLWorld
from pybullet_utils.logger import Logger
from pybullet_envs.deep_mimic.testrl import update_world, update_timestep, build_world
@@ -17,36 +16,40 @@ import pybullet_utils.mpi_util as MPIUtil
args = []
world = None
+
def run():
- global update_timestep
- global world
+ global update_timestep
+ global world
+
+ done = False
+ while not (done):
+ update_world(world, update_timestep)
- done = False
- while not (done):
- update_world(world, update_timestep)
+ return
- return
def shutdown():
- global world
+ global world
+
+ Logger.print2('Shutting down...')
+ world.shutdown()
+ return
- Logger.print2('Shutting down...')
- world.shutdown()
- return
def main():
- global args
- global world
+ global args
+ global world
+
+ # Command line arguments
+ args = sys.argv[1:]
+ enable_draw = False
+ world = build_world(args, enable_draw)
- # Command line arguments
- args = sys.argv[1:]
- enable_draw = False
- world = build_world(args, enable_draw)
+ run()
+ shutdown()
- run()
- shutdown()
+ return
- return
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/action_space.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/action_space.py
index 1014f7497..f28621417 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/action_space.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/action_space.py
@@ -1,6 +1,7 @@
from enum import Enum
+
class ActionSpace(Enum):
- Null = 0
- Continuous = 1
- Discrete = 2 \ No newline at end of file
+ Null = 0
+ Continuous = 1
+ Discrete = 2
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/env.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/env.py
index c8c17df5d..900702bdd 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/env.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/env.py
@@ -1,19 +1,21 @@
-from abc import abstractmethod
+from abc import abstractmethod
import sys, abc
if sys.version_info >= (3, 4):
- ABC = abc.ABC
+ ABC = abc.ABC
else:
- ABC = abc.ABCMeta('ABC', (), {})
+ ABC = abc.ABCMeta('ABC', (), {})
import numpy as np
from enum import Enum
+
class Env(ABC):
- class Terminate(Enum):
- Null = 0
- Fail = 1
- Succ = 2
-
- def __init__(self, args, enable_draw):
- self.enable_draw = enable_draw
- return
+
+ class Terminate(Enum):
+ Null = 0
+ Fail = 1
+ Succ = 2
+
+ def __init__(self, args, enable_draw):
+ self.enable_draw = enable_draw
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_pose_interpolator.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_pose_interpolator.py
index af0870ff5..15839ccf1 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_pose_interpolator.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_pose_interpolator.py
@@ -1,36 +1,61 @@
from pybullet_utils import bullet_client
import math
-
+
+
class HumanoidPoseInterpolator(object):
+
def __init__(self):
pass
-
- def Reset(self,basePos=[0,0,0], baseOrn=[0,0,0,1],chestRot=[0,0,0,1], neckRot=[0,0,0,1],rightHipRot= [0,0,0,1], rightKneeRot=[0],rightAnkleRot = [0,0,0,1],
- rightShoulderRot = [0,0,0,1],rightElbowRot = [0], leftHipRot = [0,0,0,1], leftKneeRot = [0],leftAnkleRot = [0,0,0,1],
- leftShoulderRot = [0,0,0,1] ,leftElbowRot = [0],
- baseLinVel = [0,0,0],baseAngVel = [0,0,0], chestVel = [0,0,0],neckVel = [0,0,0],rightHipVel = [0,0,0],rightKneeVel = [0],
- rightAnkleVel = [0,0,0],rightShoulderVel = [0,0,0],rightElbowVel = [0],leftHipVel = [0,0,0],leftKneeVel = [0],leftAnkleVel = [0,0,0],leftShoulderVel = [0,0,0],leftElbowVel = [0]
- ):
-
+
+ def Reset(self,
+ basePos=[0, 0, 0],
+ baseOrn=[0, 0, 0, 1],
+ chestRot=[0, 0, 0, 1],
+ neckRot=[0, 0, 0, 1],
+ rightHipRot=[0, 0, 0, 1],
+ rightKneeRot=[0],
+ rightAnkleRot=[0, 0, 0, 1],
+ rightShoulderRot=[0, 0, 0, 1],
+ rightElbowRot=[0],
+ leftHipRot=[0, 0, 0, 1],
+ leftKneeRot=[0],
+ leftAnkleRot=[0, 0, 0, 1],
+ leftShoulderRot=[0, 0, 0, 1],
+ leftElbowRot=[0],
+ baseLinVel=[0, 0, 0],
+ baseAngVel=[0, 0, 0],
+ chestVel=[0, 0, 0],
+ neckVel=[0, 0, 0],
+ rightHipVel=[0, 0, 0],
+ rightKneeVel=[0],
+ rightAnkleVel=[0, 0, 0],
+ rightShoulderVel=[0, 0, 0],
+ rightElbowVel=[0],
+ leftHipVel=[0, 0, 0],
+ leftKneeVel=[0],
+ leftAnkleVel=[0, 0, 0],
+ leftShoulderVel=[0, 0, 0],
+ leftElbowVel=[0]):
+
self._basePos = basePos
self._baseLinVel = baseLinVel
#print("HumanoidPoseInterpolator.Reset: baseLinVel = ", baseLinVel)
- self._baseOrn =baseOrn
+ self._baseOrn = baseOrn
self._baseAngVel = baseAngVel
-
+
self._chestRot = chestRot
- self._chestVel =chestVel
+ self._chestVel = chestVel
self._neckRot = neckRot
self._neckVel = neckVel
-
+
self._rightHipRot = rightHipRot
self._rightHipVel = rightHipVel
- self._rightKneeRot =rightKneeRot
+ self._rightKneeRot = rightKneeRot
self._rightKneeVel = rightKneeVel
self._rightAnkleRot = rightAnkleRot
self._rightAnkleVel = rightAnkleVel
-
- self._rightShoulderRot =rightShoulderRot
+
+ self._rightShoulderRot = rightShoulderRot
self._rightShoulderVel = rightShoulderVel
self._rightElbowRot = rightElbowRot
self._rightElbowVel = rightElbowVel
@@ -39,225 +64,253 @@ class HumanoidPoseInterpolator(object):
self._leftHipVel = leftHipVel
self._leftKneeRot = leftKneeRot
self._leftKneeVel = leftKneeVel
- self._leftAnkleRot =leftAnkleRot
+ self._leftAnkleRot = leftAnkleRot
self._leftAnkleVel = leftAnkleVel
-
+
self._leftShoulderRot = leftShoulderRot
self._leftShoulderVel = leftShoulderVel
- self._leftElbowRot =leftElbowRot
+ self._leftElbowRot = leftElbowRot
self._leftElbowVel = leftElbowVel
- def ComputeLinVel(self,posStart, posEnd, deltaTime):
- vel = [(posEnd[0]-posStart[0])/deltaTime,(posEnd[1]-posStart[1])/deltaTime,(posEnd[2]-posStart[2])/deltaTime]
+ def ComputeLinVel(self, posStart, posEnd, deltaTime):
+ vel = [(posEnd[0] - posStart[0]) / deltaTime, (posEnd[1] - posStart[1]) / deltaTime,
+ (posEnd[2] - posStart[2]) / deltaTime]
return vel
-
- def ComputeAngVel(self,ornStart, ornEnd, deltaTime, bullet_client):
- dorn = bullet_client.getDifferenceQuaternion(ornStart,ornEnd)
- axis,angle = bullet_client.getAxisAngleFromQuaternion(dorn)
- angVel = [(axis[0]*angle)/deltaTime,(axis[1]*angle)/deltaTime,(axis[2]*angle)/deltaTime]
+
+ def ComputeAngVel(self, ornStart, ornEnd, deltaTime, bullet_client):
+ dorn = bullet_client.getDifferenceQuaternion(ornStart, ornEnd)
+ axis, angle = bullet_client.getAxisAngleFromQuaternion(dorn)
+ angVel = [(axis[0] * angle) / deltaTime, (axis[1] * angle) / deltaTime,
+ (axis[2] * angle) / deltaTime]
return angVel
-
- def ComputeAngVelRel(self,ornStart, ornEnd, deltaTime, bullet_client):
- ornStartConjugate = [-ornStart[0],-ornStart[1],-ornStart[2],ornStart[3]]
- pos_diff, q_diff =bullet_client.multiplyTransforms([0,0,0], ornStartConjugate, [0,0,0], ornEnd)
- axis,angle = bullet_client.getAxisAngleFromQuaternion(q_diff)
- angVel = [(axis[0]*angle)/deltaTime,(axis[1]*angle)/deltaTime,(axis[2]*angle)/deltaTime]
+
+ def ComputeAngVelRel(self, ornStart, ornEnd, deltaTime, bullet_client):
+ ornStartConjugate = [-ornStart[0], -ornStart[1], -ornStart[2], ornStart[3]]
+ pos_diff, q_diff = bullet_client.multiplyTransforms([0, 0, 0], ornStartConjugate, [0, 0, 0],
+ ornEnd)
+ axis, angle = bullet_client.getAxisAngleFromQuaternion(q_diff)
+ angVel = [(axis[0] * angle) / deltaTime, (axis[1] * angle) / deltaTime,
+ (axis[2] * angle) / deltaTime]
return angVel
-
-
+
def NormalizeVector(self, vec):
- length2 = orn[0]*orn[0]+orn[1]*orn[1]+orn[2]*orn[2]
- if (length2>0):
+ length2 = orn[0] * orn[0] + orn[1] * orn[1] + orn[2] * orn[2]
+ if (length2 > 0):
length = math.sqrt(length2)
-
+
def NormalizeQuaternion(self, orn):
- length2 = orn[0]*orn[0]+orn[1]*orn[1]+orn[2]*orn[2]+orn[3]*orn[3]
- if (length2>0):
+ length2 = orn[0] * orn[0] + orn[1] * orn[1] + orn[2] * orn[2] + orn[3] * orn[3]
+ if (length2 > 0):
length = math.sqrt(length2)
- orn[0]/=length
- orn[1]/=length
- orn[2]/=length
- orn[3]/=length
+ orn[0] /= length
+ orn[1] /= length
+ orn[2] /= length
+ orn[3] /= length
return orn
-
+
#print("Normalize? length=",length)
-
def PostProcessMotionData(self, frameData):
- baseOrn1Start = [frameData[5],frameData[6], frameData[7],frameData[4]]
-
- chestRotStart = [frameData[9],frameData[10],frameData[11],frameData[8]]
-
- neckRotStart = [frameData[13],frameData[14],frameData[15],frameData[12]]
- rightHipRotStart = [frameData[17],frameData[18],frameData[19],frameData[16]]
- rightAnkleRotStart = [frameData[22],frameData[23],frameData[24],frameData[21]]
- rightShoulderRotStart = [frameData[26],frameData[27],frameData[28],frameData[25]]
- leftHipRotStart = [frameData[31],frameData[32],frameData[33],frameData[30]]
- leftAnkleRotStart = [frameData[36],frameData[37],frameData[38],frameData[35]]
- leftShoulderRotStart = [frameData[40],frameData[41],frameData[42],frameData[39]]
-
-
+ baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
+
+ chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]]
+
+ neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]]
+ rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]]
+ rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]]
+ rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]]
+ leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]]
+ leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]]
+ leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]]
+
def GetPose(self):
- pose = [ self._basePos[0],self._basePos[1],self._basePos[2],
- self._baseOrn[0],self._baseOrn[1],self._baseOrn[2],self._baseOrn[3],
- self._chestRot[0],self._chestRot[1],self._chestRot[2],self._chestRot[3],
- self._neckRot[0],self._neckRot[1],self._neckRot[2],self._neckRot[3],
- self._rightHipRot[0],self._rightHipRot[1],self._rightHipRot[2],self._rightHipRot[3],
- self._rightKneeRot[0],
- self._rightAnkleRot[0],self._rightAnkleRot[1],self._rightAnkleRot[2],self._rightAnkleRot[3],
- self._rightShoulderRot[0],self._rightShoulderRot[1],self._rightShoulderRot[2],self._rightShoulderRot[3],
- self._rightElbowRot[0],
- self._leftHipRot[0],self._leftHipRot[1],self._leftHipRot[2],self._leftHipRot[3],
- self._leftKneeRot[0],
- self._leftAnkleRot[0],self._leftAnkleRot[1],self._leftAnkleRot[2],self._leftAnkleRot[3],
- self._leftShoulderRot[0],self._leftShoulderRot[1],self._leftShoulderRot[2],self._leftShoulderRot[3],
- self._leftElbowRot[0] ]
- return pose
-
- def Slerp(self, frameFraction, frameData, frameDataNext,bullet_client ):
+ pose = [
+ self._basePos[0], self._basePos[1], self._basePos[2], self._baseOrn[0], self._baseOrn[1],
+ self._baseOrn[2], self._baseOrn[3], self._chestRot[0], self._chestRot[1],
+ self._chestRot[2], self._chestRot[3], self._neckRot[0], self._neckRot[1], self._neckRot[2],
+ self._neckRot[3], self._rightHipRot[0], self._rightHipRot[1], self._rightHipRot[2],
+ self._rightHipRot[3], self._rightKneeRot[0], self._rightAnkleRot[0],
+ self._rightAnkleRot[1], self._rightAnkleRot[2], self._rightAnkleRot[3],
+ self._rightShoulderRot[0], self._rightShoulderRot[1], self._rightShoulderRot[2],
+ self._rightShoulderRot[3], self._rightElbowRot[0], self._leftHipRot[0],
+ self._leftHipRot[1], self._leftHipRot[2], self._leftHipRot[3], self._leftKneeRot[0],
+ self._leftAnkleRot[0], self._leftAnkleRot[1], self._leftAnkleRot[2], self._leftAnkleRot[3],
+ self._leftShoulderRot[0], self._leftShoulderRot[1], self._leftShoulderRot[2],
+ self._leftShoulderRot[3], self._leftElbowRot[0]
+ ]
+ return pose
+
+ def Slerp(self, frameFraction, frameData, frameDataNext, bullet_client):
keyFrameDuration = frameData[0]
- basePos1Start = [frameData[1],frameData[2],frameData[3]]
- basePos1End = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._basePos = [basePos1Start[0]+frameFraction*(basePos1End[0]-basePos1Start[0]),
- basePos1Start[1]+frameFraction*(basePos1End[1]-basePos1Start[1]),
- basePos1Start[2]+frameFraction*(basePos1End[2]-basePos1Start[2])]
- self._baseLinVel = self.ComputeLinVel(basePos1Start,basePos1End, keyFrameDuration)
- baseOrn1Start = [frameData[5],frameData[6], frameData[7],frameData[4]]
- baseOrn1Next = [frameDataNext[5],frameDataNext[6], frameDataNext[7],frameDataNext[4]]
- self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start,baseOrn1Next,frameFraction)
- self._baseAngVel = self.ComputeAngVel(baseOrn1Start,baseOrn1Next, keyFrameDuration, bullet_client)
-
+ basePos1Start = [frameData[1], frameData[2], frameData[3]]
+ basePos1End = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._basePos = [
+ basePos1Start[0] + frameFraction * (basePos1End[0] - basePos1Start[0]),
+ basePos1Start[1] + frameFraction * (basePos1End[1] - basePos1Start[1]),
+ basePos1Start[2] + frameFraction * (basePos1End[2] - basePos1Start[2])
+ ]
+ self._baseLinVel = self.ComputeLinVel(basePos1Start, basePos1End, keyFrameDuration)
+ baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
+ baseOrn1Next = [frameDataNext[5], frameDataNext[6], frameDataNext[7], frameDataNext[4]]
+ self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start, baseOrn1Next, frameFraction)
+ self._baseAngVel = self.ComputeAngVel(baseOrn1Start, baseOrn1Next, keyFrameDuration,
+ bullet_client)
+
##pre-rotate to make z-up
#y2zPos=[0,0,0.0]
#y2zOrn = p.getQuaternionFromEuler([1.57,0,0])
#basePos,baseOrn = p.multiplyTransforms(y2zPos, y2zOrn,basePos1,baseOrn1)
- chestRotStart = [frameData[9],frameData[10],frameData[11],frameData[8]]
- chestRotEnd = [frameDataNext[9],frameDataNext[10],frameDataNext[11],frameDataNext[8]]
- self._chestRot = bullet_client.getQuaternionSlerp(chestRotStart,chestRotEnd,frameFraction)
- self._chestVel = self.ComputeAngVelRel(chestRotStart,chestRotEnd,keyFrameDuration,bullet_client)
-
- neckRotStart = [frameData[13],frameData[14],frameData[15],frameData[12]]
- neckRotEnd= [frameDataNext[13],frameDataNext[14],frameDataNext[15],frameDataNext[12]]
- self._neckRot = bullet_client.getQuaternionSlerp(neckRotStart,neckRotEnd,frameFraction)
- self._neckVel = self.ComputeAngVelRel(neckRotStart,neckRotEnd,keyFrameDuration,bullet_client)
-
- rightHipRotStart = [frameData[17],frameData[18],frameData[19],frameData[16]]
- rightHipRotEnd = [frameDataNext[17],frameDataNext[18],frameDataNext[19],frameDataNext[16]]
- self._rightHipRot = bullet_client.getQuaternionSlerp(rightHipRotStart,rightHipRotEnd,frameFraction)
- self._rightHipVel = self.ComputeAngVelRel(rightHipRotStart,rightHipRotEnd,keyFrameDuration,bullet_client)
-
+ chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]]
+ chestRotEnd = [frameDataNext[9], frameDataNext[10], frameDataNext[11], frameDataNext[8]]
+ self._chestRot = bullet_client.getQuaternionSlerp(chestRotStart, chestRotEnd, frameFraction)
+ self._chestVel = self.ComputeAngVelRel(chestRotStart, chestRotEnd, keyFrameDuration,
+ bullet_client)
+
+ neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]]
+ neckRotEnd = [frameDataNext[13], frameDataNext[14], frameDataNext[15], frameDataNext[12]]
+ self._neckRot = bullet_client.getQuaternionSlerp(neckRotStart, neckRotEnd, frameFraction)
+ self._neckVel = self.ComputeAngVelRel(neckRotStart, neckRotEnd, keyFrameDuration,
+ bullet_client)
+
+ rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]]
+ rightHipRotEnd = [frameDataNext[17], frameDataNext[18], frameDataNext[19], frameDataNext[16]]
+ self._rightHipRot = bullet_client.getQuaternionSlerp(rightHipRotStart, rightHipRotEnd,
+ frameFraction)
+ self._rightHipVel = self.ComputeAngVelRel(rightHipRotStart, rightHipRotEnd, keyFrameDuration,
+ bullet_client)
+
rightKneeRotStart = [frameData[20]]
rightKneeRotEnd = [frameDataNext[20]]
- self._rightKneeRot = [rightKneeRotStart[0]+frameFraction*(rightKneeRotEnd[0]-rightKneeRotStart[0])]
- self._rightKneeVel = [(rightKneeRotEnd[0]-rightKneeRotStart[0])/keyFrameDuration]
-
- rightAnkleRotStart = [frameData[22],frameData[23],frameData[24],frameData[21]]
- rightAnkleRotEnd = [frameDataNext[22],frameDataNext[23],frameDataNext[24],frameDataNext[21]]
- self._rightAnkleRot = bullet_client.getQuaternionSlerp(rightAnkleRotStart,rightAnkleRotEnd,frameFraction)
- self._rightAnkleVel = self.ComputeAngVelRel(rightAnkleRotStart,rightAnkleRotEnd,keyFrameDuration,bullet_client)
-
- rightShoulderRotStart = [frameData[26],frameData[27],frameData[28],frameData[25]]
- rightShoulderRotEnd = [frameDataNext[26],frameDataNext[27],frameDataNext[28],frameDataNext[25]]
- self._rightShoulderRot = bullet_client.getQuaternionSlerp(rightShoulderRotStart,rightShoulderRotEnd,frameFraction)
- self._rightShoulderVel = self.ComputeAngVelRel(rightShoulderRotStart,rightShoulderRotEnd, keyFrameDuration,bullet_client)
-
+ self._rightKneeRot = [
+ rightKneeRotStart[0] + frameFraction * (rightKneeRotEnd[0] - rightKneeRotStart[0])
+ ]
+ self._rightKneeVel = [(rightKneeRotEnd[0] - rightKneeRotStart[0]) / keyFrameDuration]
+
+ rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]]
+ rightAnkleRotEnd = [frameDataNext[22], frameDataNext[23], frameDataNext[24], frameDataNext[21]]
+ self._rightAnkleRot = bullet_client.getQuaternionSlerp(rightAnkleRotStart, rightAnkleRotEnd,
+ frameFraction)
+ self._rightAnkleVel = self.ComputeAngVelRel(rightAnkleRotStart, rightAnkleRotEnd,
+ keyFrameDuration, bullet_client)
+
+ rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]]
+ rightShoulderRotEnd = [
+ frameDataNext[26], frameDataNext[27], frameDataNext[28], frameDataNext[25]
+ ]
+ self._rightShoulderRot = bullet_client.getQuaternionSlerp(rightShoulderRotStart,
+ rightShoulderRotEnd, frameFraction)
+ self._rightShoulderVel = self.ComputeAngVelRel(rightShoulderRotStart, rightShoulderRotEnd,
+ keyFrameDuration, bullet_client)
+
rightElbowRotStart = [frameData[29]]
rightElbowRotEnd = [frameDataNext[29]]
- self._rightElbowRot = [rightElbowRotStart[0]+frameFraction*(rightElbowRotEnd[0]-rightElbowRotStart[0])]
- self._rightElbowVel = [(rightElbowRotEnd[0]-rightElbowRotStart[0])/keyFrameDuration]
-
- leftHipRotStart = [frameData[31],frameData[32],frameData[33],frameData[30]]
- leftHipRotEnd = [frameDataNext[31],frameDataNext[32],frameDataNext[33],frameDataNext[30]]
- self._leftHipRot = bullet_client.getQuaternionSlerp(leftHipRotStart,leftHipRotEnd,frameFraction)
- self._leftHipVel = self.ComputeAngVelRel(leftHipRotStart, leftHipRotEnd,keyFrameDuration,bullet_client)
-
+ self._rightElbowRot = [
+ rightElbowRotStart[0] + frameFraction * (rightElbowRotEnd[0] - rightElbowRotStart[0])
+ ]
+ self._rightElbowVel = [(rightElbowRotEnd[0] - rightElbowRotStart[0]) / keyFrameDuration]
+
+ leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]]
+ leftHipRotEnd = [frameDataNext[31], frameDataNext[32], frameDataNext[33], frameDataNext[30]]
+ self._leftHipRot = bullet_client.getQuaternionSlerp(leftHipRotStart, leftHipRotEnd,
+ frameFraction)
+ self._leftHipVel = self.ComputeAngVelRel(leftHipRotStart, leftHipRotEnd, keyFrameDuration,
+ bullet_client)
+
leftKneeRotStart = [frameData[34]]
leftKneeRotEnd = [frameDataNext[34]]
- self._leftKneeRot = [leftKneeRotStart[0] +frameFraction*(leftKneeRotEnd[0]-leftKneeRotStart[0]) ]
- self._leftKneeVel = [(leftKneeRotEnd[0]-leftKneeRotStart[0])/keyFrameDuration]
-
- leftAnkleRotStart = [frameData[36],frameData[37],frameData[38],frameData[35]]
- leftAnkleRotEnd = [frameDataNext[36],frameDataNext[37],frameDataNext[38],frameDataNext[35]]
- self._leftAnkleRot = bullet_client.getQuaternionSlerp(leftAnkleRotStart,leftAnkleRotEnd,frameFraction)
- self._leftAnkleVel = self.ComputeAngVelRel(leftAnkleRotStart,leftAnkleRotEnd,keyFrameDuration,bullet_client)
-
- leftShoulderRotStart = [frameData[40],frameData[41],frameData[42],frameData[39]]
- leftShoulderRotEnd = [frameDataNext[40],frameDataNext[41],frameDataNext[42],frameDataNext[39]]
- self._leftShoulderRot = bullet_client.getQuaternionSlerp(leftShoulderRotStart,leftShoulderRotEnd,frameFraction)
- self._leftShoulderVel = self.ComputeAngVelRel(leftShoulderRotStart,leftShoulderRotEnd,keyFrameDuration,bullet_client)
+ self._leftKneeRot = [
+ leftKneeRotStart[0] + frameFraction * (leftKneeRotEnd[0] - leftKneeRotStart[0])
+ ]
+ self._leftKneeVel = [(leftKneeRotEnd[0] - leftKneeRotStart[0]) / keyFrameDuration]
+
+ leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]]
+ leftAnkleRotEnd = [frameDataNext[36], frameDataNext[37], frameDataNext[38], frameDataNext[35]]
+ self._leftAnkleRot = bullet_client.getQuaternionSlerp(leftAnkleRotStart, leftAnkleRotEnd,
+ frameFraction)
+ self._leftAnkleVel = self.ComputeAngVelRel(leftAnkleRotStart, leftAnkleRotEnd,
+ keyFrameDuration, bullet_client)
+
+ leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]]
+ leftShoulderRotEnd = [
+ frameDataNext[40], frameDataNext[41], frameDataNext[42], frameDataNext[39]
+ ]
+ self._leftShoulderRot = bullet_client.getQuaternionSlerp(leftShoulderRotStart,
+ leftShoulderRotEnd, frameFraction)
+ self._leftShoulderVel = self.ComputeAngVelRel(leftShoulderRotStart, leftShoulderRotEnd,
+ keyFrameDuration, bullet_client)
leftElbowRotStart = [frameData[43]]
leftElbowRotEnd = [frameDataNext[43]]
- self._leftElbowRot = [leftElbowRotStart[0]+frameFraction*(leftElbowRotEnd[0]-leftElbowRotStart[0])]
- self._leftElbowVel = [(leftElbowRotEnd[0]-leftElbowRotStart[0])/keyFrameDuration]
+ self._leftElbowRot = [
+ leftElbowRotStart[0] + frameFraction * (leftElbowRotEnd[0] - leftElbowRotStart[0])
+ ]
+ self._leftElbowVel = [(leftElbowRotEnd[0] - leftElbowRotStart[0]) / keyFrameDuration]
pose = self.GetPose()
return pose
-
+
def ConvertFromAction(self, pybullet_client, action):
#turn action into pose
-
- self.Reset()#?? needed?
- index=0
+
+ self.Reset() #?? needed?
+ index = 0
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._chestRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._chestRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
#print("pose._chestRot=",pose._chestRot)
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._neckRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._neckRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._rightHipRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._rightHipRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
self._rightKneeRot = [angle]
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._rightAnkleRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._rightAnkleRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._rightShoulderRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._rightShoulderRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
self._rightElbowRot = [angle]
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._leftHipRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._leftHipRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
self._leftKneeRot = [angle]
-
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._leftAnkleRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._leftAnkleRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- self._leftShoulderRot = pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ self._leftShoulderRot = pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
self._leftElbowRot = [angle]
-
+
pose = self.GetPose()
return pose
-
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py
index 9418dd4bd..1a39a91cb 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py
@@ -1,144 +1,222 @@
-
-from pybullet_utils import pd_controller_stable
+from pybullet_utils import pd_controller_stable
from pybullet_envs.deep_mimic.env import humanoid_pose_interpolator
import math
-chest=1
-neck=2
-rightHip=3
-rightKnee=4
-rightAnkle=5
-rightShoulder=6
-rightElbow=7
-leftHip=9
-leftKnee=10
-leftAnkle=11
-leftShoulder=12
-leftElbow=13
+chest = 1
+neck = 2
+rightHip = 3
+rightKnee = 4
+rightAnkle = 5
+rightShoulder = 6
+rightElbow = 7
+leftHip = 9
+leftKnee = 10
+leftAnkle = 11
+leftShoulder = 12
+leftElbow = 13
jointFrictionForce = 0
+
class HumanoidStablePD(object):
+
def __init__(self, pybullet_client, mocap_data, timeStep, useFixedBase=True):
self._pybullet_client = pybullet_client
self._mocap_data = mocap_data
print("LOADING humanoid!")
-
+
self._sim_model = self._pybullet_client.loadURDF(
- "humanoid/humanoid.urdf", [0,0.889540259,0],globalScaling=0.25, useFixedBase=useFixedBase, flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER)
+ "humanoid/humanoid.urdf", [0, 0.889540259, 0],
+ globalScaling=0.25,
+ useFixedBase=useFixedBase,
+ flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER)
#self._pybullet_client.setCollisionFilterGroupMask(self._sim_model,-1,collisionFilterGroup=0,collisionFilterMask=0)
#for j in range (self._pybullet_client.getNumJoints(self._sim_model)):
# self._pybullet_client.setCollisionFilterGroupMask(self._sim_model,j,collisionFilterGroup=0,collisionFilterMask=0)
-
-
- self._end_effectors = [5,8,11,14] #ankle and wrist, both left and right
-
+
+ self._end_effectors = [5, 8, 11, 14] #ankle and wrist, both left and right
+
self._kin_model = self._pybullet_client.loadURDF(
- "humanoid/humanoid.urdf", [0,0.85,0],globalScaling=0.25, useFixedBase=True, flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER)
-
+ "humanoid/humanoid.urdf", [0, 0.85, 0],
+ globalScaling=0.25,
+ useFixedBase=True,
+ flags=self._pybullet_client.URDF_MAINTAIN_LINK_ORDER)
+
self._pybullet_client.changeDynamics(self._sim_model, -1, lateralFriction=0.9)
- for j in range (self._pybullet_client.getNumJoints(self._sim_model)):
+ for j in range(self._pybullet_client.getNumJoints(self._sim_model)):
self._pybullet_client.changeDynamics(self._sim_model, j, lateralFriction=0.9)
-
+
self._pybullet_client.changeDynamics(self._sim_model, -1, linearDamping=0, angularDamping=0)
self._pybullet_client.changeDynamics(self._kin_model, -1, linearDamping=0, angularDamping=0)
-
+
#todo: add feature to disable simulation for a particular object. Until then, disable all collisions
- self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,-1,collisionFilterGroup=0,collisionFilterMask=0)
- self._pybullet_client.changeDynamics(self._kin_model,-1,activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP+self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING+self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
+ self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,
+ -1,
+ collisionFilterGroup=0,
+ collisionFilterMask=0)
+ self._pybullet_client.changeDynamics(
+ self._kin_model,
+ -1,
+ activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP +
+ self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING +
+ self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
alpha = 0.4
- self._pybullet_client.changeVisualShape(self._kin_model,-1, rgbaColor=[1,1,1,alpha])
- for j in range (self._pybullet_client.getNumJoints(self._kin_model)):
- self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,j,collisionFilterGroup=0,collisionFilterMask=0)
- self._pybullet_client.changeDynamics(self._kin_model,j,activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP+self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING+self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
- self._pybullet_client.changeVisualShape(self._kin_model,j, rgbaColor=[1,1,1,alpha])
-
-
+ self._pybullet_client.changeVisualShape(self._kin_model, -1, rgbaColor=[1, 1, 1, alpha])
+ for j in range(self._pybullet_client.getNumJoints(self._kin_model)):
+ self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,
+ j,
+ collisionFilterGroup=0,
+ collisionFilterMask=0)
+ self._pybullet_client.changeDynamics(
+ self._kin_model,
+ j,
+ activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP +
+ self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING +
+ self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
+ self._pybullet_client.changeVisualShape(self._kin_model, j, rgbaColor=[1, 1, 1, alpha])
+
self._poseInterpolator = humanoid_pose_interpolator.HumanoidPoseInterpolator()
-
- for i in range (self._mocap_data.NumFrames()-1):
+
+ for i in range(self._mocap_data.NumFrames() - 1):
frameData = self._mocap_data._motion_data['Frames'][i]
self._poseInterpolator.PostProcessMotionData(frameData)
-
+
self._stablePD = pd_controller_stable.PDControllerStableMultiDof(self._pybullet_client)
self._timeStep = timeStep
- self._kpOrg = [0,0,0,0,0,0,0,1000,1000,1000,1000,100,100,100,100,500,500,500,500,500,400,400,400,400,400,400,400,400,300,500,500,500,500,500,400,400,400,400,400,400,400,400,300]
- self._kdOrg = [0,0,0,0,0,0,0,100,100,100,100,10,10,10,10,50,50,50,50,50,40,40,40,40,40,40,40,40,30,50,50,50,50,50,40,40,40,40,40,40,40,40,30]
-
- self._jointIndicesAll = [chest,neck, rightHip,rightKnee,rightAnkle,rightShoulder,rightElbow,leftHip,leftKnee,leftAnkle,leftShoulder,leftElbow]
+ self._kpOrg = [
+ 0, 0, 0, 0, 0, 0, 0, 1000, 1000, 1000, 1000, 100, 100, 100, 100, 500, 500, 500, 500, 500,
+ 400, 400, 400, 400, 400, 400, 400, 400, 300, 500, 500, 500, 500, 500, 400, 400, 400, 400,
+ 400, 400, 400, 400, 300
+ ]
+ self._kdOrg = [
+ 0, 0, 0, 0, 0, 0, 0, 100, 100, 100, 100, 10, 10, 10, 10, 50, 50, 50, 50, 50, 40, 40, 40,
+ 40, 40, 40, 40, 40, 30, 50, 50, 50, 50, 50, 40, 40, 40, 40, 40, 40, 40, 40, 30
+ ]
+
+ self._jointIndicesAll = [
+ chest, neck, rightHip, rightKnee, rightAnkle, rightShoulder, rightElbow, leftHip, leftKnee,
+ leftAnkle, leftShoulder, leftElbow
+ ]
for j in self._jointIndicesAll:
#self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, j, self._pybullet_client.POSITION_CONTROL, force=[1,1,1])
- self._pybullet_client.setJointMotorControl2(self._sim_model, j, self._pybullet_client.POSITION_CONTROL, targetPosition=0, positionGain=0, targetVelocity=0,force=jointFrictionForce)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, j, self._pybullet_client.POSITION_CONTROL,targetPosition=[0,0,0,1], targetVelocity=[0,0,0], positionGain=0,velocityGain=1,force=[jointFrictionForce,jointFrictionForce,jointFrictionForce])
- self._pybullet_client.setJointMotorControl2(self._kin_model, j, self._pybullet_client.POSITION_CONTROL, targetPosition=0, positionGain=0, targetVelocity=0,force=0)
- self._pybullet_client.setJointMotorControlMultiDof(self._kin_model, j, self._pybullet_client.POSITION_CONTROL,targetPosition=[0,0,0,1], targetVelocity=[0,0,0], positionGain=0,velocityGain=1,force=[jointFrictionForce,jointFrictionForce,0])
-
- self._jointDofCounts=[4,4,4,1,4,4,1,4,1,4,4,1]
-
+ self._pybullet_client.setJointMotorControl2(self._sim_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=0,
+ positionGain=0,
+ targetVelocity=0,
+ force=jointFrictionForce)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=[0, 0, 0, 1],
+ targetVelocity=[0, 0, 0],
+ positionGain=0,
+ velocityGain=1,
+ force=[jointFrictionForce, jointFrictionForce, jointFrictionForce])
+ self._pybullet_client.setJointMotorControl2(self._kin_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=0,
+ positionGain=0,
+ targetVelocity=0,
+ force=0)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._kin_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=[0, 0, 0, 1],
+ targetVelocity=[0, 0, 0],
+ positionGain=0,
+ velocityGain=1,
+ force=[jointFrictionForce, jointFrictionForce, 0])
+
+ self._jointDofCounts = [4, 4, 4, 1, 4, 4, 1, 4, 1, 4, 4, 1]
+
#only those body parts/links are allowed to touch the ground, otherwise the episode terminates
- self._allowed_body_parts=[5,11]
-
+ self._allowed_body_parts = [5, 11]
+
#[x,y,z] base position and [x,y,z,w] base orientation!
- self._totalDofs = 7
+ self._totalDofs = 7
for dof in self._jointDofCounts:
self._totalDofs += dof
self.setSimTime(0)
-
+
self.resetPose()
-
+
def resetPose(self):
#print("resetPose with self._frame=", self._frame, " and self._frameFraction=",self._frameFraction)
pose = self.computePose(self._frameFraction)
self.initializePose(self._poseInterpolator, self._sim_model, initBase=True)
self.initializePose(self._poseInterpolator, self._kin_model, initBase=False)
-
- def initializePose(self, pose, phys_model,initBase, initializeVelocity = True):
-
+
+ def initializePose(self, pose, phys_model, initBase, initializeVelocity=True):
+
if initializeVelocity:
if initBase:
- self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos, pose._baseOrn)
+ self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos,
+ pose._baseOrn)
self._pybullet_client.resetBaseVelocity(phys_model, pose._baseLinVel, pose._baseAngVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,chest,pose._chestRot, pose._chestVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,neck,pose._neckRot, pose._neckVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightHip,pose._rightHipRot, pose._rightHipVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightKnee,pose._rightKneeRot, pose._rightKneeVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightAnkle,pose._rightAnkleRot, pose._rightAnkleVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightShoulder,pose._rightShoulderRot, pose._rightShoulderVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightElbow, pose._rightElbowRot, pose._rightElbowVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftHip, pose._leftHipRot, pose._leftHipVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftKnee, pose._leftKneeRot, pose._leftKneeVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftAnkle, pose._leftAnkleRot, pose._leftAnkleVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftShoulder, pose._leftShoulderRot, pose._leftShoulderVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftElbow, pose._leftElbowRot, pose._leftElbowVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, chest, pose._chestRot,
+ pose._chestVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, neck, pose._neckRot, pose._neckVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightHip, pose._rightHipRot,
+ pose._rightHipVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightKnee, pose._rightKneeRot,
+ pose._rightKneeVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightAnkle, pose._rightAnkleRot,
+ pose._rightAnkleVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightShoulder,
+ pose._rightShoulderRot, pose._rightShoulderVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightElbow, pose._rightElbowRot,
+ pose._rightElbowVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftHip, pose._leftHipRot,
+ pose._leftHipVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftKnee, pose._leftKneeRot,
+ pose._leftKneeVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftAnkle, pose._leftAnkleRot,
+ pose._leftAnkleVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftShoulder,
+ pose._leftShoulderRot, pose._leftShoulderVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftElbow, pose._leftElbowRot,
+ pose._leftElbowVel)
else:
if initBase:
- self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos, pose._baseOrn)
- self._pybullet_client.resetJointStateMultiDof(phys_model,chest,pose._chestRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,neck,pose._neckRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightHip,pose._rightHipRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightKnee,pose._rightKneeRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightAnkle,pose._rightAnkleRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightShoulder,pose._rightShoulderRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightElbow, pose._rightElbowRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftHip, pose._leftHipRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftKnee, pose._leftKneeRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftAnkle, pose._leftAnkleRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftShoulder, pose._leftShoulderRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftElbow, pose._leftElbowRot, [0])
+ self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos,
+ pose._baseOrn)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, chest, pose._chestRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, neck, pose._neckRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightHip, pose._rightHipRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightKnee, pose._rightKneeRot, [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightAnkle, pose._rightAnkleRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightShoulder,
+ pose._rightShoulderRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightElbow, pose._rightElbowRot,
+ [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftHip, pose._leftHipRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftKnee, pose._leftKneeRot, [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftAnkle, pose._leftAnkleRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftShoulder,
+ pose._leftShoulderRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftElbow, pose._leftElbowRot, [0])
def calcCycleCount(self, simTime, cycleTime):
- phases = simTime / cycleTime;
+ phases = simTime / cycleTime
count = math.floor(phases)
loop = True
#count = (loop) ? count : cMathUtil::Clamp(count, 0, 1);
return count
-
def getCycleTime(self):
keyFrameDuration = self._mocap_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._mocap_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._mocap_data.NumFrames() - 1)
return cycleTime
-
+
def setSimTime(self, t):
self._simTime = t
#print("SetTimeTime time =",t)
@@ -147,163 +225,266 @@ class HumanoidStablePD(object):
#print("self._motion_data.NumFrames()=",self._mocap_data.NumFrames())
self._cycleCount = self.calcCycleCount(t, cycleTime)
#print("cycles=",cycles)
- frameTime = t - self._cycleCount*cycleTime
- if (frameTime<0):
+ frameTime = t - self._cycleCount * cycleTime
+ if (frameTime < 0):
frameTime += cycleTime
-
- #print("keyFrameDuration=",keyFrameDuration)
+
+ #print("keyFrameDuration=",keyFrameDuration)
#print("frameTime=",frameTime)
- self._frame = int(frameTime/keyFrameDuration)
+ self._frame = int(frameTime / keyFrameDuration)
#print("self._frame=",self._frame)
-
- self._frameNext = self._frame+1
- if (self._frameNext >= self._mocap_data.NumFrames()):
+
+ self._frameNext = self._frame + 1
+ if (self._frameNext >= self._mocap_data.NumFrames()):
self._frameNext = self._frame
- self._frameFraction = (frameTime - self._frame*keyFrameDuration)/(keyFrameDuration)
-
-
+ self._frameFraction = (frameTime - self._frame * keyFrameDuration) / (keyFrameDuration)
+
def computeCycleOffset(self):
- firstFrame=0
- lastFrame = self._mocap_data.NumFrames()-1
+ firstFrame = 0
+ lastFrame = self._mocap_data.NumFrames() - 1
frameData = self._mocap_data._motion_data['Frames'][0]
frameDataNext = self._mocap_data._motion_data['Frames'][lastFrame]
-
- basePosStart = [frameData[1],frameData[2],frameData[3]]
- basePosEnd = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._cycleOffset = [basePosEnd[0]-basePosStart[0],basePosEnd[1]-basePosStart[1],basePosEnd[2]-basePosStart[2]]
+
+ basePosStart = [frameData[1], frameData[2], frameData[3]]
+ basePosEnd = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._cycleOffset = [
+ basePosEnd[0] - basePosStart[0], basePosEnd[1] - basePosStart[1],
+ basePosEnd[2] - basePosStart[2]
+ ]
return self._cycleOffset
-
+
def computePose(self, frameFraction):
frameData = self._mocap_data._motion_data['Frames'][self._frame]
frameDataNext = self._mocap_data._motion_data['Frames'][self._frameNext]
-
+
self._poseInterpolator.Slerp(frameFraction, frameData, frameDataNext, self._pybullet_client)
#print("self._poseInterpolator.Slerp(", frameFraction,")=", pose)
self.computeCycleOffset()
oldPos = self._poseInterpolator._basePos
- self._poseInterpolator._basePos = [oldPos[0]+self._cycleCount*self._cycleOffset[0],oldPos[1]+self._cycleCount*self._cycleOffset[1],oldPos[2]+self._cycleCount*self._cycleOffset[2]]
+ self._poseInterpolator._basePos = [
+ oldPos[0] + self._cycleCount * self._cycleOffset[0],
+ oldPos[1] + self._cycleCount * self._cycleOffset[1],
+ oldPos[2] + self._cycleCount * self._cycleOffset[2]
+ ]
pose = self._poseInterpolator.GetPose()
-
- return pose
+ return pose
def convertActionToPose(self, action):
pose = self._poseInterpolator.ConvertFromAction(self._pybullet_client, action)
- return pose
+ return pose
def computePDForces(self, desiredPositions, desiredVelocities, maxForces):
- if desiredVelocities==None:
- desiredVelocities = [0]*self._totalDofs
-
-
- taus = self._stablePD.computePD(bodyUniqueId=self._sim_model,
- jointIndices = self._jointIndicesAll,
- desiredPositions = desiredPositions,
- desiredVelocities = desiredVelocities,
- kps = self._kpOrg,
- kds = self._kdOrg,
- maxForces = maxForces,
- timeStep=self._timeStep)
+ if desiredVelocities == None:
+ desiredVelocities = [0] * self._totalDofs
+
+ taus = self._stablePD.computePD(bodyUniqueId=self._sim_model,
+ jointIndices=self._jointIndicesAll,
+ desiredPositions=desiredPositions,
+ desiredVelocities=desiredVelocities,
+ kps=self._kpOrg,
+ kds=self._kdOrg,
+ maxForces=maxForces,
+ timeStep=self._timeStep)
return taus
def applyPDForces(self, taus):
- dofIndex=7
+ dofIndex = 7
scaling = 1
- for index in range (len(self._jointIndicesAll)):
+ for index in range(len(self._jointIndicesAll)):
jointIndex = self._jointIndicesAll[index]
- if self._jointDofCounts[index]==4:
- force=[scaling*taus[dofIndex+0],scaling*taus[dofIndex+1],scaling*taus[dofIndex+2]]
- #print("force[", jointIndex,"]=",force)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,jointIndex,self._pybullet_client.TORQUE_CONTROL,force=force)
- if self._jointDofCounts[index]==1:
- force=[scaling*taus[dofIndex]]
- #print("force[", jointIndex,"]=",force)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, jointIndex, controlMode=self._pybullet_client.TORQUE_CONTROL, force=force)
- dofIndex+=self._jointDofCounts[index]
-
+ if self._jointDofCounts[index] == 4:
+ force = [
+ scaling * taus[dofIndex + 0], scaling * taus[dofIndex + 1],
+ scaling * taus[dofIndex + 2]
+ ]
+ #print("force[", jointIndex,"]=",force)
+ self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,
+ jointIndex,
+ self._pybullet_client.TORQUE_CONTROL,
+ force=force)
+ if self._jointDofCounts[index] == 1:
+ force = [scaling * taus[dofIndex]]
+ #print("force[", jointIndex,"]=",force)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ jointIndex,
+ controlMode=self._pybullet_client.TORQUE_CONTROL,
+ force=force)
+ dofIndex += self._jointDofCounts[index]
+
def setJointMotors(self, desiredPositions, maxForces):
controlMode = self._pybullet_client.POSITION_CONTROL
- startIndex=7
- chest=1
- neck=2
- rightHip=3
- rightKnee=4
- rightAnkle=5
- rightShoulder=6
- rightElbow=7
- leftHip=9
- leftKnee=10
- leftAnkle=11
- leftShoulder=12
- leftElbow=13
+ startIndex = 7
+ chest = 1
+ neck = 2
+ rightHip = 3
+ rightKnee = 4
+ rightAnkle = 5
+ rightShoulder = 6
+ rightElbow = 7
+ leftHip = 9
+ leftKnee = 10
+ leftAnkle = 11
+ leftShoulder = 12
+ leftElbow = 13
kp = 0.2
-
- forceScale=1
+
+ forceScale = 1
#self._jointDofCounts=[4,4,4,1,4,4,1,4,1,4,4,1]
- maxForce = [forceScale*maxForces[startIndex],forceScale*maxForces[startIndex+1],forceScale*maxForces[startIndex+2],forceScale*maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,chest,controlMode, targetPosition=self._poseInterpolator._chestRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,neck,controlMode,targetPosition=self._poseInterpolator._neckRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightHip,controlMode,targetPosition=self._poseInterpolator._rightHipRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightKnee,controlMode,targetPosition=self._poseInterpolator._rightKneeRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightAnkle,controlMode,targetPosition=self._poseInterpolator._rightAnkleRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex],forceScale*maxForces[startIndex+1],forceScale*maxForces[startIndex+2],forceScale*maxForces[startIndex+3]]
- startIndex+=4
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightElbow, controlMode,targetPosition=self._poseInterpolator._rightElbowRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftHip, controlMode,targetPosition=self._poseInterpolator._leftHipRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftKnee, controlMode,targetPosition=self._poseInterpolator._leftKneeRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftAnkle, controlMode,targetPosition=self._poseInterpolator._leftAnkleRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftShoulder, controlMode,targetPosition=self._poseInterpolator._leftShoulderRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftElbow, controlMode,targetPosition=self._poseInterpolator._leftElbowRot,positionGain=kp, force=maxForce)
+ maxForce = [
+ forceScale * maxForces[startIndex], forceScale * maxForces[startIndex + 1],
+ forceScale * maxForces[startIndex + 2], forceScale * maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ chest,
+ controlMode,
+ targetPosition=self._poseInterpolator._chestRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ neck,
+ controlMode,
+ targetPosition=self._poseInterpolator._neckRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightHip,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightHipRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightKnee,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightKneeRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightAnkle,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightAnkleRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ forceScale * maxForces[startIndex], forceScale * maxForces[startIndex + 1],
+ forceScale * maxForces[startIndex + 2], forceScale * maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightElbow,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightElbowRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftHip,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftHipRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftKnee,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftKneeRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftAnkle,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftAnkleRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftShoulder,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftShoulderRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftElbow,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftElbowRot,
+ positionGain=kp,
+ force=maxForce)
#print("startIndex=",startIndex)
-
+
def getPhase(self):
keyFrameDuration = self._mocap_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._mocap_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._mocap_data.NumFrames() - 1)
phase = self._simTime / cycleTime
- phase = math.fmod(phase,1.0)
- if (phase<0):
+ phase = math.fmod(phase, 1.0)
+ if (phase < 0):
phase += 1
return phase
def buildHeadingTrans(self, rootOrn):
#align root transform 'forward' with world-space x axis
eul = self._pybullet_client.getEulerFromQuaternion(rootOrn)
- refDir = [1,0,0]
+ refDir = [1, 0, 0]
rotVec = self._pybullet_client.rotateVector(rootOrn, refDir)
heading = math.atan2(-rotVec[2], rotVec[0])
- heading2=eul[1]
+ heading2 = eul[1]
#print("heading=",heading)
- headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0,1,0],-heading)
+ headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0, 1, 0], -heading)
return headingOrn
-
def buildOriginTrans(self):
- rootPos,rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
-
+ rootPos, rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+
#print("rootPos=",rootPos, " rootOrn=",rootOrn)
- invRootPos=[-rootPos[0], 0, -rootPos[2]]
+ invRootPos = [-rootPos[0], 0, -rootPos[2]]
#invOrigTransPos, invOrigTransOrn = self._pybullet_client.invertTransform(rootPos,rootOrn)
headingOrn = self.buildHeadingTrans(rootOrn)
#print("headingOrn=",headingOrn)
@@ -311,8 +492,11 @@ class HumanoidStablePD(object):
#print("headingMat=",headingMat)
#dummy, rootOrnWithoutHeading = self._pybullet_client.multiplyTransforms([0,0,0],headingOrn, [0,0,0], rootOrn)
#dummy, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0,0,0],rootOrnWithoutHeading, invOrigTransPos, invOrigTransOrn)
-
- invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms( [0,0,0],headingOrn, invRootPos,[0,0,0,1])
+
+ invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0, 0, 0],
+ headingOrn,
+ invRootPos,
+ [0, 0, 0, 1])
#print("invOrigTransPos=",invOrigTransPos)
#print("invOrigTransOrn=",invOrigTransOrn)
invOrigTransMat = self._pybullet_client.getMatrixFromQuaternion(invOrigTransOrn)
@@ -325,106 +509,115 @@ class HumanoidStablePD(object):
phase = self.getPhase()
#print("phase=",phase)
stateVector.append(phase)
-
- rootTransPos, rootTransOrn=self.buildOriginTrans()
- basePos,baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
-
- rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, basePos,[0,0,0,1])
+
+ rootTransPos, rootTransOrn = self.buildOriginTrans()
+ basePos, baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+
+ rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, [0, 0, 0, 1])
#print("!!!rootPosRel =",rootPosRel )
#print("rootTransPos=",rootTransPos)
#print("basePos=",basePos)
- localPos,localOrn = self._pybullet_client.multiplyTransforms( rootTransPos, rootTransOrn , basePos,baseOrn )
-
- localPos=[localPos[0]-rootPosRel[0],localPos[1]-rootPosRel[1],localPos[2]-rootPosRel[2]]
+ localPos, localOrn = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, baseOrn)
+
+ localPos = [
+ localPos[0] - rootPosRel[0], localPos[1] - rootPosRel[1], localPos[2] - rootPosRel[2]
+ ]
#print("localPos=",localPos)
-
+
stateVector.append(rootPosRel[1])
-
+
#self.pb2dmJoints=[0,1,2,9,10,11,3,4,5,12,13,14,6,7,8]
- self.pb2dmJoints=[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14]
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._sim_model)):
+ self.pb2dmJoints = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14]
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._sim_model)):
j = self.pb2dmJoints[pbJoint]
#print("joint order:",j)
ls = self._pybullet_client.getLinkState(self._sim_model, j, computeForwardKinematics=True)
linkPos = ls[0]
linkOrn = ls[1]
- linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, linkPos,linkOrn)
- if (linkOrnLocal[3]<0):
- linkOrnLocal=[-linkOrnLocal[0],-linkOrnLocal[1],-linkOrnLocal[2],-linkOrnLocal[3]]
- linkPosLocal=[linkPosLocal[0]-rootPosRel[0],linkPosLocal[1]-rootPosRel[1],linkPosLocal[2]-rootPosRel[2]]
+ linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(
+ rootTransPos, rootTransOrn, linkPos, linkOrn)
+ if (linkOrnLocal[3] < 0):
+ linkOrnLocal = [-linkOrnLocal[0], -linkOrnLocal[1], -linkOrnLocal[2], -linkOrnLocal[3]]
+ linkPosLocal = [
+ linkPosLocal[0] - rootPosRel[0], linkPosLocal[1] - rootPosRel[1],
+ linkPosLocal[2] - rootPosRel[2]
+ ]
for l in linkPosLocal:
stateVector.append(l)
#re-order the quaternion, DeepMimic uses w,x,y,z
-
- if (linkOrnLocal[3]<0):
- linkOrnLocal[0]*=-1
- linkOrnLocal[1]*=-1
- linkOrnLocal[2]*=-1
- linkOrnLocal[3]*=-1
-
+
+ if (linkOrnLocal[3] < 0):
+ linkOrnLocal[0] *= -1
+ linkOrnLocal[1] *= -1
+ linkOrnLocal[2] *= -1
+ linkOrnLocal[3] *= -1
+
stateVector.append(linkOrnLocal[3])
stateVector.append(linkOrnLocal[0])
stateVector.append(linkOrnLocal[1])
stateVector.append(linkOrnLocal[2])
-
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._sim_model)):
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._sim_model)):
j = self.pb2dmJoints[pbJoint]
ls = self._pybullet_client.getLinkState(self._sim_model, j, computeLinkVelocity=True)
linkLinVel = ls[6]
linkAngVel = ls[7]
- linkLinVelLocal , unused = self._pybullet_client.multiplyTransforms([0,0,0], rootTransOrn, linkLinVel,[0,0,0,1])
+ linkLinVelLocal, unused = self._pybullet_client.multiplyTransforms([0, 0, 0], rootTransOrn,
+ linkLinVel, [0, 0, 0, 1])
#linkLinVelLocal=[linkLinVelLocal[0]-rootPosRel[0],linkLinVelLocal[1]-rootPosRel[1],linkLinVelLocal[2]-rootPosRel[2]]
- linkAngVelLocal ,unused = self._pybullet_client.multiplyTransforms([0,0,0], rootTransOrn, linkAngVel,[0,0,0,1])
-
+ linkAngVelLocal, unused = self._pybullet_client.multiplyTransforms([0, 0, 0], rootTransOrn,
+ linkAngVel, [0, 0, 0, 1])
+
for l in linkLinVelLocal:
stateVector.append(l)
for l in linkAngVelLocal:
stateVector.append(l)
-
- #print("stateVector len=",len(stateVector))
+
+ #print("stateVector len=",len(stateVector))
#for st in range (len(stateVector)):
# print("state[",st,"]=",stateVector[st])
return stateVector
-
+
def terminates(self):
#check if any non-allowed body part hits the ground
- terminates=False
+ terminates = False
pts = self._pybullet_client.getContactPoints()
for p in pts:
part = -1
#ignore self-collision
- if (p[1]==p[2]):
+ if (p[1] == p[2]):
continue
- if (p[1]==self._sim_model):
- part=p[3]
- if (p[2]==self._sim_model):
- part=p[4]
- if (part >=0 and part not in self._allowed_body_parts):
+ if (p[1] == self._sim_model):
+ part = p[3]
+ if (p[2] == self._sim_model):
+ part = p[4]
+ if (part >= 0 and part not in self._allowed_body_parts):
#print("terminating part:", part)
- terminates=True
-
+ terminates = True
+
return terminates
-
+
def quatMul(self, q1, q2):
- return [ q1[3] * q2[0] + q1[0] * q2[3] + q1[1] * q2[2] - q1[2] * q2[1],
- q1[3] * q2[1] + q1[1] * q2[3] + q1[2] * q2[0] - q1[0] * q2[2],
- q1[3] * q2[2] + q1[2] * q2[3] + q1[0] * q2[1] - q1[1] * q2[0],
- q1[3] * q2[3] - q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2]]
-
+ return [
+ q1[3] * q2[0] + q1[0] * q2[3] + q1[1] * q2[2] - q1[2] * q2[1],
+ q1[3] * q2[1] + q1[1] * q2[3] + q1[2] * q2[0] - q1[0] * q2[2],
+ q1[3] * q2[2] + q1[2] * q2[3] + q1[0] * q2[1] - q1[1] * q2[0],
+ q1[3] * q2[3] - q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2]
+ ]
+
def calcRootAngVelErr(self, vel0, vel1):
- diff = [vel0[0]-vel1[0],vel0[1]-vel1[1], vel0[2]-vel1[2]]
- return diff[0]*diff[0]+diff[1]*diff[1]+diff[2]*diff[2]
+ diff = [vel0[0] - vel1[0], vel0[1] - vel1[1], vel0[2] - vel1[2]]
+ return diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2]
-
-
- def calcRootRotDiff(self,orn0, orn1):
- orn0Conj = [-orn0[0],-orn0[1],-orn0[2],orn0[3]]
+ def calcRootRotDiff(self, orn0, orn1):
+ orn0Conj = [-orn0[0], -orn0[1], -orn0[2], orn0[3]]
q_diff = self.quatMul(orn1, orn0Conj)
- axis,angle = self._pybullet_client.getAxisAngleFromQuaternion(q_diff)
- return angle*angle
-
+ axis, angle = self._pybullet_client.getAxisAngleFromQuaternion(q_diff)
+ return angle * angle
+
def getReward(self, pose):
#from DeepMimic double cSceneImitate::CalcRewardImitate
#todo: compensate for ground height in some parts, once we move to non-flat terrain
@@ -432,7 +625,7 @@ class HumanoidStablePD(object):
vel_w = 0.05
end_eff_w = 0.15
root_w = 0.2
- com_w = 0 #0.1
+ com_w = 0 #0.1
total_w = pose_w + vel_w + end_eff_w + root_w + com_w
pose_w /= total_w
@@ -456,9 +649,9 @@ class HumanoidStablePD(object):
root_err = 0
com_err = 0
heading_err = 0
-
+
#create a mimic reward, comparing the dynamics humanoid with a kinematic one
-
+
#pose = self.InitializePoseFromMotionData()
#print("self._kin_model=",self._kin_model)
#print("kinematicHumanoid #joints=",self._pybullet_client.getNumJoints(self._kin_model))
@@ -487,91 +680,102 @@ class HumanoidStablePD(object):
#tVector root_ang_vel0 = cKinTree::GetRootAngVel(joint_mat, vel0);
#tVector root_ang_vel1 = cKinTree::GetRootAngVel(joint_mat, vel1);
- mJointWeights = [0.20833,0.10416, 0.0625, 0.10416,
- 0.0625, 0.041666666666666671, 0.0625, 0.0416,
- 0.00, 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000]
-
+ mJointWeights = [
+ 0.20833, 0.10416, 0.0625, 0.10416, 0.0625, 0.041666666666666671, 0.0625, 0.0416, 0.00,
+ 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000
+ ]
+
num_end_effs = 0
num_joints = 15
-
+
root_rot_w = mJointWeights[root_id]
- rootPosSim,rootOrnSim = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
- rootPosKin ,rootOrnKin = self._pybullet_client.getBasePositionAndOrientation(self._kin_model)
+ rootPosSim, rootOrnSim = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+ rootPosKin, rootOrnKin = self._pybullet_client.getBasePositionAndOrientation(self._kin_model)
linVelSim, angVelSim = self._pybullet_client.getBaseVelocity(self._sim_model)
linVelKin, angVelKin = self._pybullet_client.getBaseVelocity(self._kin_model)
-
-
- root_rot_err = self.calcRootRotDiff(rootOrnSim,rootOrnKin)
+
+ root_rot_err = self.calcRootRotDiff(rootOrnSim, rootOrnKin)
pose_err += root_rot_w * root_rot_err
-
-
- root_vel_diff = [linVelSim[0]-linVelKin[0],linVelSim[1]-linVelKin[1],linVelSim[2]-linVelKin[2]]
- root_vel_err = root_vel_diff[0]*root_vel_diff[0]+root_vel_diff[1]*root_vel_diff[1]+root_vel_diff[2]*root_vel_diff[2]
-
- root_ang_vel_err = self.calcRootAngVelErr( angVelSim, angVelKin)
+
+ root_vel_diff = [
+ linVelSim[0] - linVelKin[0], linVelSim[1] - linVelKin[1], linVelSim[2] - linVelKin[2]
+ ]
+ root_vel_err = root_vel_diff[0] * root_vel_diff[0] + root_vel_diff[1] * root_vel_diff[
+ 1] + root_vel_diff[2] * root_vel_diff[2]
+
+ root_ang_vel_err = self.calcRootAngVelErr(angVelSim, angVelKin)
vel_err += root_rot_w * root_ang_vel_err
- for j in range (num_joints):
+ for j in range(num_joints):
curr_pose_err = 0
curr_vel_err = 0
- w = mJointWeights[j];
-
+ w = mJointWeights[j]
+
simJointInfo = self._pybullet_client.getJointStateMultiDof(self._sim_model, j)
-
+
#print("simJointInfo.pos=",simJointInfo[0])
#print("simJointInfo.vel=",simJointInfo[1])
- kinJointInfo = self._pybullet_client.getJointStateMultiDof(self._kin_model,j)
+ kinJointInfo = self._pybullet_client.getJointStateMultiDof(self._kin_model, j)
#print("kinJointInfo.pos=",kinJointInfo[0])
#print("kinJointInfo.vel=",kinJointInfo[1])
- if (len(simJointInfo[0])==1):
- angle = simJointInfo[0][0]-kinJointInfo[0][0]
- curr_pose_err = angle*angle
- velDiff = simJointInfo[1][0]-kinJointInfo[1][0]
- curr_vel_err = velDiff*velDiff
- if (len(simJointInfo[0])==4):
+ if (len(simJointInfo[0]) == 1):
+ angle = simJointInfo[0][0] - kinJointInfo[0][0]
+ curr_pose_err = angle * angle
+ velDiff = simJointInfo[1][0] - kinJointInfo[1][0]
+ curr_vel_err = velDiff * velDiff
+ if (len(simJointInfo[0]) == 4):
#print("quaternion diff")
- diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0],kinJointInfo[0])
- axis,angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
- curr_pose_err = angle*angle
- diffVel = [simJointInfo[1][0]-kinJointInfo[1][0],simJointInfo[1][1]-kinJointInfo[1][1],simJointInfo[1][2]-kinJointInfo[1][2]]
- curr_vel_err = diffVel[0]*diffVel[0]+diffVel[1]*diffVel[1]+diffVel[2]*diffVel[2]
-
-
+ diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0], kinJointInfo[0])
+ axis, angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
+ curr_pose_err = angle * angle
+ diffVel = [
+ simJointInfo[1][0] - kinJointInfo[1][0], simJointInfo[1][1] - kinJointInfo[1][1],
+ simJointInfo[1][2] - kinJointInfo[1][2]
+ ]
+ curr_vel_err = diffVel[0] * diffVel[0] + diffVel[1] * diffVel[1] + diffVel[2] * diffVel[2]
+
pose_err += w * curr_pose_err
vel_err += w * curr_vel_err
-
+
is_end_eff = j in self._end_effectors
if is_end_eff:
-
+
linkStateSim = self._pybullet_client.getLinkState(self._sim_model, j)
linkStateKin = self._pybullet_client.getLinkState(self._kin_model, j)
linkPosSim = linkStateSim[0]
linkPosKin = linkStateKin[0]
- linkPosDiff = [linkPosSim[0]-linkPosKin[0],linkPosSim[1]-linkPosKin[1],linkPosSim[2]-linkPosKin[2]]
- curr_end_err = linkPosDiff[0]*linkPosDiff[0]+linkPosDiff[1]*linkPosDiff[1]+linkPosDiff[2]*linkPosDiff[2]
+ linkPosDiff = [
+ linkPosSim[0] - linkPosKin[0], linkPosSim[1] - linkPosKin[1],
+ linkPosSim[2] - linkPosKin[2]
+ ]
+ curr_end_err = linkPosDiff[0] * linkPosDiff[0] + linkPosDiff[1] * linkPosDiff[
+ 1] + linkPosDiff[2] * linkPosDiff[2]
end_eff_err += curr_end_err
- num_end_effs+=1
-
+ num_end_effs += 1
+
if (num_end_effs > 0):
end_eff_err /= num_end_effs
-
+
#double root_ground_h0 = mGround->SampleHeight(sim_char.GetRootPos())
#double root_ground_h1 = kin_char.GetOriginPos()[1]
#root_pos0[1] -= root_ground_h0
#root_pos1[1] -= root_ground_h1
- root_pos_diff = [rootPosSim[0]-rootPosKin[0],rootPosSim[1]-rootPosKin[1],rootPosSim[2]-rootPosKin[2]]
- root_pos_err = root_pos_diff[0]*root_pos_diff[0]+root_pos_diff[1]*root_pos_diff[1]+root_pos_diff[2]*root_pos_diff[2]
- #
+ root_pos_diff = [
+ rootPosSim[0] - rootPosKin[0], rootPosSim[1] - rootPosKin[1], rootPosSim[2] - rootPosKin[2]
+ ]
+ root_pos_err = root_pos_diff[0] * root_pos_diff[0] + root_pos_diff[1] * root_pos_diff[
+ 1] + root_pos_diff[2] * root_pos_diff[2]
+ #
#root_rot_err = cMathUtil::QuatDiffTheta(root_rot0, root_rot1)
#root_rot_err *= root_rot_err
#root_vel_err = (root_vel1 - root_vel0).squaredNorm()
#root_ang_vel_err = (root_ang_vel1 - root_ang_vel0).squaredNorm()
- root_err = root_pos_err + 0.1 * root_rot_err+ 0.01 * root_vel_err+ 0.001 * root_ang_vel_err
-
+ root_err = root_pos_err + 0.1 * root_rot_err + 0.01 * root_vel_err + 0.001 * root_ang_vel_err
+
#com_err = 0.1 * (com_vel1_world - com_vel0_world).squaredNorm()
-
+
#print("pose_err=",pose_err)
#print("vel_err=",vel_err)
pose_reward = math.exp(-err_scale * pose_scale * pose_err)
@@ -582,7 +786,6 @@ class HumanoidStablePD(object):
reward = pose_w * pose_reward + vel_w * vel_reward + end_eff_w * end_eff_reward + root_w * root_reward + com_w * com_reward
-
# pose_reward,vel_reward,end_eff_reward, root_reward, com_reward);
#print("reward=",reward)
#print("pose_reward=",pose_reward)
@@ -590,5 +793,5 @@ class HumanoidStablePD(object):
#print("end_eff_reward=",end_eff_reward)
#print("root_reward=",root_reward)
#print("com_reward=",com_reward)
-
+
return reward
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/motion_capture_data.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/motion_capture_data.py
index ea9399899..f14ef9e78 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/motion_capture_data.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/motion_capture_data.py
@@ -1,7 +1,9 @@
import json
import math
+
class MotionCaptureData(object):
+
def __init__(self):
self.Reset()
@@ -13,30 +15,33 @@ class MotionCaptureData(object):
self._motion_data = json.load(f)
def NumFrames(self):
- return len(self._motion_data['Frames'])
+ return len(self._motion_data['Frames'])
def KeyFrameDuraction(self):
- return self._motion_data['Frames'][0][0]
-
+ return self._motion_data['Frames'][0][0]
+
def getCycleTime(self):
keyFrameDuration = self.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self.NumFrames() - 1)
return cycleTime
-
+
def calcCycleCount(self, simTime, cycleTime):
- phases = simTime / cycleTime;
+ phases = simTime / cycleTime
count = math.floor(phases)
loop = True
#count = (loop) ? count : cMathUtil::Clamp(count, 0, 1);
return count
-
+
def computeCycleOffset(self):
- firstFrame=0
- lastFrame = self.NumFrames()-1
+ firstFrame = 0
+ lastFrame = self.NumFrames() - 1
frameData = self._motion_data['Frames'][0]
frameDataNext = self._motion_data['Frames'][lastFrame]
-
- basePosStart = [frameData[1],frameData[2],frameData[3]]
- basePosEnd = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._cycleOffset = [basePosEnd[0]-basePosStart[0],basePosEnd[1]-basePosStart[1],basePosEnd[2]-basePosStart[2]]
- return self._cycleOffset \ No newline at end of file
+
+ basePosStart = [frameData[1], frameData[2], frameData[3]]
+ basePosEnd = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._cycleOffset = [
+ basePosEnd[0] - basePosStart[0], basePosEnd[1] - basePosStart[1],
+ basePosEnd[2] - basePosStart[2]
+ ]
+ return self._cycleOffset
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/pybullet_deep_mimic_env.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/pybullet_deep_mimic_env.py
index 68e4d613e..764d70c3d 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/pybullet_deep_mimic_env.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/pybullet_deep_mimic_env.py
@@ -9,301 +9,313 @@ from pybullet_envs.deep_mimic.env import humanoid_stable_pd
import pybullet_data
import pybullet as p1
import random
-
-
+
+
class PyBulletDeepMimicEnv(Env):
- def __init__(self, arg_parser=None, enable_draw=False, pybullet_client=None):
- super().__init__(arg_parser, enable_draw)
- self._num_agents = 1
- self._pybullet_client = pybullet_client
- self._isInitialized = False
- self._useStablePD = True
- self._arg_parser = arg_parser
- self.reset()
-
- def reset(self):
-
-
- if not self._isInitialized:
- if self.enable_draw:
- self._pybullet_client = bullet_client.BulletClient(connection_mode=p1.GUI)
- #disable 'GUI' since it slows down a lot on Mac OSX and some other platforms
- self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_GUI,0)
- else:
- self._pybullet_client = bullet_client.BulletClient()
-
- self._pybullet_client.setAdditionalSearchPath(pybullet_data.getDataPath())
- z2y = self._pybullet_client.getQuaternionFromEuler([-math.pi*0.5,0,0])
- self._planeId = self._pybullet_client.loadURDF("plane_implicit.urdf",[0,0,0],z2y, useMaximalCoordinates=True)
- #print("planeId=",self._planeId)
- self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_Y_AXIS_UP,1)
- self._pybullet_client.setGravity(0,-9.8,0)
-
- self._pybullet_client.setPhysicsEngineParameter(numSolverIterations=10)
- self._pybullet_client.changeDynamics(self._planeId, linkIndex=-1, lateralFriction=0.9)
-
- self._mocapData = motion_capture_data.MotionCaptureData()
-
- motion_file = self._arg_parser.parse_strings('motion_file')
- print("motion_file=",motion_file[0])
-
- motionPath = pybullet_data.getDataPath()+"/"+motion_file[0]
- #motionPath = pybullet_data.getDataPath()+"/motions/humanoid3d_backflip.txt"
- self._mocapData.Load(motionPath)
- timeStep = 1./600.
- useFixedBase=False
- self._humanoid = humanoid_stable_pd.HumanoidStablePD(self._pybullet_client, self._mocapData, timeStep, useFixedBase)
- self._isInitialized = True
-
- self._pybullet_client.setTimeStep(timeStep)
- self._pybullet_client.setPhysicsEngineParameter(numSubSteps=1)
-
-
- selfCheck = False
- if (selfCheck):
- curTime = 0
- while self._pybullet_client.isConnected():
- self._humanoid.setSimTime(curTime)
- state = self._humanoid.getState()
- #print("state=",state)
- pose = self._humanoid.computePose(self._humanoid._frameFraction)
- for i in range (10):
- curTime+=timeStep
- #taus = self._humanoid.computePDForces(pose)
- #self._humanoid.applyPDForces(taus)
- #self._pybullet_client.stepSimulation()
- time.sleep(timeStep)
- #print("numframes = ", self._humanoid._mocap_data.NumFrames())
- #startTime = random.randint(0,self._humanoid._mocap_data.NumFrames()-2)
- rnrange = 1000
- rn = random.randint(0,rnrange)
- startTime = float(rn)/rnrange * self._humanoid.getCycleTime()
- self.t = startTime
-
- self._humanoid.setSimTime(startTime)
-
- self._humanoid.resetPose()
- #this clears the contact points. Todo: add API to explicitly clear all contact points?
- #self._pybullet_client.stepSimulation()
- self._humanoid.resetPose()
- self.needs_update_time = self.t-1#force update
-
- def get_num_agents(self):
- return self._num_agents
-
- def get_action_space(self, agent_id):
- return ActionSpace(ActionSpace.Continuous)
-
- def get_reward_min(self, agent_id):
- return 0
-
- def get_reward_max(self, agent_id):
- return 1
-
- def get_reward_fail(self, agent_id):
- return self.get_reward_min(agent_id)
-
- def get_reward_succ(self, agent_id):
- return self.get_reward_max(agent_id)
-
- #scene_name == "imitate" -> cDrawSceneImitate
- def get_state_size(self, agent_id):
- #cCtController::GetStateSize()
- #int state_size = cDeepMimicCharController::GetStateSize();
- # state_size += GetStatePoseSize();#106
- # state_size += GetStateVelSize(); #(3+3)*numBodyParts=90
- #state_size += GetStatePhaseSize();#1
- #197
- return 197
-
- def build_state_norm_groups(self, agent_id):
- #if (mEnablePhaseInput)
- #{
- #int phase_group = gNormGroupNone;
- #int phase_offset = GetStatePhaseOffset();
- #int phase_size = GetStatePhaseSize();
- #out_groups.segment(phase_offset, phase_size) = phase_group * Eigen::VectorXi::Ones(phase_size);
- groups = [0]*self.get_state_size(agent_id)
- groups[0] = -1
- return groups
-
- def build_state_offset(self, agent_id):
- out_offset = [0]*self.get_state_size(agent_id)
- phase_offset = -0.5
- out_offset[0] = phase_offset
- return np.array(out_offset)
-
- def build_state_scale(self, agent_id):
- out_scale = [1]*self.get_state_size(agent_id)
- phase_scale = 2
- out_scale[0] = phase_scale
- return np.array(out_scale)
-
- def get_goal_size(self, agent_id):
- return 0
-
- def get_action_size(self, agent_id):
- ctrl_size = 43 #numDof
- root_size = 7
- return ctrl_size - root_size
-
- def build_goal_norm_groups(self, agent_id):
- return np.array([])
-
- def build_goal_offset(self, agent_id):
- return np.array([])
-
- def build_goal_scale(self, agent_id):
- return np.array([])
-
- def build_action_offset(self, agent_id):
- out_offset = [0] * self.get_action_size(agent_id)
- out_offset = [0.0000000000,0.0000000000,0.0000000000,-0.200000000,0.0000000000,0.0000000000,0.0000000000,
- -0.200000000,0.0000000000,0.0000000000, 0.00000000, -0.2000000, 1.57000000, 0.00000000, 0.00000000,
- 0.00000000, -0.2000000, 0.00000000, 0.00000000, 0.00000000, -0.2000000, -1.5700000, 0.00000000, 0.00000000,
- 0.00000000, -0.2000000, 1.57000000, 0.00000000, 0.00000000, 0.00000000, -0.2000000, 0.00000000, 0.00000000,
- 0.00000000, -0.2000000, -1.5700000]
- #see cCtCtrlUtil::BuildOffsetScalePDPrismatic and
- #see cCtCtrlUtil::BuildOffsetScalePDSpherical
- return np.array(out_offset)
-
- def build_action_scale(self, agent_id):
- out_scale = [1] * self.get_action_size(agent_id)
- #see cCtCtrlUtil::BuildOffsetScalePDPrismatic and
- #see cCtCtrlUtil::BuildOffsetScalePDSpherical
- out_scale=[ 0.20833333333333,1.00000000000000,1.00000000000000,1.00000000000000,0.25000000000000,
- 1.00000000000000,1.00000000000000,1.00000000000000,0.12077294685990,1.00000000000000,
- 1.000000000000, 1.000000000000, 0.159235668789, 0.159235668789, 1.000000000000,
- 1.000000000000, 1.000000000000, 0.079617834394, 1.000000000000, 1.000000000000,
- 1.000000000000, 0.159235668789, 0.120772946859, 1.000000000000, 1.000000000000,
- 1.000000000000, 0.159235668789, 0.159235668789, 1.000000000000, 1.000000000000,
- 1.000000000000, 0.107758620689, 1.000000000000, 1.000000000000, 1.000000000000,
- 0.159235668789]
- return np.array(out_scale)
-
- def build_action_bound_min(self, agent_id):
- #see cCtCtrlUtil::BuildBoundsPDSpherical
- out_scale = [-1] * self.get_action_size(agent_id)
- out_scale = [-4.79999999999,-1.00000000000,-1.00000000000,-1.00000000000,-4.00000000000,
- -1.00000000000,-1.00000000000,-1.00000000000,-7.77999999999,-1.00000000000, -1.000000000,
- -1.000000000, -7.850000000, -6.280000000, -1.000000000, -1.000000000, -1.000000000,
- -12.56000000, -1.000000000, -1.000000000, -1.000000000, -4.710000000,
- -7.779999999, -1.000000000, -1.000000000, -1.000000000, -7.850000000,
- -6.280000000, -1.000000000, -1.000000000, -1.000000000, -8.460000000,
- -1.000000000, -1.000000000, -1.000000000, -4.710000000]
-
- return out_scale
-
- def build_action_bound_max(self, agent_id):
- out_scale = [1] * self.get_action_size(agent_id)
- out_scale=[
- 4.799999999,1.000000000,1.000000000,1.000000000,4.000000000,1.000000000,
- 1.000000000,1.000000000,8.779999999,1.000000000, 1.0000000, 1.0000000,
- 4.7100000, 6.2800000, 1.0000000, 1.0000000, 1.0000000,
- 12.560000, 1.0000000, 1.0000000, 1.0000000, 7.8500000,
- 8.7799999, 1.0000000, 1.0000000, 1.0000000, 4.7100000,
- 6.2800000, 1.0000000, 1.0000000, 1.0000000, 10.100000,
- 1.0000000, 1.0000000, 1.0000000, 7.8500000]
- return out_scale
-
- def set_mode(self, mode):
- self._mode = mode
-
- def need_new_action(self, agent_id):
- if self.t>=self.needs_update_time:
- self.needs_update_time = self.t + 1./30.
- return True
- return False
-
- def record_state(self, agent_id):
- state = self._humanoid.getState()
-
- return np.array(state)
-
-
- def record_goal(self, agent_id):
- return np.array([])
-
- def calc_reward(self, agent_id):
- kinPose = self._humanoid.computePose(self._humanoid._frameFraction)
- reward = self._humanoid.getReward(kinPose)
- return reward
-
- def set_action(self, agent_id, action):
- #print("action=",)
- #for a in action:
- # print(a)
- np.savetxt("pb_action.csv", action, delimiter=",")
- self.desiredPose = self._humanoid.convertActionToPose(action)
- #we need the target root positon and orientation to be zero, to be compatible with deep mimic
- self.desiredPose[0] = 0
- self.desiredPose[1] = 0
- self.desiredPose[2] = 0
- self.desiredPose[3] = 0
- self.desiredPose[4] = 0
- self.desiredPose[5] = 0
- self.desiredPose[6] = 0
- target_pose = np.array(self.desiredPose)
-
-
- np.savetxt("pb_target_pose.csv", target_pose, delimiter=",")
-
- #print("set_action: desiredPose=", self.desiredPose)
-
- def log_val(self, agent_id, val):
- pass
-
-
- def update(self, timeStep):
- #print("pybullet_deep_mimic_env:update timeStep=",timeStep," t=",self.t)
+
+ def __init__(self, arg_parser=None, enable_draw=False, pybullet_client=None):
+ super().__init__(arg_parser, enable_draw)
+ self._num_agents = 1
+ self._pybullet_client = pybullet_client
+ self._isInitialized = False
+ self._useStablePD = True
+ self._arg_parser = arg_parser
+ self.reset()
+
+ def reset(self):
+
+ if not self._isInitialized:
+ if self.enable_draw:
+ self._pybullet_client = bullet_client.BulletClient(connection_mode=p1.GUI)
+ #disable 'GUI' since it slows down a lot on Mac OSX and some other platforms
+ self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_GUI, 0)
+ else:
+ self._pybullet_client = bullet_client.BulletClient()
+
+ self._pybullet_client.setAdditionalSearchPath(pybullet_data.getDataPath())
+ z2y = self._pybullet_client.getQuaternionFromEuler([-math.pi * 0.5, 0, 0])
+ self._planeId = self._pybullet_client.loadURDF("plane_implicit.urdf", [0, 0, 0],
+ z2y,
+ useMaximalCoordinates=True)
+ #print("planeId=",self._planeId)
+ self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_Y_AXIS_UP, 1)
+ self._pybullet_client.setGravity(0, -9.8, 0)
+
+ self._pybullet_client.setPhysicsEngineParameter(numSolverIterations=10)
+ self._pybullet_client.changeDynamics(self._planeId, linkIndex=-1, lateralFriction=0.9)
+
+ self._mocapData = motion_capture_data.MotionCaptureData()
+
+ motion_file = self._arg_parser.parse_strings('motion_file')
+ print("motion_file=", motion_file[0])
+
+ motionPath = pybullet_data.getDataPath() + "/" + motion_file[0]
+ #motionPath = pybullet_data.getDataPath()+"/motions/humanoid3d_backflip.txt"
+ self._mocapData.Load(motionPath)
+ timeStep = 1. / 600.
+ useFixedBase = False
+ self._humanoid = humanoid_stable_pd.HumanoidStablePD(self._pybullet_client, self._mocapData,
+ timeStep, useFixedBase)
+ self._isInitialized = True
+
self._pybullet_client.setTimeStep(timeStep)
- self._humanoid._timeStep = timeStep
-
- for i in range(1):
- self.t += timeStep
- self._humanoid.setSimTime(self.t)
-
- if self.desiredPose:
- kinPose = self._humanoid.computePose(self._humanoid._frameFraction)
- self._humanoid.initializePose(self._humanoid._poseInterpolator, self._humanoid._kin_model, initBase=True)
- #pos,orn=self._pybullet_client.getBasePositionAndOrientation(self._humanoid._sim_model)
- #self._pybullet_client.resetBasePositionAndOrientation(self._humanoid._kin_model, [pos[0]+3,pos[1],pos[2]],orn)
- #print("desiredPositions=",self.desiredPose)
- maxForces = [0,0,0,0,0,0,0,200,200,200,200, 50,50,50,50, 200,200,200,200, 150, 90,90,90,90, 100,100,100,100, 60, 200,200,200,200, 150, 90, 90, 90, 90, 100,100,100,100, 60]
-
- if self._useStablePD:
- taus = self._humanoid.computePDForces(self.desiredPose, desiredVelocities=None, maxForces=maxForces)
- self._humanoid.applyPDForces(taus)
- else:
- self._humanoid.setJointMotors(self.desiredPose, maxForces=maxForces)
-
- self._pybullet_client.stepSimulation()
-
-
- def set_sample_count(self, count):
- return
-
- def check_terminate(self, agent_id):
- return Env.Terminate(self.is_episode_end())
-
- def is_episode_end(self):
- isEnded = self._humanoid.terminates()
- #also check maximum time, 20 seconds (todo get from file)
- #print("self.t=",self.t)
- if (self.t>20):
- isEnded = True
- return isEnded
-
- def check_valid_episode(self):
- #could check if limbs exceed velocity threshold
- return true
-
- def getKeyboardEvents(self):
- return self._pybullet_client.getKeyboardEvents()
-
- def isKeyTriggered(self, keys, key):
- o = ord(key)
- #print("ord=",o)
- if o in keys:
- return keys[ord(key)] & self._pybullet_client.KEY_WAS_TRIGGERED
- return False
+ self._pybullet_client.setPhysicsEngineParameter(numSubSteps=1)
+
+ selfCheck = False
+ if (selfCheck):
+ curTime = 0
+ while self._pybullet_client.isConnected():
+ self._humanoid.setSimTime(curTime)
+ state = self._humanoid.getState()
+ #print("state=",state)
+ pose = self._humanoid.computePose(self._humanoid._frameFraction)
+ for i in range(10):
+ curTime += timeStep
+ #taus = self._humanoid.computePDForces(pose)
+ #self._humanoid.applyPDForces(taus)
+ #self._pybullet_client.stepSimulation()
+ time.sleep(timeStep)
+ #print("numframes = ", self._humanoid._mocap_data.NumFrames())
+ #startTime = random.randint(0,self._humanoid._mocap_data.NumFrames()-2)
+ rnrange = 1000
+ rn = random.randint(0, rnrange)
+ startTime = float(rn) / rnrange * self._humanoid.getCycleTime()
+ self.t = startTime
+
+ self._humanoid.setSimTime(startTime)
+
+ self._humanoid.resetPose()
+ #this clears the contact points. Todo: add API to explicitly clear all contact points?
+ #self._pybullet_client.stepSimulation()
+ self._humanoid.resetPose()
+ self.needs_update_time = self.t - 1 #force update
+
+ def get_num_agents(self):
+ return self._num_agents
+
+ def get_action_space(self, agent_id):
+ return ActionSpace(ActionSpace.Continuous)
+
+ def get_reward_min(self, agent_id):
+ return 0
+
+ def get_reward_max(self, agent_id):
+ return 1
+
+ def get_reward_fail(self, agent_id):
+ return self.get_reward_min(agent_id)
+
+ def get_reward_succ(self, agent_id):
+ return self.get_reward_max(agent_id)
+
+ #scene_name == "imitate" -> cDrawSceneImitate
+ def get_state_size(self, agent_id):
+ #cCtController::GetStateSize()
+ #int state_size = cDeepMimicCharController::GetStateSize();
+ # state_size += GetStatePoseSize();#106
+ # state_size += GetStateVelSize(); #(3+3)*numBodyParts=90
+ #state_size += GetStatePhaseSize();#1
+ #197
+ return 197
+
+ def build_state_norm_groups(self, agent_id):
+ #if (mEnablePhaseInput)
+ #{
+ #int phase_group = gNormGroupNone;
+ #int phase_offset = GetStatePhaseOffset();
+ #int phase_size = GetStatePhaseSize();
+ #out_groups.segment(phase_offset, phase_size) = phase_group * Eigen::VectorXi::Ones(phase_size);
+ groups = [0] * self.get_state_size(agent_id)
+ groups[0] = -1
+ return groups
+
+ def build_state_offset(self, agent_id):
+ out_offset = [0] * self.get_state_size(agent_id)
+ phase_offset = -0.5
+ out_offset[0] = phase_offset
+ return np.array(out_offset)
+
+ def build_state_scale(self, agent_id):
+ out_scale = [1] * self.get_state_size(agent_id)
+ phase_scale = 2
+ out_scale[0] = phase_scale
+ return np.array(out_scale)
+
+ def get_goal_size(self, agent_id):
+ return 0
+
+ def get_action_size(self, agent_id):
+ ctrl_size = 43 #numDof
+ root_size = 7
+ return ctrl_size - root_size
+
+ def build_goal_norm_groups(self, agent_id):
+ return np.array([])
+
+ def build_goal_offset(self, agent_id):
+ return np.array([])
+
+ def build_goal_scale(self, agent_id):
+ return np.array([])
+
+ def build_action_offset(self, agent_id):
+ out_offset = [0] * self.get_action_size(agent_id)
+ out_offset = [
+ 0.0000000000, 0.0000000000, 0.0000000000, -0.200000000, 0.0000000000, 0.0000000000,
+ 0.0000000000, -0.200000000, 0.0000000000, 0.0000000000, 0.00000000, -0.2000000, 1.57000000,
+ 0.00000000, 0.00000000, 0.00000000, -0.2000000, 0.00000000, 0.00000000, 0.00000000,
+ -0.2000000, -1.5700000, 0.00000000, 0.00000000, 0.00000000, -0.2000000, 1.57000000,
+ 0.00000000, 0.00000000, 0.00000000, -0.2000000, 0.00000000, 0.00000000, 0.00000000,
+ -0.2000000, -1.5700000
+ ]
+ #see cCtCtrlUtil::BuildOffsetScalePDPrismatic and
+ #see cCtCtrlUtil::BuildOffsetScalePDSpherical
+ return np.array(out_offset)
+
+ def build_action_scale(self, agent_id):
+ out_scale = [1] * self.get_action_size(agent_id)
+ #see cCtCtrlUtil::BuildOffsetScalePDPrismatic and
+ #see cCtCtrlUtil::BuildOffsetScalePDSpherical
+ out_scale = [
+ 0.20833333333333, 1.00000000000000, 1.00000000000000, 1.00000000000000, 0.25000000000000,
+ 1.00000000000000, 1.00000000000000, 1.00000000000000, 0.12077294685990, 1.00000000000000,
+ 1.000000000000, 1.000000000000, 0.159235668789, 0.159235668789, 1.000000000000,
+ 1.000000000000, 1.000000000000, 0.079617834394, 1.000000000000, 1.000000000000,
+ 1.000000000000, 0.159235668789, 0.120772946859, 1.000000000000, 1.000000000000,
+ 1.000000000000, 0.159235668789, 0.159235668789, 1.000000000000, 1.000000000000,
+ 1.000000000000, 0.107758620689, 1.000000000000, 1.000000000000, 1.000000000000,
+ 0.159235668789
+ ]
+ return np.array(out_scale)
+
+ def build_action_bound_min(self, agent_id):
+ #see cCtCtrlUtil::BuildBoundsPDSpherical
+ out_scale = [-1] * self.get_action_size(agent_id)
+ out_scale = [
+ -4.79999999999, -1.00000000000, -1.00000000000, -1.00000000000, -4.00000000000,
+ -1.00000000000, -1.00000000000, -1.00000000000, -7.77999999999, -1.00000000000,
+ -1.000000000, -1.000000000, -7.850000000, -6.280000000, -1.000000000, -1.000000000,
+ -1.000000000, -12.56000000, -1.000000000, -1.000000000, -1.000000000, -4.710000000,
+ -7.779999999, -1.000000000, -1.000000000, -1.000000000, -7.850000000, -6.280000000,
+ -1.000000000, -1.000000000, -1.000000000, -8.460000000, -1.000000000, -1.000000000,
+ -1.000000000, -4.710000000
+ ]
+
+ return out_scale
+
+ def build_action_bound_max(self, agent_id):
+ out_scale = [1] * self.get_action_size(agent_id)
+ out_scale = [
+ 4.799999999, 1.000000000, 1.000000000, 1.000000000, 4.000000000, 1.000000000, 1.000000000,
+ 1.000000000, 8.779999999, 1.000000000, 1.0000000, 1.0000000, 4.7100000, 6.2800000,
+ 1.0000000, 1.0000000, 1.0000000, 12.560000, 1.0000000, 1.0000000, 1.0000000, 7.8500000,
+ 8.7799999, 1.0000000, 1.0000000, 1.0000000, 4.7100000, 6.2800000, 1.0000000, 1.0000000,
+ 1.0000000, 10.100000, 1.0000000, 1.0000000, 1.0000000, 7.8500000
+ ]
+ return out_scale
+
+ def set_mode(self, mode):
+ self._mode = mode
+
+ def need_new_action(self, agent_id):
+ if self.t >= self.needs_update_time:
+ self.needs_update_time = self.t + 1. / 30.
+ return True
+ return False
+
+ def record_state(self, agent_id):
+ state = self._humanoid.getState()
+
+ return np.array(state)
+
+ def record_goal(self, agent_id):
+ return np.array([])
+
+ def calc_reward(self, agent_id):
+ kinPose = self._humanoid.computePose(self._humanoid._frameFraction)
+ reward = self._humanoid.getReward(kinPose)
+ return reward
+
+ def set_action(self, agent_id, action):
+ #print("action=",)
+ #for a in action:
+ # print(a)
+ np.savetxt("pb_action.csv", action, delimiter=",")
+ self.desiredPose = self._humanoid.convertActionToPose(action)
+ #we need the target root positon and orientation to be zero, to be compatible with deep mimic
+ self.desiredPose[0] = 0
+ self.desiredPose[1] = 0
+ self.desiredPose[2] = 0
+ self.desiredPose[3] = 0
+ self.desiredPose[4] = 0
+ self.desiredPose[5] = 0
+ self.desiredPose[6] = 0
+ target_pose = np.array(self.desiredPose)
+
+ np.savetxt("pb_target_pose.csv", target_pose, delimiter=",")
+
+ #print("set_action: desiredPose=", self.desiredPose)
+
+ def log_val(self, agent_id, val):
+ pass
+
+ def update(self, timeStep):
+ #print("pybullet_deep_mimic_env:update timeStep=",timeStep," t=",self.t)
+ self._pybullet_client.setTimeStep(timeStep)
+ self._humanoid._timeStep = timeStep
+
+ for i in range(1):
+ self.t += timeStep
+ self._humanoid.setSimTime(self.t)
+
+ if self.desiredPose:
+ kinPose = self._humanoid.computePose(self._humanoid._frameFraction)
+ self._humanoid.initializePose(self._humanoid._poseInterpolator,
+ self._humanoid._kin_model,
+ initBase=True)
+ #pos,orn=self._pybullet_client.getBasePositionAndOrientation(self._humanoid._sim_model)
+ #self._pybullet_client.resetBasePositionAndOrientation(self._humanoid._kin_model, [pos[0]+3,pos[1],pos[2]],orn)
+ #print("desiredPositions=",self.desiredPose)
+ maxForces = [
+ 0, 0, 0, 0, 0, 0, 0, 200, 200, 200, 200, 50, 50, 50, 50, 200, 200, 200, 200, 150, 90,
+ 90, 90, 90, 100, 100, 100, 100, 60, 200, 200, 200, 200, 150, 90, 90, 90, 90, 100, 100,
+ 100, 100, 60
+ ]
+
+ if self._useStablePD:
+ taus = self._humanoid.computePDForces(self.desiredPose,
+ desiredVelocities=None,
+ maxForces=maxForces)
+ self._humanoid.applyPDForces(taus)
+ else:
+ self._humanoid.setJointMotors(self.desiredPose, maxForces=maxForces)
+
+ self._pybullet_client.stepSimulation()
+
+ def set_sample_count(self, count):
+ return
+
+ def check_terminate(self, agent_id):
+ return Env.Terminate(self.is_episode_end())
+
+ def is_episode_end(self):
+ isEnded = self._humanoid.terminates()
+ #also check maximum time, 20 seconds (todo get from file)
+ #print("self.t=",self.t)
+ if (self.t > 20):
+ isEnded = True
+ return isEnded
+
+ def check_valid_episode(self):
+ #could check if limbs exceed velocity threshold
+ return true
+
+ def getKeyboardEvents(self):
+ return self._pybullet_client.getKeyboardEvents()
+
+ def isKeyTriggered(self, keys, key):
+ o = ord(key)
+ #print("ord=",o)
+ if o in keys:
+ return keys[ord(key)] & self._pybullet_client.KEY_WAS_TRIGGERED
+ return False
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadrupedPoseInterpolator.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadrupedPoseInterpolator.py
index 9aa6d2652..49a05b003 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadrupedPoseInterpolator.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadrupedPoseInterpolator.py
@@ -1,54 +1,66 @@
from pybullet_utils import bullet_client
import math
-
+
+
class QuadrupedPoseInterpolator(object):
+
def __init__(self):
pass
-
-
- def ComputeLinVel(self,posStart, posEnd, deltaTime):
- vel = [(posEnd[0]-posStart[0])/deltaTime,(posEnd[1]-posStart[1])/deltaTime,(posEnd[2]-posStart[2])/deltaTime]
+
+ def ComputeLinVel(self, posStart, posEnd, deltaTime):
+ vel = [(posEnd[0] - posStart[0]) / deltaTime, (posEnd[1] - posStart[1]) / deltaTime,
+ (posEnd[2] - posStart[2]) / deltaTime]
return vel
-
- def ComputeAngVel(self,ornStart, ornEnd, deltaTime, bullet_client):
- dorn = bullet_client.getDifferenceQuaternion(ornStart,ornEnd)
- axis,angle = bullet_client.getAxisAngleFromQuaternion(dorn)
- angVel = [(axis[0]*angle)/deltaTime,(axis[1]*angle)/deltaTime,(axis[2]*angle)/deltaTime]
+
+ def ComputeAngVel(self, ornStart, ornEnd, deltaTime, bullet_client):
+ dorn = bullet_client.getDifferenceQuaternion(ornStart, ornEnd)
+ axis, angle = bullet_client.getAxisAngleFromQuaternion(dorn)
+ angVel = [(axis[0] * angle) / deltaTime, (axis[1] * angle) / deltaTime,
+ (axis[2] * angle) / deltaTime]
return angVel
-
- def ComputeAngVelRel(self,ornStart, ornEnd, deltaTime, bullet_client):
- ornStartConjugate = [-ornStart[0],-ornStart[1],-ornStart[2],ornStart[3]]
- pos_diff, q_diff =bullet_client.multiplyTransforms([0,0,0], ornStartConjugate, [0,0,0], ornEnd)
- axis,angle = bullet_client.getAxisAngleFromQuaternion(q_diff)
- angVel = [(axis[0]*angle)/deltaTime,(axis[1]*angle)/deltaTime,(axis[2]*angle)/deltaTime]
+
+ def ComputeAngVelRel(self, ornStart, ornEnd, deltaTime, bullet_client):
+ ornStartConjugate = [-ornStart[0], -ornStart[1], -ornStart[2], ornStart[3]]
+ pos_diff, q_diff = bullet_client.multiplyTransforms([0, 0, 0], ornStartConjugate, [0, 0, 0],
+ ornEnd)
+ axis, angle = bullet_client.getAxisAngleFromQuaternion(q_diff)
+ angVel = [(axis[0] * angle) / deltaTime, (axis[1] * angle) / deltaTime,
+ (axis[2] * angle) / deltaTime]
return angVel
-
- def Slerp(self, frameFraction, frameData, frameDataNext,bullet_client ):
+
+ def Slerp(self, frameFraction, frameData, frameDataNext, bullet_client):
keyFrameDuration = frameData[0]
- basePos1Start = [frameData[1],frameData[2],frameData[3]]
- basePos1End = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._basePos = [basePos1Start[0]+frameFraction*(basePos1End[0]-basePos1Start[0]),
- basePos1Start[1]+frameFraction*(basePos1End[1]-basePos1Start[1]),
- basePos1Start[2]+frameFraction*(basePos1End[2]-basePos1Start[2])]
- self._baseLinVel = self.ComputeLinVel(basePos1Start,basePos1End, keyFrameDuration)
- baseOrn1Start = [frameData[5],frameData[6], frameData[7],frameData[4]]
- baseOrn1Next = [frameDataNext[5],frameDataNext[6], frameDataNext[7],frameDataNext[4]]
- self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start,baseOrn1Next,frameFraction)
- self._baseAngVel = self.ComputeAngVel(baseOrn1Start,baseOrn1Next, keyFrameDuration, bullet_client)
-
- jointPositions=[self._basePos[0],self._basePos[1],self._basePos[2],
- self._baseOrn[0],self._baseOrn[1],self._baseOrn[2],self._baseOrn[3]]
- jointVelocities=[self._baseLinVel[0],self._baseLinVel[1],self._baseLinVel[2],
- self._baseAngVel[0],self._baseAngVel[1],self._baseAngVel[2]]
-
- for j in range (12):
- index=j+8
- jointPosStart=frameData[index]
- jointPosEnd=frameDataNext[index]
- jointPos=jointPosStart+frameFraction*(jointPosEnd-jointPosStart)
- jointVel=(jointPosEnd-jointPosStart)/keyFrameDuration
+ basePos1Start = [frameData[1], frameData[2], frameData[3]]
+ basePos1End = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._basePos = [
+ basePos1Start[0] + frameFraction * (basePos1End[0] - basePos1Start[0]),
+ basePos1Start[1] + frameFraction * (basePos1End[1] - basePos1Start[1]),
+ basePos1Start[2] + frameFraction * (basePos1End[2] - basePos1Start[2])
+ ]
+ self._baseLinVel = self.ComputeLinVel(basePos1Start, basePos1End, keyFrameDuration)
+ baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
+ baseOrn1Next = [frameDataNext[5], frameDataNext[6], frameDataNext[7], frameDataNext[4]]
+ self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start, baseOrn1Next, frameFraction)
+ self._baseAngVel = self.ComputeAngVel(baseOrn1Start, baseOrn1Next, keyFrameDuration,
+ bullet_client)
+
+ jointPositions = [
+ self._basePos[0], self._basePos[1], self._basePos[2], self._baseOrn[0], self._baseOrn[1],
+ self._baseOrn[2], self._baseOrn[3]
+ ]
+ jointVelocities = [
+ self._baseLinVel[0], self._baseLinVel[1], self._baseLinVel[2], self._baseAngVel[0],
+ self._baseAngVel[1], self._baseAngVel[2]
+ ]
+
+ for j in range(12):
+ index = j + 8
+ jointPosStart = frameData[index]
+ jointPosEnd = frameDataNext[index]
+ jointPos = jointPosStart + frameFraction * (jointPosEnd - jointPosStart)
+ jointVel = (jointPosEnd - jointPosStart) / keyFrameDuration
jointPositions.append(jointPos)
jointVelocities.append(jointVel)
self._jointPositions = jointPositions
self._jointVelocities = jointVelocities
- return jointPositions,jointVelocities
+ return jointPositions, jointVelocities
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadruped_stable_pd.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadruped_stable_pd.py
index ce66fb462..66f2f70b2 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadruped_stable_pd.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/quadruped_stable_pd.py
@@ -1,127 +1,209 @@
-
-from pybullet_utils import pd_controller_stable
+from pybullet_utils import pd_controller_stable
from pybullet_envs.deep_mimic.env import quadruped_pose_interpolator
import math
class QuadrupedStablePD(object):
+
def __init__(self, pybullet_client, mocap_data, timeStep, useFixedBase=True):
self._pybullet_client = pybullet_client
self._mocap_data = mocap_data
print("LOADING quadruped!")
-
- startPos=[0.007058990464444105, 0.03149299192130908, 0.4918981912395484]
- startOrn=[0.005934649695708604, 0.7065453990917289, 0.7076373820553712, -0.0027774940359030264]
- self._sim_model = self._pybullet_client.loadURDF("laikago/laikago.urdf",startPos,startOrn, flags = urdfFlags,useFixedBase=False)
- self._pybullet_client.resetBasePositionAndOrientation(_sim_model,startPos,startOrn)
-
+
+ startPos = [0.007058990464444105, 0.03149299192130908, 0.4918981912395484]
+ startOrn = [
+ 0.005934649695708604, 0.7065453990917289, 0.7076373820553712, -0.0027774940359030264
+ ]
+ self._sim_model = self._pybullet_client.loadURDF("laikago/laikago.urdf",
+ startPos,
+ startOrn,
+ flags=urdfFlags,
+ useFixedBase=False)
+ self._pybullet_client.resetBasePositionAndOrientation(_sim_model, startPos, startOrn)
+
self._end_effectors = [] #ankle and wrist, both left and right
- self._kin_model = self._pybullet_client.loadURDF("laikago/laikago.urdf",startPos,startOrn,useFixedBase=True)
-
+ self._kin_model = self._pybullet_client.loadURDF("laikago/laikago.urdf",
+ startPos,
+ startOrn,
+ useFixedBase=True)
+
self._pybullet_client.changeDynamics(self._sim_model, -1, lateralFriction=0.9)
- for j in range (self._pybullet_client.getNumJoints(self._sim_model)):
+ for j in range(self._pybullet_client.getNumJoints(self._sim_model)):
self._pybullet_client.changeDynamics(self._sim_model, j, lateralFriction=0.9)
-
+
self._pybullet_client.changeDynamics(self._sim_model, -1, linearDamping=0, angularDamping=0)
self._pybullet_client.changeDynamics(self._kin_model, -1, linearDamping=0, angularDamping=0)
-
+
#todo: add feature to disable simulation for a particular object. Until then, disable all collisions
- self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,-1,collisionFilterGroup=0,collisionFilterMask=0)
- self._pybullet_client.changeDynamics(self._kin_model,-1,activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP+self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING+self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
+ self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,
+ -1,
+ collisionFilterGroup=0,
+ collisionFilterMask=0)
+ self._pybullet_client.changeDynamics(
+ self._kin_model,
+ -1,
+ activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP +
+ self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING +
+ self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
alpha = 0.4
- self._pybullet_client.changeVisualShape(self._kin_model,-1, rgbaColor=[1,1,1,alpha])
- for j in range (self._pybullet_client.getNumJoints(self._kin_model)):
- self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,j,collisionFilterGroup=0,collisionFilterMask=0)
- self._pybullet_client.changeDynamics(self._kin_model,j,activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP+self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING+self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
- self._pybullet_client.changeVisualShape(self._kin_model,j, rgbaColor=[1,1,1,alpha])
-
+ self._pybullet_client.changeVisualShape(self._kin_model, -1, rgbaColor=[1, 1, 1, alpha])
+ for j in range(self._pybullet_client.getNumJoints(self._kin_model)):
+ self._pybullet_client.setCollisionFilterGroupMask(self._kin_model,
+ j,
+ collisionFilterGroup=0,
+ collisionFilterMask=0)
+ self._pybullet_client.changeDynamics(
+ self._kin_model,
+ j,
+ activationState=self._pybullet_client.ACTIVATION_STATE_SLEEP +
+ self._pybullet_client.ACTIVATION_STATE_ENABLE_SLEEPING +
+ self._pybullet_client.ACTIVATION_STATE_DISABLE_WAKEUP)
+ self._pybullet_client.changeVisualShape(self._kin_model, j, rgbaColor=[1, 1, 1, alpha])
+
self._poseInterpolator = humanoid_pose_interpolator.HumanoidPoseInterpolator()
-
- for i in range (self._mocap_data.NumFrames()-1):
+
+ for i in range(self._mocap_data.NumFrames() - 1):
frameData = self._mocap_data._motion_data['Frames'][i]
self._poseInterpolator.PostProcessMotionData(frameData)
-
+
self._stablePD = pd_controller_stable.PDControllerStableMultiDof(self._pybullet_client)
self._timeStep = timeStep
#todo: kp/pd
- self._kpOrg = [0,0,0,0,0,0,0,1000,1000,1000,1000,100,100,100,100,500,500,500,500,500,400,400,400,400,400,400,400,400,300,500,500,500,500,500,400,400,400,400,400,400,400,400,300]
- self._kdOrg = [0,0,0,0,0,0,0,100,100,100,100,10,10,10,10,50,50,50,50,50,40,40,40,40,40,40,40,40,30,50,50,50,50,50,40,40,40,40,40,40,40,40,30]
-
- self._jointIndicesAll = [chest,neck, rightHip,rightKnee,rightAnkle,rightShoulder,rightElbow,leftHip,leftKnee,leftAnkle,leftShoulder,leftElbow]
+ self._kpOrg = [
+ 0, 0, 0, 0, 0, 0, 0, 1000, 1000, 1000, 1000, 100, 100, 100, 100, 500, 500, 500, 500, 500,
+ 400, 400, 400, 400, 400, 400, 400, 400, 300, 500, 500, 500, 500, 500, 400, 400, 400, 400,
+ 400, 400, 400, 400, 300
+ ]
+ self._kdOrg = [
+ 0, 0, 0, 0, 0, 0, 0, 100, 100, 100, 100, 10, 10, 10, 10, 50, 50, 50, 50, 50, 40, 40, 40,
+ 40, 40, 40, 40, 40, 30, 50, 50, 50, 50, 50, 40, 40, 40, 40, 40, 40, 40, 40, 30
+ ]
+
+ self._jointIndicesAll = [
+ chest, neck, rightHip, rightKnee, rightAnkle, rightShoulder, rightElbow, leftHip, leftKnee,
+ leftAnkle, leftShoulder, leftElbow
+ ]
for j in self._jointIndicesAll:
#self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, j, self._pybullet_client.POSITION_CONTROL, force=[1,1,1])
- self._pybullet_client.setJointMotorControl2(self._sim_model, j, self._pybullet_client.POSITION_CONTROL, targetPosition=0, positionGain=0, targetVelocity=0,force=jointFrictionForce)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, j, self._pybullet_client.POSITION_CONTROL,targetPosition=[0,0,0,1], targetVelocity=[0,0,0], positionGain=0,velocityGain=1,force=[jointFrictionForce,jointFrictionForce,jointFrictionForce])
- self._pybullet_client.setJointMotorControl2(self._kin_model, j, self._pybullet_client.POSITION_CONTROL, targetPosition=0, positionGain=0, targetVelocity=0,force=0)
- self._pybullet_client.setJointMotorControlMultiDof(self._kin_model, j, self._pybullet_client.POSITION_CONTROL,targetPosition=[0,0,0,1], targetVelocity=[0,0,0], positionGain=0,velocityGain=1,force=[jointFrictionForce,jointFrictionForce,0])
-
- self._jointDofCounts=[4,4,4,1,4,4,1,4,1,4,4,1]
-
+ self._pybullet_client.setJointMotorControl2(self._sim_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=0,
+ positionGain=0,
+ targetVelocity=0,
+ force=jointFrictionForce)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=[0, 0, 0, 1],
+ targetVelocity=[0, 0, 0],
+ positionGain=0,
+ velocityGain=1,
+ force=[jointFrictionForce, jointFrictionForce, jointFrictionForce])
+ self._pybullet_client.setJointMotorControl2(self._kin_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=0,
+ positionGain=0,
+ targetVelocity=0,
+ force=0)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._kin_model,
+ j,
+ self._pybullet_client.POSITION_CONTROL,
+ targetPosition=[0, 0, 0, 1],
+ targetVelocity=[0, 0, 0],
+ positionGain=0,
+ velocityGain=1,
+ force=[jointFrictionForce, jointFrictionForce, 0])
+
+ self._jointDofCounts = [4, 4, 4, 1, 4, 4, 1, 4, 1, 4, 4, 1]
+
#only those body parts/links are allowed to touch the ground, otherwise the episode terminates
- self._allowed_body_parts=[5,11]
-
+ self._allowed_body_parts = [5, 11]
+
#[x,y,z] base position and [x,y,z,w] base orientation!
- self._totalDofs = 7
+ self._totalDofs = 7
for dof in self._jointDofCounts:
self._totalDofs += dof
self.setSimTime(0)
-
+
self.resetPose()
-
+
def resetPose(self):
#print("resetPose with self._frame=", self._frame, " and self._frameFraction=",self._frameFraction)
pose = self.computePose(self._frameFraction)
self.initializePose(self._poseInterpolator, self._sim_model, initBase=True)
self.initializePose(self._poseInterpolator, self._kin_model, initBase=False)
-
- def initializePose(self, pose, phys_model,initBase, initializeVelocity = True):
-
+
+ def initializePose(self, pose, phys_model, initBase, initializeVelocity=True):
+
if initializeVelocity:
if initBase:
- self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos, pose._baseOrn)
+ self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos,
+ pose._baseOrn)
self._pybullet_client.resetBaseVelocity(phys_model, pose._baseLinVel, pose._baseAngVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,chest,pose._chestRot, pose._chestVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,neck,pose._neckRot, pose._neckVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightHip,pose._rightHipRot, pose._rightHipVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightKnee,pose._rightKneeRot, pose._rightKneeVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightAnkle,pose._rightAnkleRot, pose._rightAnkleVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightShoulder,pose._rightShoulderRot, pose._rightShoulderVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightElbow, pose._rightElbowRot, pose._rightElbowVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftHip, pose._leftHipRot, pose._leftHipVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftKnee, pose._leftKneeRot, pose._leftKneeVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftAnkle, pose._leftAnkleRot, pose._leftAnkleVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftShoulder, pose._leftShoulderRot, pose._leftShoulderVel)
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftElbow, pose._leftElbowRot, pose._leftElbowVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, chest, pose._chestRot,
+ pose._chestVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, neck, pose._neckRot, pose._neckVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightHip, pose._rightHipRot,
+ pose._rightHipVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightKnee, pose._rightKneeRot,
+ pose._rightKneeVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightAnkle, pose._rightAnkleRot,
+ pose._rightAnkleVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightShoulder,
+ pose._rightShoulderRot, pose._rightShoulderVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightElbow, pose._rightElbowRot,
+ pose._rightElbowVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftHip, pose._leftHipRot,
+ pose._leftHipVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftKnee, pose._leftKneeRot,
+ pose._leftKneeVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftAnkle, pose._leftAnkleRot,
+ pose._leftAnkleVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftShoulder,
+ pose._leftShoulderRot, pose._leftShoulderVel)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftElbow, pose._leftElbowRot,
+ pose._leftElbowVel)
else:
if initBase:
- self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos, pose._baseOrn)
- self._pybullet_client.resetJointStateMultiDof(phys_model,chest,pose._chestRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,neck,pose._neckRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightHip,pose._rightHipRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightKnee,pose._rightKneeRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightAnkle,pose._rightAnkleRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightShoulder,pose._rightShoulderRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,rightElbow, pose._rightElbowRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftHip, pose._leftHipRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftKnee, pose._leftKneeRot, [0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftAnkle, pose._leftAnkleRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftShoulder, pose._leftShoulderRot, [0,0,0])
- self._pybullet_client.resetJointStateMultiDof(phys_model,leftElbow, pose._leftElbowRot, [0])
+ self._pybullet_client.resetBasePositionAndOrientation(phys_model, pose._basePos,
+ pose._baseOrn)
+ self._pybullet_client.resetJointStateMultiDof(phys_model, chest, pose._chestRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, neck, pose._neckRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightHip, pose._rightHipRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightKnee, pose._rightKneeRot, [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightAnkle, pose._rightAnkleRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightShoulder,
+ pose._rightShoulderRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, rightElbow, pose._rightElbowRot,
+ [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftHip, pose._leftHipRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftKnee, pose._leftKneeRot, [0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftAnkle, pose._leftAnkleRot,
+ [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftShoulder,
+ pose._leftShoulderRot, [0, 0, 0])
+ self._pybullet_client.resetJointStateMultiDof(phys_model, leftElbow, pose._leftElbowRot, [0])
def calcCycleCount(self, simTime, cycleTime):
- phases = simTime / cycleTime;
+ phases = simTime / cycleTime
count = math.floor(phases)
loop = True
#count = (loop) ? count : cMathUtil::Clamp(count, 0, 1);
return count
-
def getCycleTime(self):
keyFrameDuration = self._mocap_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._mocap_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._mocap_data.NumFrames() - 1)
return cycleTime
-
+
def setSimTime(self, t):
self._simTime = t
#print("SetTimeTime time =",t)
@@ -130,163 +212,266 @@ class QuadrupedStablePD(object):
#print("self._motion_data.NumFrames()=",self._mocap_data.NumFrames())
self._cycleCount = self.calcCycleCount(t, cycleTime)
#print("cycles=",cycles)
- frameTime = t - self._cycleCount*cycleTime
- if (frameTime<0):
+ frameTime = t - self._cycleCount * cycleTime
+ if (frameTime < 0):
frameTime += cycleTime
-
- #print("keyFrameDuration=",keyFrameDuration)
+
+ #print("keyFrameDuration=",keyFrameDuration)
#print("frameTime=",frameTime)
- self._frame = int(frameTime/keyFrameDuration)
+ self._frame = int(frameTime / keyFrameDuration)
#print("self._frame=",self._frame)
-
- self._frameNext = self._frame+1
- if (self._frameNext >= self._mocap_data.NumFrames()):
+
+ self._frameNext = self._frame + 1
+ if (self._frameNext >= self._mocap_data.NumFrames()):
self._frameNext = self._frame
- self._frameFraction = (frameTime - self._frame*keyFrameDuration)/(keyFrameDuration)
-
-
+ self._frameFraction = (frameTime - self._frame * keyFrameDuration) / (keyFrameDuration)
+
def computeCycleOffset(self):
- firstFrame=0
- lastFrame = self._mocap_data.NumFrames()-1
+ firstFrame = 0
+ lastFrame = self._mocap_data.NumFrames() - 1
frameData = self._mocap_data._motion_data['Frames'][0]
frameDataNext = self._mocap_data._motion_data['Frames'][lastFrame]
-
- basePosStart = [frameData[1],frameData[2],frameData[3]]
- basePosEnd = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._cycleOffset = [basePosEnd[0]-basePosStart[0],basePosEnd[1]-basePosStart[1],basePosEnd[2]-basePosStart[2]]
+
+ basePosStart = [frameData[1], frameData[2], frameData[3]]
+ basePosEnd = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._cycleOffset = [
+ basePosEnd[0] - basePosStart[0], basePosEnd[1] - basePosStart[1],
+ basePosEnd[2] - basePosStart[2]
+ ]
return self._cycleOffset
-
+
def computePose(self, frameFraction):
frameData = self._mocap_data._motion_data['Frames'][self._frame]
frameDataNext = self._mocap_data._motion_data['Frames'][self._frameNext]
-
+
self._poseInterpolator.Slerp(frameFraction, frameData, frameDataNext, self._pybullet_client)
#print("self._poseInterpolator.Slerp(", frameFraction,")=", pose)
self.computeCycleOffset()
oldPos = self._poseInterpolator._basePos
- self._poseInterpolator._basePos = [oldPos[0]+self._cycleCount*self._cycleOffset[0],oldPos[1]+self._cycleCount*self._cycleOffset[1],oldPos[2]+self._cycleCount*self._cycleOffset[2]]
+ self._poseInterpolator._basePos = [
+ oldPos[0] + self._cycleCount * self._cycleOffset[0],
+ oldPos[1] + self._cycleCount * self._cycleOffset[1],
+ oldPos[2] + self._cycleCount * self._cycleOffset[2]
+ ]
pose = self._poseInterpolator.GetPose()
-
- return pose
+ return pose
def convertActionToPose(self, action):
pose = self._poseInterpolator.ConvertFromAction(self._pybullet_client, action)
- return pose
+ return pose
def computePDForces(self, desiredPositions, desiredVelocities, maxForces):
- if desiredVelocities==None:
- desiredVelocities = [0]*self._totalDofs
-
-
- taus = self._stablePD.computePD(bodyUniqueId=self._sim_model,
- jointIndices = self._jointIndicesAll,
- desiredPositions = desiredPositions,
- desiredVelocities = desiredVelocities,
- kps = self._kpOrg,
- kds = self._kdOrg,
- maxForces = maxForces,
- timeStep=self._timeStep)
+ if desiredVelocities == None:
+ desiredVelocities = [0] * self._totalDofs
+
+ taus = self._stablePD.computePD(bodyUniqueId=self._sim_model,
+ jointIndices=self._jointIndicesAll,
+ desiredPositions=desiredPositions,
+ desiredVelocities=desiredVelocities,
+ kps=self._kpOrg,
+ kds=self._kdOrg,
+ maxForces=maxForces,
+ timeStep=self._timeStep)
return taus
def applyPDForces(self, taus):
- dofIndex=7
+ dofIndex = 7
scaling = 1
- for index in range (len(self._jointIndicesAll)):
+ for index in range(len(self._jointIndicesAll)):
jointIndex = self._jointIndicesAll[index]
- if self._jointDofCounts[index]==4:
- force=[scaling*taus[dofIndex+0],scaling*taus[dofIndex+1],scaling*taus[dofIndex+2]]
- #print("force[", jointIndex,"]=",force)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,jointIndex,self._pybullet_client.TORQUE_CONTROL,force=force)
- if self._jointDofCounts[index]==1:
- force=[scaling*taus[dofIndex]]
- #print("force[", jointIndex,"]=",force)
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model, jointIndex, controlMode=self._pybullet_client.TORQUE_CONTROL, force=force)
- dofIndex+=self._jointDofCounts[index]
-
+ if self._jointDofCounts[index] == 4:
+ force = [
+ scaling * taus[dofIndex + 0], scaling * taus[dofIndex + 1],
+ scaling * taus[dofIndex + 2]
+ ]
+ #print("force[", jointIndex,"]=",force)
+ self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,
+ jointIndex,
+ self._pybullet_client.TORQUE_CONTROL,
+ force=force)
+ if self._jointDofCounts[index] == 1:
+ force = [scaling * taus[dofIndex]]
+ #print("force[", jointIndex,"]=",force)
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ jointIndex,
+ controlMode=self._pybullet_client.TORQUE_CONTROL,
+ force=force)
+ dofIndex += self._jointDofCounts[index]
+
def setJointMotors(self, desiredPositions, maxForces):
controlMode = self._pybullet_client.POSITION_CONTROL
- startIndex=7
- chest=1
- neck=2
- rightHip=3
- rightKnee=4
- rightAnkle=5
- rightShoulder=6
- rightElbow=7
- leftHip=9
- leftKnee=10
- leftAnkle=11
- leftShoulder=12
- leftElbow=13
+ startIndex = 7
+ chest = 1
+ neck = 2
+ rightHip = 3
+ rightKnee = 4
+ rightAnkle = 5
+ rightShoulder = 6
+ rightElbow = 7
+ leftHip = 9
+ leftKnee = 10
+ leftAnkle = 11
+ leftShoulder = 12
+ leftElbow = 13
kp = 0.2
-
- forceScale=1
+
+ forceScale = 1
#self._jointDofCounts=[4,4,4,1,4,4,1,4,1,4,4,1]
- maxForce = [forceScale*maxForces[startIndex],forceScale*maxForces[startIndex+1],forceScale*maxForces[startIndex+2],forceScale*maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,chest,controlMode, targetPosition=self._poseInterpolator._chestRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,neck,controlMode,targetPosition=self._poseInterpolator._neckRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightHip,controlMode,targetPosition=self._poseInterpolator._rightHipRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightKnee,controlMode,targetPosition=self._poseInterpolator._rightKneeRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightAnkle,controlMode,targetPosition=self._poseInterpolator._rightAnkleRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex],forceScale*maxForces[startIndex+1],forceScale*maxForces[startIndex+2],forceScale*maxForces[startIndex+3]]
- startIndex+=4
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,rightElbow, controlMode,targetPosition=self._poseInterpolator._rightElbowRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftHip, controlMode,targetPosition=self._poseInterpolator._leftHipRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftKnee, controlMode,targetPosition=self._poseInterpolator._leftKneeRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftAnkle, controlMode,targetPosition=self._poseInterpolator._leftAnkleRot,positionGain=kp, force=maxForce)
- maxForce = [maxForces[startIndex],maxForces[startIndex+1],maxForces[startIndex+2],maxForces[startIndex+3]]
- startIndex+=4
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftShoulder, controlMode,targetPosition=self._poseInterpolator._leftShoulderRot,positionGain=kp, force=maxForce)
- maxForce = [forceScale*maxForces[startIndex]]
- startIndex+=1
- self._pybullet_client.setJointMotorControlMultiDof(self._sim_model,leftElbow, controlMode,targetPosition=self._poseInterpolator._leftElbowRot,positionGain=kp, force=maxForce)
+ maxForce = [
+ forceScale * maxForces[startIndex], forceScale * maxForces[startIndex + 1],
+ forceScale * maxForces[startIndex + 2], forceScale * maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ chest,
+ controlMode,
+ targetPosition=self._poseInterpolator._chestRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ neck,
+ controlMode,
+ targetPosition=self._poseInterpolator._neckRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightHip,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightHipRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightKnee,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightKneeRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightAnkle,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightAnkleRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ forceScale * maxForces[startIndex], forceScale * maxForces[startIndex + 1],
+ forceScale * maxForces[startIndex + 2], forceScale * maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ rightElbow,
+ controlMode,
+ targetPosition=self._poseInterpolator._rightElbowRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftHip,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftHipRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftKnee,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftKneeRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftAnkle,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftAnkleRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [
+ maxForces[startIndex], maxForces[startIndex + 1], maxForces[startIndex + 2],
+ maxForces[startIndex + 3]
+ ]
+ startIndex += 4
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftShoulder,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftShoulderRot,
+ positionGain=kp,
+ force=maxForce)
+ maxForce = [forceScale * maxForces[startIndex]]
+ startIndex += 1
+ self._pybullet_client.setJointMotorControlMultiDof(
+ self._sim_model,
+ leftElbow,
+ controlMode,
+ targetPosition=self._poseInterpolator._leftElbowRot,
+ positionGain=kp,
+ force=maxForce)
#print("startIndex=",startIndex)
-
+
def getPhase(self):
keyFrameDuration = self._mocap_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._mocap_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._mocap_data.NumFrames() - 1)
phase = self._simTime / cycleTime
- phase = math.fmod(phase,1.0)
- if (phase<0):
+ phase = math.fmod(phase, 1.0)
+ if (phase < 0):
phase += 1
return phase
def buildHeadingTrans(self, rootOrn):
#align root transform 'forward' with world-space x axis
eul = self._pybullet_client.getEulerFromQuaternion(rootOrn)
- refDir = [1,0,0]
+ refDir = [1, 0, 0]
rotVec = self._pybullet_client.rotateVector(rootOrn, refDir)
heading = math.atan2(-rotVec[2], rotVec[0])
- heading2=eul[1]
+ heading2 = eul[1]
#print("heading=",heading)
- headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0,1,0],-heading)
+ headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0, 1, 0], -heading)
return headingOrn
-
def buildOriginTrans(self):
- rootPos,rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
-
+ rootPos, rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+
#print("rootPos=",rootPos, " rootOrn=",rootOrn)
- invRootPos=[-rootPos[0], 0, -rootPos[2]]
+ invRootPos = [-rootPos[0], 0, -rootPos[2]]
#invOrigTransPos, invOrigTransOrn = self._pybullet_client.invertTransform(rootPos,rootOrn)
headingOrn = self.buildHeadingTrans(rootOrn)
#print("headingOrn=",headingOrn)
@@ -294,8 +479,11 @@ class QuadrupedStablePD(object):
#print("headingMat=",headingMat)
#dummy, rootOrnWithoutHeading = self._pybullet_client.multiplyTransforms([0,0,0],headingOrn, [0,0,0], rootOrn)
#dummy, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0,0,0],rootOrnWithoutHeading, invOrigTransPos, invOrigTransOrn)
-
- invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms( [0,0,0],headingOrn, invRootPos,[0,0,0,1])
+
+ invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0, 0, 0],
+ headingOrn,
+ invRootPos,
+ [0, 0, 0, 1])
#print("invOrigTransPos=",invOrigTransPos)
#print("invOrigTransOrn=",invOrigTransOrn)
invOrigTransMat = self._pybullet_client.getMatrixFromQuaternion(invOrigTransOrn)
@@ -308,106 +496,115 @@ class QuadrupedStablePD(object):
phase = self.getPhase()
#print("phase=",phase)
stateVector.append(phase)
-
- rootTransPos, rootTransOrn=self.buildOriginTrans()
- basePos,baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
-
- rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, basePos,[0,0,0,1])
+
+ rootTransPos, rootTransOrn = self.buildOriginTrans()
+ basePos, baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+
+ rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, [0, 0, 0, 1])
#print("!!!rootPosRel =",rootPosRel )
#print("rootTransPos=",rootTransPos)
#print("basePos=",basePos)
- localPos,localOrn = self._pybullet_client.multiplyTransforms( rootTransPos, rootTransOrn , basePos,baseOrn )
-
- localPos=[localPos[0]-rootPosRel[0],localPos[1]-rootPosRel[1],localPos[2]-rootPosRel[2]]
+ localPos, localOrn = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, baseOrn)
+
+ localPos = [
+ localPos[0] - rootPosRel[0], localPos[1] - rootPosRel[1], localPos[2] - rootPosRel[2]
+ ]
#print("localPos=",localPos)
-
+
stateVector.append(rootPosRel[1])
-
+
#self.pb2dmJoints=[0,1,2,9,10,11,3,4,5,12,13,14,6,7,8]
- self.pb2dmJoints=[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14]
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._sim_model)):
+ self.pb2dmJoints = [0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14]
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._sim_model)):
j = self.pb2dmJoints[pbJoint]
#print("joint order:",j)
ls = self._pybullet_client.getLinkState(self._sim_model, j, computeForwardKinematics=True)
linkPos = ls[0]
linkOrn = ls[1]
- linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, linkPos,linkOrn)
- if (linkOrnLocal[3]<0):
- linkOrnLocal=[-linkOrnLocal[0],-linkOrnLocal[1],-linkOrnLocal[2],-linkOrnLocal[3]]
- linkPosLocal=[linkPosLocal[0]-rootPosRel[0],linkPosLocal[1]-rootPosRel[1],linkPosLocal[2]-rootPosRel[2]]
+ linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(
+ rootTransPos, rootTransOrn, linkPos, linkOrn)
+ if (linkOrnLocal[3] < 0):
+ linkOrnLocal = [-linkOrnLocal[0], -linkOrnLocal[1], -linkOrnLocal[2], -linkOrnLocal[3]]
+ linkPosLocal = [
+ linkPosLocal[0] - rootPosRel[0], linkPosLocal[1] - rootPosRel[1],
+ linkPosLocal[2] - rootPosRel[2]
+ ]
for l in linkPosLocal:
stateVector.append(l)
#re-order the quaternion, DeepMimic uses w,x,y,z
-
- if (linkOrnLocal[3]<0):
- linkOrnLocal[0]*=-1
- linkOrnLocal[1]*=-1
- linkOrnLocal[2]*=-1
- linkOrnLocal[3]*=-1
-
+
+ if (linkOrnLocal[3] < 0):
+ linkOrnLocal[0] *= -1
+ linkOrnLocal[1] *= -1
+ linkOrnLocal[2] *= -1
+ linkOrnLocal[3] *= -1
+
stateVector.append(linkOrnLocal[3])
stateVector.append(linkOrnLocal[0])
stateVector.append(linkOrnLocal[1])
stateVector.append(linkOrnLocal[2])
-
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._sim_model)):
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._sim_model)):
j = self.pb2dmJoints[pbJoint]
ls = self._pybullet_client.getLinkState(self._sim_model, j, computeLinkVelocity=True)
linkLinVel = ls[6]
linkAngVel = ls[7]
- linkLinVelLocal , unused = self._pybullet_client.multiplyTransforms([0,0,0], rootTransOrn, linkLinVel,[0,0,0,1])
+ linkLinVelLocal, unused = self._pybullet_client.multiplyTransforms([0, 0, 0], rootTransOrn,
+ linkLinVel, [0, 0, 0, 1])
#linkLinVelLocal=[linkLinVelLocal[0]-rootPosRel[0],linkLinVelLocal[1]-rootPosRel[1],linkLinVelLocal[2]-rootPosRel[2]]
- linkAngVelLocal ,unused = self._pybullet_client.multiplyTransforms([0,0,0], rootTransOrn, linkAngVel,[0,0,0,1])
-
+ linkAngVelLocal, unused = self._pybullet_client.multiplyTransforms([0, 0, 0], rootTransOrn,
+ linkAngVel, [0, 0, 0, 1])
+
for l in linkLinVelLocal:
stateVector.append(l)
for l in linkAngVelLocal:
stateVector.append(l)
-
- #print("stateVector len=",len(stateVector))
+
+ #print("stateVector len=",len(stateVector))
#for st in range (len(stateVector)):
# print("state[",st,"]=",stateVector[st])
return stateVector
-
+
def terminates(self):
#check if any non-allowed body part hits the ground
- terminates=False
+ terminates = False
pts = self._pybullet_client.getContactPoints()
for p in pts:
part = -1
#ignore self-collision
- if (p[1]==p[2]):
+ if (p[1] == p[2]):
continue
- if (p[1]==self._sim_model):
- part=p[3]
- if (p[2]==self._sim_model):
- part=p[4]
- if (part >=0 and part not in self._allowed_body_parts):
+ if (p[1] == self._sim_model):
+ part = p[3]
+ if (p[2] == self._sim_model):
+ part = p[4]
+ if (part >= 0 and part not in self._allowed_body_parts):
#print("terminating part:", part)
- terminates=True
-
+ terminates = True
+
return terminates
-
+
def quatMul(self, q1, q2):
- return [ q1[3] * q2[0] + q1[0] * q2[3] + q1[1] * q2[2] - q1[2] * q2[1],
- q1[3] * q2[1] + q1[1] * q2[3] + q1[2] * q2[0] - q1[0] * q2[2],
- q1[3] * q2[2] + q1[2] * q2[3] + q1[0] * q2[1] - q1[1] * q2[0],
- q1[3] * q2[3] - q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2]]
-
+ return [
+ q1[3] * q2[0] + q1[0] * q2[3] + q1[1] * q2[2] - q1[2] * q2[1],
+ q1[3] * q2[1] + q1[1] * q2[3] + q1[2] * q2[0] - q1[0] * q2[2],
+ q1[3] * q2[2] + q1[2] * q2[3] + q1[0] * q2[1] - q1[1] * q2[0],
+ q1[3] * q2[3] - q1[0] * q2[0] - q1[1] * q2[1] - q1[2] * q2[2]
+ ]
+
def calcRootAngVelErr(self, vel0, vel1):
- diff = [vel0[0]-vel1[0],vel0[1]-vel1[1], vel0[2]-vel1[2]]
- return diff[0]*diff[0]+diff[1]*diff[1]+diff[2]*diff[2]
+ diff = [vel0[0] - vel1[0], vel0[1] - vel1[1], vel0[2] - vel1[2]]
+ return diff[0] * diff[0] + diff[1] * diff[1] + diff[2] * diff[2]
-
-
- def calcRootRotDiff(self,orn0, orn1):
- orn0Conj = [-orn0[0],-orn0[1],-orn0[2],orn0[3]]
+ def calcRootRotDiff(self, orn0, orn1):
+ orn0Conj = [-orn0[0], -orn0[1], -orn0[2], orn0[3]]
q_diff = self.quatMul(orn1, orn0Conj)
- axis,angle = self._pybullet_client.getAxisAngleFromQuaternion(q_diff)
- return angle*angle
-
+ axis, angle = self._pybullet_client.getAxisAngleFromQuaternion(q_diff)
+ return angle * angle
+
def getReward(self, pose):
#from DeepMimic double cSceneImitate::CalcRewardImitate
#todo: compensate for ground height in some parts, once we move to non-flat terrain
@@ -415,7 +612,7 @@ class QuadrupedStablePD(object):
vel_w = 0.05
end_eff_w = 0.15
root_w = 0.2
- com_w = 0 #0.1
+ com_w = 0 #0.1
total_w = pose_w + vel_w + end_eff_w + root_w + com_w
pose_w /= total_w
@@ -439,9 +636,9 @@ class QuadrupedStablePD(object):
root_err = 0
com_err = 0
heading_err = 0
-
+
#create a mimic reward, comparing the dynamics humanoid with a kinematic one
-
+
#pose = self.InitializePoseFromMotionData()
#print("self._kin_model=",self._kin_model)
#print("kinematicHumanoid #joints=",self._pybullet_client.getNumJoints(self._kin_model))
@@ -470,91 +667,102 @@ class QuadrupedStablePD(object):
#tVector root_ang_vel0 = cKinTree::GetRootAngVel(joint_mat, vel0);
#tVector root_ang_vel1 = cKinTree::GetRootAngVel(joint_mat, vel1);
- mJointWeights = [0.20833,0.10416, 0.0625, 0.10416,
- 0.0625, 0.041666666666666671, 0.0625, 0.0416,
- 0.00, 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000]
-
+ mJointWeights = [
+ 0.20833, 0.10416, 0.0625, 0.10416, 0.0625, 0.041666666666666671, 0.0625, 0.0416, 0.00,
+ 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000
+ ]
+
num_end_effs = 0
num_joints = 15
-
+
root_rot_w = mJointWeights[root_id]
- rootPosSim,rootOrnSim = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
- rootPosKin ,rootOrnKin = self._pybullet_client.getBasePositionAndOrientation(self._kin_model)
+ rootPosSim, rootOrnSim = self._pybullet_client.getBasePositionAndOrientation(self._sim_model)
+ rootPosKin, rootOrnKin = self._pybullet_client.getBasePositionAndOrientation(self._kin_model)
linVelSim, angVelSim = self._pybullet_client.getBaseVelocity(self._sim_model)
linVelKin, angVelKin = self._pybullet_client.getBaseVelocity(self._kin_model)
-
-
- root_rot_err = self.calcRootRotDiff(rootOrnSim,rootOrnKin)
+
+ root_rot_err = self.calcRootRotDiff(rootOrnSim, rootOrnKin)
pose_err += root_rot_w * root_rot_err
-
-
- root_vel_diff = [linVelSim[0]-linVelKin[0],linVelSim[1]-linVelKin[1],linVelSim[2]-linVelKin[2]]
- root_vel_err = root_vel_diff[0]*root_vel_diff[0]+root_vel_diff[1]*root_vel_diff[1]+root_vel_diff[2]*root_vel_diff[2]
-
- root_ang_vel_err = self.calcRootAngVelErr( angVelSim, angVelKin)
+
+ root_vel_diff = [
+ linVelSim[0] - linVelKin[0], linVelSim[1] - linVelKin[1], linVelSim[2] - linVelKin[2]
+ ]
+ root_vel_err = root_vel_diff[0] * root_vel_diff[0] + root_vel_diff[1] * root_vel_diff[
+ 1] + root_vel_diff[2] * root_vel_diff[2]
+
+ root_ang_vel_err = self.calcRootAngVelErr(angVelSim, angVelKin)
vel_err += root_rot_w * root_ang_vel_err
- for j in range (num_joints):
+ for j in range(num_joints):
curr_pose_err = 0
curr_vel_err = 0
- w = mJointWeights[j];
-
+ w = mJointWeights[j]
+
simJointInfo = self._pybullet_client.getJointStateMultiDof(self._sim_model, j)
-
+
#print("simJointInfo.pos=",simJointInfo[0])
#print("simJointInfo.vel=",simJointInfo[1])
- kinJointInfo = self._pybullet_client.getJointStateMultiDof(self._kin_model,j)
+ kinJointInfo = self._pybullet_client.getJointStateMultiDof(self._kin_model, j)
#print("kinJointInfo.pos=",kinJointInfo[0])
#print("kinJointInfo.vel=",kinJointInfo[1])
- if (len(simJointInfo[0])==1):
- angle = simJointInfo[0][0]-kinJointInfo[0][0]
- curr_pose_err = angle*angle
- velDiff = simJointInfo[1][0]-kinJointInfo[1][0]
- curr_vel_err = velDiff*velDiff
- if (len(simJointInfo[0])==4):
+ if (len(simJointInfo[0]) == 1):
+ angle = simJointInfo[0][0] - kinJointInfo[0][0]
+ curr_pose_err = angle * angle
+ velDiff = simJointInfo[1][0] - kinJointInfo[1][0]
+ curr_vel_err = velDiff * velDiff
+ if (len(simJointInfo[0]) == 4):
#print("quaternion diff")
- diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0],kinJointInfo[0])
- axis,angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
- curr_pose_err = angle*angle
- diffVel = [simJointInfo[1][0]-kinJointInfo[1][0],simJointInfo[1][1]-kinJointInfo[1][1],simJointInfo[1][2]-kinJointInfo[1][2]]
- curr_vel_err = diffVel[0]*diffVel[0]+diffVel[1]*diffVel[1]+diffVel[2]*diffVel[2]
-
-
+ diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0], kinJointInfo[0])
+ axis, angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
+ curr_pose_err = angle * angle
+ diffVel = [
+ simJointInfo[1][0] - kinJointInfo[1][0], simJointInfo[1][1] - kinJointInfo[1][1],
+ simJointInfo[1][2] - kinJointInfo[1][2]
+ ]
+ curr_vel_err = diffVel[0] * diffVel[0] + diffVel[1] * diffVel[1] + diffVel[2] * diffVel[2]
+
pose_err += w * curr_pose_err
vel_err += w * curr_vel_err
-
+
is_end_eff = j in self._end_effectors
if is_end_eff:
-
+
linkStateSim = self._pybullet_client.getLinkState(self._sim_model, j)
linkStateKin = self._pybullet_client.getLinkState(self._kin_model, j)
linkPosSim = linkStateSim[0]
linkPosKin = linkStateKin[0]
- linkPosDiff = [linkPosSim[0]-linkPosKin[0],linkPosSim[1]-linkPosKin[1],linkPosSim[2]-linkPosKin[2]]
- curr_end_err = linkPosDiff[0]*linkPosDiff[0]+linkPosDiff[1]*linkPosDiff[1]+linkPosDiff[2]*linkPosDiff[2]
+ linkPosDiff = [
+ linkPosSim[0] - linkPosKin[0], linkPosSim[1] - linkPosKin[1],
+ linkPosSim[2] - linkPosKin[2]
+ ]
+ curr_end_err = linkPosDiff[0] * linkPosDiff[0] + linkPosDiff[1] * linkPosDiff[
+ 1] + linkPosDiff[2] * linkPosDiff[2]
end_eff_err += curr_end_err
- num_end_effs+=1
-
+ num_end_effs += 1
+
if (num_end_effs > 0):
end_eff_err /= num_end_effs
-
+
#double root_ground_h0 = mGround->SampleHeight(sim_char.GetRootPos())
#double root_ground_h1 = kin_char.GetOriginPos()[1]
#root_pos0[1] -= root_ground_h0
#root_pos1[1] -= root_ground_h1
- root_pos_diff = [rootPosSim[0]-rootPosKin[0],rootPosSim[1]-rootPosKin[1],rootPosSim[2]-rootPosKin[2]]
- root_pos_err = root_pos_diff[0]*root_pos_diff[0]+root_pos_diff[1]*root_pos_diff[1]+root_pos_diff[2]*root_pos_diff[2]
- #
+ root_pos_diff = [
+ rootPosSim[0] - rootPosKin[0], rootPosSim[1] - rootPosKin[1], rootPosSim[2] - rootPosKin[2]
+ ]
+ root_pos_err = root_pos_diff[0] * root_pos_diff[0] + root_pos_diff[1] * root_pos_diff[
+ 1] + root_pos_diff[2] * root_pos_diff[2]
+ #
#root_rot_err = cMathUtil::QuatDiffTheta(root_rot0, root_rot1)
#root_rot_err *= root_rot_err
#root_vel_err = (root_vel1 - root_vel0).squaredNorm()
#root_ang_vel_err = (root_ang_vel1 - root_ang_vel0).squaredNorm()
- root_err = root_pos_err + 0.1 * root_rot_err+ 0.01 * root_vel_err+ 0.001 * root_ang_vel_err
-
+ root_err = root_pos_err + 0.1 * root_rot_err + 0.01 * root_vel_err + 0.001 * root_ang_vel_err
+
#com_err = 0.1 * (com_vel1_world - com_vel0_world).squaredNorm()
-
+
#print("pose_err=",pose_err)
#print("vel_err=",vel_err)
pose_reward = math.exp(-err_scale * pose_scale * pose_err)
@@ -565,7 +773,6 @@ class QuadrupedStablePD(object):
reward = pose_w * pose_reward + vel_w * vel_reward + end_eff_w * end_eff_reward + root_w * root_reward + com_w * com_reward
-
# pose_reward,vel_reward,end_eff_reward, root_reward, com_reward);
#print("reward=",reward)
#print("pose_reward=",pose_reward)
@@ -573,5 +780,5 @@ class QuadrupedStablePD(object):
#print("end_eff_reward=",end_eff_reward)
#print("root_reward=",root_reward)
#print("com_reward=",com_reward)
-
+
return reward
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testHumanoid.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testHumanoid.py
index d34ffe794..c689a062a 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testHumanoid.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testHumanoid.py
@@ -8,87 +8,89 @@ import pybullet as p1
import humanoid_pose_interpolator
import numpy as np
-pybullet_client = bullet_client.BulletClient(connection_mode=p1.GUI)
+pybullet_client = bullet_client.BulletClient(connection_mode=p1.GUI)
pybullet_client.setAdditionalSearchPath(pybullet_data.getDataPath())
-z2y = pybullet_client.getQuaternionFromEuler([-math.pi*0.5,0,0])
+z2y = pybullet_client.getQuaternionFromEuler([-math.pi * 0.5, 0, 0])
#planeId = pybullet_client.loadURDF("plane.urdf",[0,0,0],z2y)
-planeId= pybullet_client.loadURDF("plane_implicit.urdf",[0,0,0],z2y, useMaximalCoordinates=True)
-pybullet_client.changeDynamics(planeId, linkIndex=-1, lateralFriction=0.9)
+planeId = pybullet_client.loadURDF("plane_implicit.urdf", [0, 0, 0],
+ z2y,
+ useMaximalCoordinates=True)
+pybullet_client.changeDynamics(planeId, linkIndex=-1, lateralFriction=0.9)
#print("planeId=",planeId)
-pybullet_client.configureDebugVisualizer(pybullet_client.COV_ENABLE_Y_AXIS_UP,1)
-pybullet_client.setGravity(0,-9.8,0)
+pybullet_client.configureDebugVisualizer(pybullet_client.COV_ENABLE_Y_AXIS_UP, 1)
+pybullet_client.setGravity(0, -9.8, 0)
pybullet_client.setPhysicsEngineParameter(numSolverIterations=10)
-
mocapData = motion_capture_data.MotionCaptureData()
#motionPath = pybullet_data.getDataPath()+"/data/motions/humanoid3d_walk.txt"
-motionPath = pybullet_data.getDataPath()+"/data/motions/humanoid3d_backflip.txt"
+motionPath = pybullet_data.getDataPath() + "/data/motions/humanoid3d_backflip.txt"
mocapData.Load(motionPath)
-timeStep = 1./600
-useFixedBase=False
+timeStep = 1. / 600
+useFixedBase = False
humanoid = humanoid_stable_pd.HumanoidStablePD(pybullet_client, mocapData, timeStep, useFixedBase)
isInitialized = True
pybullet_client.setTimeStep(timeStep)
pybullet_client.setPhysicsEngineParameter(numSubSteps=2)
-timeId = pybullet_client.addUserDebugParameter("time",0,10,0)
+timeId = pybullet_client.addUserDebugParameter("time", 0, 10, 0)
+
-
def isKeyTriggered(keys, key):
o = ord(key)
if o in keys:
return keys[ord(key)] & pybullet_client.KEY_WAS_TRIGGERED
return False
-
+
+
animating = False
singleStep = False
-
-t=0
+t = 0
while (1):
keys = pybullet_client.getKeyboardEvents()
#print(keys)
if isKeyTriggered(keys, ' '):
- animating = not animating
+ animating = not animating
if isKeyTriggered(keys, 'b'):
- singleStep = True
-
+ singleStep = True
+
if animating or singleStep:
-
-
+
singleStep = False
#t = pybullet_client.readUserDebugParameter(timeId)
#print("t=",t)
- for i in range (1):
+ for i in range(1):
- print("t=",t)
+ print("t=", t)
humanoid.setSimTime(t)
-
+
humanoid.computePose(humanoid._frameFraction)
pose = humanoid._poseInterpolator
#humanoid.initializePose(pose=pose, phys_model = humanoid._sim_model, initBase=True, initializeVelocity=True)
#humanoid.resetPose()
-
-
+
desiredPose = humanoid.computePose(humanoid._frameFraction)
- #desiredPose = desiredPose.GetPose()
+ #desiredPose = desiredPose.GetPose()
#curPose = HumanoidPoseInterpolator()
#curPose.reset()
s = humanoid.getState()
#np.savetxt("pb_record_state_s.csv", s, delimiter=",")
- maxForces = [0,0,0,0,0,0,0,200,200,200,200, 50,50,50,50, 200,200,200,200, 150, 90,90,90,90, 100,100,100,100, 60, 200,200,200,200, 150, 90, 90, 90, 90, 100,100,100,100, 60]
+ maxForces = [
+ 0, 0, 0, 0, 0, 0, 0, 200, 200, 200, 200, 50, 50, 50, 50, 200, 200, 200, 200, 150, 90, 90,
+ 90, 90, 100, 100, 100, 100, 60, 200, 200, 200, 200, 150, 90, 90, 90, 90, 100, 100, 100,
+ 100, 60
+ ]
taus = humanoid.computePDForces(desiredPose, desiredVelocities=None, maxForces=maxForces)
-
+
#print("taus=",taus)
humanoid.applyPDForces(taus)
-
+
pybullet_client.stepSimulation()
- t+=1./600.
-
-
- time.sleep(1./600.) \ No newline at end of file
+ t += 1. / 600.
+
+ time.sleep(1. / 600.)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py
index c7543639f..ef2b21c33 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/testLaikago.py
@@ -8,240 +8,258 @@ import motion_capture_data
import quadrupedPoseInterpolator
useConstraints = False
-
-p = bullet_client.BulletClient(connection_mode=p1.GUI)
+
+p = bullet_client.BulletClient(connection_mode=p1.GUI)
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane = p.loadURDF("plane.urdf")
-p.setGravity(0,0,-10)
-timeStep=1./500
+p.setGravity(0, 0, -10)
+timeStep = 1. / 500
p.setTimeStep(timeStep)
#p.setDefaultContactERP(0)
-#urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
+#urdfFlags = p.URDF_USE_SELF_COLLISION+p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS
urdfFlags = p.URDF_USE_SELF_COLLISION
-
-startPos=[0.007058990464444105, 0.03149299192130908, 0.4918981912395484]
-startOrn=[0.005934649695708604, 0.7065453990917289, 0.7076373820553712, -0.0027774940359030264]
-quadruped = p.loadURDF("laikago/laikago.urdf",startPos,startOrn, flags = urdfFlags,useFixedBase=False)
-p.resetBasePositionAndOrientation(quadruped,startPos,startOrn)
+startPos = [0.007058990464444105, 0.03149299192130908, 0.4918981912395484]
+startOrn = [0.005934649695708604, 0.7065453990917289, 0.7076373820553712, -0.0027774940359030264]
+quadruped = p.loadURDF("laikago/laikago.urdf",
+ startPos,
+ startOrn,
+ flags=urdfFlags,
+ useFixedBase=False)
+p.resetBasePositionAndOrientation(quadruped, startPos, startOrn)
if not useConstraints:
for j in range(p.getNumJoints(quadruped)):
- p.setJointMotorControl2(quadruped,j,p.POSITION_CONTROL,force=0)
-
-#This cube is added as a soft constraint to keep the laikago from falling
+ p.setJointMotorControl2(quadruped, j, p.POSITION_CONTROL, force=0)
+
+#This cube is added as a soft constraint to keep the laikago from falling
#since we didn't train it yet, it doesn't balance
-cube = p.loadURDF("cube_no_rotation.urdf",[0,0,-0.5],[0,0.5,0.5,0])
-p.setCollisionFilterGroupMask(cube,-1,0,0)
+cube = p.loadURDF("cube_no_rotation.urdf", [0, 0, -0.5], [0, 0.5, 0.5, 0])
+p.setCollisionFilterGroupMask(cube, -1, 0, 0)
for j in range(p.getNumJoints(cube)):
- p.setJointMotorControl2(cube,j,p.POSITION_CONTROL,force=0)
- p.setCollisionFilterGroupMask(cube,j,0,0)
- p.changeVisualShape(cube,j,rgbaColor=[1,0,0,0])
-cid = p.createConstraint(cube,p.getNumJoints(cube)-1,quadruped,-1,p.JOINT_FIXED,[0,0,0],[0,1,0],[0,0,0])
+ p.setJointMotorControl2(cube, j, p.POSITION_CONTROL, force=0)
+ p.setCollisionFilterGroupMask(cube, j, 0, 0)
+ p.changeVisualShape(cube, j, rgbaColor=[1, 0, 0, 0])
+cid = p.createConstraint(cube,
+ p.getNumJoints(cube) - 1, quadruped, -1, p.JOINT_FIXED, [0, 0, 0],
+ [0, 1, 0], [0, 0, 0])
p.changeConstraint(cid, maxForce=10)
+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)
-
-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)
+maxForceId = p.addUserDebugParameter("maxForce", 0, 100, 20)
-
-startQ=[0.08389, 0.8482, -1.547832, -0.068933, 0.625726, -1.272086, 0.074398, 0.61135, -1.255892, -0.068262, 0.836745, -1.534517]
for j in range(p.getNumJoints(quadruped)):
- p.resetJointState(quadruped,jointIds[j],jointDirections[j]*startQ[j]+jointOffsets[j])
-
+ 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)
+
+startQ = [
+ 0.08389, 0.8482, -1.547832, -0.068933, 0.625726, -1.272086, 0.074398, 0.61135, -1.255892,
+ -0.068262, 0.836745, -1.534517
+]
+for j in range(p.getNumJoints(quadruped)):
+ p.resetJointState(quadruped, jointIds[j], jointDirections[j] * startQ[j] + jointOffsets[j])
qpi = quadrupedPoseInterpolator.QuadrupedPoseInterpolator()
#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):
- 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)
-
-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):
- jointOffsets.append(0)
- jointOffsets.append(-0.7)
- jointOffsets.append(0.7)
-
-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)
-
-
-p.getCameraImage(480,320)
-p.setRealTimeSimulation(0)
+ for l1 in lower_legs:
+ 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)
+
+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):
+ jointOffsets.append(0)
+ jointOffsets.append(-0.7)
+ jointOffsets.append(0.7)
+
+maxForceId = p.addUserDebugParameter("maxForce", 0, 100, 20)
-joints=[]
+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.setRealTimeSimulation(0)
+joints = []
mocapData = motion_capture_data.MotionCaptureData()
-motionPath = pybullet_data.getDataPath()+"/data/motions/laikago_walk.txt"
+motionPath = pybullet_data.getDataPath() + "/data/motions/laikago_walk.txt"
mocapData.Load(motionPath)
-print("mocapData.NumFrames=",mocapData.NumFrames())
-print("mocapData.KeyFrameDuraction=",mocapData.KeyFrameDuraction())
-print("mocapData.getCycleTime=",mocapData.getCycleTime())
-print("mocapData.computeCycleOffset=",mocapData.computeCycleOffset())
+print("mocapData.NumFrames=", mocapData.NumFrames())
+print("mocapData.KeyFrameDuraction=", mocapData.KeyFrameDuraction())
+print("mocapData.getCycleTime=", mocapData.getCycleTime())
+print("mocapData.computeCycleOffset=", mocapData.computeCycleOffset())
stablePD = pd_controller_stable.PDControllerStable(p)
cycleTime = mocapData.getCycleTime()
-t=0
+t = 0
-while t<10.*cycleTime:
+while t < 10. * cycleTime:
#get interpolated joint
keyFrameDuration = mocapData.KeyFrameDuraction()
cycleTime = mocapData.getCycleTime()
cycleCount = mocapData.calcCycleCount(t, cycleTime)
-
+
#print("cycleTime=",cycleTime)
#print("cycleCount=",cycleCount)
-
+
#print("cycles=",cycles)
- frameTime = t - cycleCount*cycleTime
+ frameTime = t - cycleCount * cycleTime
#print("frameTime=",frameTime)
- if (frameTime<0):
+ if (frameTime < 0):
frameTime += cycleTime
- frame = int(frameTime/keyFrameDuration)
- frameNext = frame+1
- if (frameNext >= mocapData.NumFrames()):
+ frame = int(frameTime / keyFrameDuration)
+ frameNext = frame + 1
+ if (frameNext >= mocapData.NumFrames()):
frameNext = frame
- frameFraction = (frameTime - frame*keyFrameDuration)/(keyFrameDuration)
+ frameFraction = (frameTime - frame * keyFrameDuration) / (keyFrameDuration)
#print("frame=",frame)
#print("frameFraction=",frameFraction)
frameData = mocapData._motion_data['Frames'][frame]
frameDataNext = mocapData._motion_data['Frames'][frameNext]
-
- jointsStr,qdot=qpi.Slerp(frameFraction, frameData, frameDataNext, p)
-
+
+ jointsStr, qdot = qpi.Slerp(frameFraction, frameData, frameDataNext, p)
+
maxForce = p.readUserDebugParameter(maxForceId)
- print("jointIds=",jointIds)
+ print("jointIds=", jointIds)
if useConstraints:
- for j in range (12):
+ for j in range(12):
#skip the base positional dofs
- targetPos = float(jointsStr[j+7])
- p.setJointMotorControl2(quadruped,jointIds[j],p.POSITION_CONTROL,jointDirections[j]*targetPos+jointOffsets[j], force=maxForce)
-
+ targetPos = float(jointsStr[j + 7])
+ p.setJointMotorControl2(quadruped,
+ jointIds[j],
+ p.POSITION_CONTROL,
+ jointDirections[j] * targetPos + jointOffsets[j],
+ force=maxForce)
+
else:
- desiredPositions=[]
- for j in range (7):
+ desiredPositions = []
+ for j in range(7):
targetPosUnmodified = float(jointsStr[j])
desiredPositions.append(targetPosUnmodified)
- for j in range (12):
- targetPosUnmodified = float(jointsStr[j+7])
- targetPos=jointDirections[j]*targetPosUnmodified+jointOffsets[j]
+ for j in range(12):
+ targetPosUnmodified = float(jointsStr[j + 7])
+ targetPos = jointDirections[j] * targetPosUnmodified + jointOffsets[j]
desiredPositions.append(targetPos)
- numBaseDofs=6
- totalDofs=12+numBaseDofs
- desiredVelocities=None
- if desiredVelocities==None:
- desiredVelocities = [0]*totalDofs
- taus = stablePD.computePD(bodyUniqueId=quadruped,
- jointIndices = jointIds,
- desiredPositions = desiredPositions,
- desiredVelocities = desiredVelocities,
- kps = [4000]*totalDofs,
- kds = [40]*totalDofs,
- maxForces = [500]*totalDofs,
- timeStep=timeStep)
-
- dofIndex=6
+ numBaseDofs = 6
+ totalDofs = 12 + numBaseDofs
+ desiredVelocities = None
+ if desiredVelocities == None:
+ desiredVelocities = [0] * totalDofs
+ taus = stablePD.computePD(bodyUniqueId=quadruped,
+ jointIndices=jointIds,
+ desiredPositions=desiredPositions,
+ desiredVelocities=desiredVelocities,
+ kps=[4000] * totalDofs,
+ kds=[40] * totalDofs,
+ maxForces=[500] * totalDofs,
+ timeStep=timeStep)
+
+ dofIndex = 6
scaling = 1
- for index in range (len(jointIds)):
+ for index in range(len(jointIds)):
jointIndex = jointIds[index]
- force=[scaling*taus[dofIndex]]
- print("force[", jointIndex,"]=",force)
- p.setJointMotorControlMultiDof(quadruped, jointIndex, controlMode=p.TORQUE_CONTROL, force=force)
- dofIndex+=1
-
+ force = [scaling * taus[dofIndex]]
+ print("force[", jointIndex, "]=", force)
+ p.setJointMotorControlMultiDof(quadruped,
+ jointIndex,
+ controlMode=p.TORQUE_CONTROL,
+ force=force)
+ dofIndex += 1
p.stepSimulation()
- t+=timeStep
+ t += timeStep
time.sleep(timeStep)
-useOrgData=False
+useOrgData = False
if useOrgData:
- with open("data1.txt","r") as filestream:
- for line in filestream:
- maxForce = p.readUserDebugParameter(maxForceId)
- currentline = line.split(",")
- frame = currentline[0]
- t = currentline[1]
- joints=currentline[2:14]
- 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.stepSimulation()
- for lower_leg in lower_legs:
- #print("points for ", quadruped, " link: ", 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]))
+ with open("data1.txt", "r") as filestream:
+ for line in filestream:
+ maxForce = p.readUserDebugParameter(maxForceId)
+ currentline = line.split(",")
+ frame = currentline[0]
+ t = currentline[1]
+ joints = currentline[2:14]
+ 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.stepSimulation()
+ for lower_leg in lower_legs:
+ #print("points for ", quadruped, " link: ", 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]))
p.setRealTimeSimulation(1)
while (1):
-
- for i in range(len(paramIds)):
- 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)
-
+
+ for i in range(len(paramIds)):
+ 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)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/agent_builder.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/agent_builder.py
index e2047da98..cf67210da 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/agent_builder.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/agent_builder.py
@@ -5,17 +5,18 @@ import pybullet_data
AGENT_TYPE_KEY = "AgentType"
+
def build_agent(world, id, file):
- agent = None
- with open(pybullet_data.getDataPath()+"/"+file) as data_file:
- json_data = json.load(data_file)
-
- assert AGENT_TYPE_KEY in json_data
- agent_type = json_data[AGENT_TYPE_KEY]
-
- if (agent_type == PPOAgent.NAME):
- agent = PPOAgent(world, id, json_data)
- else:
- assert False, 'Unsupported agent type: ' + agent_type
+ agent = None
+ with open(pybullet_data.getDataPath() + "/" + file) as data_file:
+ json_data = json.load(data_file)
+
+ assert AGENT_TYPE_KEY in json_data
+ agent_type = json_data[AGENT_TYPE_KEY]
+
+ if (agent_type == PPOAgent.NAME):
+ agent = PPOAgent(world, id, json_data)
+ else:
+ assert False, 'Unsupported agent type: ' + agent_type
- return agent
+ return agent
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/exp_params.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/exp_params.py
index 07c83e0f2..4a01dfec9 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/exp_params.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/exp_params.py
@@ -2,53 +2,54 @@ import json
import numpy as np
import pybullet_utils.math_util as MathUtil
+
class ExpParams(object):
- RATE_KEY = 'Rate'
- INIT_ACTION_RATE_KEY = 'InitActionRate'
- NOISE_KEY = 'Noise'
- NOISE_INTERNAL_KEY = 'NoiseInternal'
- TEMP_KEY = 'Temp'
-
- def __init__(self):
- self.rate = 0.2
- self.init_action_rate = 0
- self.noise = 0.1
- self.noise_internal = 0
- self.temp = 0.1
- return
-
- def __str__(self):
- str = ''
- str += '{}: {:.2f}\n'.format(self.RATE_KEY, self.rate)
- str += '{}: {:.2f}\n'.format(self.INIT_ACTION_RATE_KEY, self.init_action_rate)
- str += '{}: {:.2f}\n'.format(self.NOISE_KEY, self.noise)
- str += '{}: {:.2f}\n'.format(self.NOISE_INTERNAL_KEY, self.noise_internal)
- str += '{}: {:.2f}\n'.format(self.TEMP_KEY, self.temp)
- return str
-
- def load(self, json_data):
- if (self.RATE_KEY in json_data):
- self.rate = json_data[self.RATE_KEY]
-
- if (self.INIT_ACTION_RATE_KEY in json_data):
- self.init_action_rate = json_data[self.INIT_ACTION_RATE_KEY]
-
- if (self.NOISE_KEY in json_data):
- self.noise = json_data[self.NOISE_KEY]
-
- if (self.NOISE_INTERNAL_KEY in json_data):
- self.noise_internal = json_data[self.NOISE_INTERNAL_KEY]
-
- if (self.TEMP_KEY in json_data):
- self.temp = json_data[self.TEMP_KEY]
-
- return
-
- def lerp(self, other, t):
- lerp_params = ExpParams()
- lerp_params.rate = MathUtil.lerp(self.rate, other.rate, t)
- lerp_params.init_action_rate = MathUtil.lerp(self.init_action_rate, other.init_action_rate, t)
- lerp_params.noise = MathUtil.lerp(self.noise, other.noise, t)
- lerp_params.noise_internal = MathUtil.lerp(self.noise_internal, other.noise_internal, t)
- lerp_params.temp = MathUtil.log_lerp(self.temp, other.temp, t)
- return lerp_params \ No newline at end of file
+ RATE_KEY = 'Rate'
+ INIT_ACTION_RATE_KEY = 'InitActionRate'
+ NOISE_KEY = 'Noise'
+ NOISE_INTERNAL_KEY = 'NoiseInternal'
+ TEMP_KEY = 'Temp'
+
+ def __init__(self):
+ self.rate = 0.2
+ self.init_action_rate = 0
+ self.noise = 0.1
+ self.noise_internal = 0
+ self.temp = 0.1
+ return
+
+ def __str__(self):
+ str = ''
+ str += '{}: {:.2f}\n'.format(self.RATE_KEY, self.rate)
+ str += '{}: {:.2f}\n'.format(self.INIT_ACTION_RATE_KEY, self.init_action_rate)
+ str += '{}: {:.2f}\n'.format(self.NOISE_KEY, self.noise)
+ str += '{}: {:.2f}\n'.format(self.NOISE_INTERNAL_KEY, self.noise_internal)
+ str += '{}: {:.2f}\n'.format(self.TEMP_KEY, self.temp)
+ return str
+
+ def load(self, json_data):
+ if (self.RATE_KEY in json_data):
+ self.rate = json_data[self.RATE_KEY]
+
+ if (self.INIT_ACTION_RATE_KEY in json_data):
+ self.init_action_rate = json_data[self.INIT_ACTION_RATE_KEY]
+
+ if (self.NOISE_KEY in json_data):
+ self.noise = json_data[self.NOISE_KEY]
+
+ if (self.NOISE_INTERNAL_KEY in json_data):
+ self.noise_internal = json_data[self.NOISE_INTERNAL_KEY]
+
+ if (self.TEMP_KEY in json_data):
+ self.temp = json_data[self.TEMP_KEY]
+
+ return
+
+ def lerp(self, other, t):
+ lerp_params = ExpParams()
+ lerp_params.rate = MathUtil.lerp(self.rate, other.rate, t)
+ lerp_params.init_action_rate = MathUtil.lerp(self.init_action_rate, other.init_action_rate, t)
+ lerp_params.noise = MathUtil.lerp(self.noise, other.noise, t)
+ lerp_params.noise_internal = MathUtil.lerp(self.noise_internal, other.noise_internal, t)
+ lerp_params.temp = MathUtil.log_lerp(self.temp, other.temp, t)
+ return lerp_params
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/__init__.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/__init__.py
index b9742821a..1e136c6c4 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/__init__.py
@@ -1 +1 @@
-from . import * \ No newline at end of file
+from . import *
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/fc_2layers_1024units.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/fc_2layers_1024units.py
index b4d466124..a0f627639 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/fc_2layers_1024units.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/fc_2layers_1024units.py
@@ -3,11 +3,12 @@ import pybullet_envs.deep_mimic.learning.tf_util as TFUtil
NAME = "fc_2layers_1024units"
+
def build_net(input_tfs, reuse=False):
- layers = [1024, 512]
- activation = tf.nn.relu
+ layers = [1024, 512]
+ activation = tf.nn.relu
- input_tf = tf.concat(axis=-1, values=input_tfs)
- h = TFUtil.fc_net(input_tf, layers, activation=activation, reuse=reuse)
- h = activation(h)
- return h \ No newline at end of file
+ input_tf = tf.concat(axis=-1, values=input_tfs)
+ h = TFUtil.fc_net(input_tf, layers, activation=activation, reuse=reuse)
+ h = activation(h)
+ return h
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/net_builder.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/net_builder.py
index 32328493b..1441bffd9 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/net_builder.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/nets/net_builder.py
@@ -1,11 +1,12 @@
import pybullet_envs.deep_mimic.learning.nets.fc_2layers_1024units as fc_2layers_1024units
+
def build_net(net_name, input_tfs, reuse=False):
- net = None
-
- if (net_name == fc_2layers_1024units.NAME):
- net = fc_2layers_1024units.build_net(input_tfs, reuse)
- else:
- assert False, 'Unsupported net: ' + net_name
-
- return net \ No newline at end of file
+ net = None
+
+ if (net_name == fc_2layers_1024units.NAME):
+ net = fc_2layers_1024units.build_net(input_tfs, reuse)
+ else:
+ assert False, 'Unsupported net: ' + net_name
+
+ return net
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/normalizer.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/normalizer.py
index 74bf90569..8feabc7f9 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/normalizer.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/normalizer.py
@@ -3,147 +3,149 @@ import copy
import pybullet_utils.mpi_util as MPIUtil
from pybullet_utils.logger import Logger
+
class Normalizer(object):
- CHECK_SYNC_COUNT = 50000 # check synchronization after a certain number of entries
-
- # these group IDs must be the same as those in CharController.h
- NORM_GROUP_SINGLE = 0
- NORM_GROUP_NONE = -1
-
- class Group(object):
- def __init__(self, id, indices):
- self.id = id
- self.indices = indices
- return
-
- def __init__(self, size, groups_ids=None, eps=0.02, clip=np.inf):
- self.eps = eps
- self.clip = clip
- self.mean = np.zeros(size)
- self.mean_sq = np.zeros(size)
- self.std = np.ones(size)
- self.count = 0
- self.groups = self._build_groups(groups_ids)
-
- self.new_count = 0
- self.new_sum = np.zeros_like(self.mean)
- self.new_sum_sq = np.zeros_like(self.mean_sq)
- return
-
- def record(self, x):
- size = self.get_size()
- is_array = isinstance(x, np.ndarray)
- if not is_array:
- assert(size == 1)
- x = np.array([[x]])
-
- assert x.shape[-1] == size, \
- Logger.print2('Normalizer shape mismatch, expecting size {:d}, but got {:d}'.format(size, x.shape[-1]))
- x = np.reshape(x, [-1, size])
-
- self.new_count += x.shape[0]
- self.new_sum += np.sum(x, axis=0)
- self.new_sum_sq += np.sum(np.square(x), axis=0)
- return
-
- def update(self):
- new_count = MPIUtil.reduce_sum(self.new_count)
- new_sum = MPIUtil.reduce_sum(self.new_sum)
- new_sum_sq = MPIUtil.reduce_sum(self.new_sum_sq)
-
- new_total = self.count + new_count
- if (self.count // self.CHECK_SYNC_COUNT != new_total // self.CHECK_SYNC_COUNT):
- assert self.check_synced(), Logger.print2('Normalizer parameters desynchronized')
-
- if new_count > 0:
- new_mean = self._process_group_data(new_sum / new_count, self.mean)
- new_mean_sq = self._process_group_data(new_sum_sq / new_count, self.mean_sq)
- w_old = float(self.count) / new_total
- w_new = float(new_count) / new_total
-
- self.mean = w_old * self.mean + w_new * new_mean
- self.mean_sq = w_old * self.mean_sq + w_new * new_mean_sq
- self.count = new_total
- self.std = self.calc_std(self.mean, self.mean_sq)
-
- self.new_count = 0
- self.new_sum.fill(0)
- self.new_sum_sq.fill(0)
-
- return
-
- def get_size(self):
- return self.mean.size
-
- def set_mean_std(self, mean, std):
- size = self.get_size()
- is_array = isinstance(mean, np.ndarray) and isinstance(std, np.ndarray)
-
- if not is_array:
- assert(size == 1)
- mean = np.array([mean])
- std = np.array([std])
-
- assert len(mean) == size and len(std) == size, \
- Logger.print2('Normalizer shape mismatch, expecting size {:d}, but got {:d} and {:d}'.format(size, len(mean), len(std)))
-
- self.mean = mean
- self.std = std
- self.mean_sq = self.calc_mean_sq(self.mean, self.std)
- return
-
- def normalize(self, x):
- norm_x = (x - self.mean) / self.std
- norm_x = np.clip(norm_x, -self.clip, self.clip)
- return norm_x
-
- def unnormalize(self, norm_x):
- x = norm_x * self.std + self.mean
- return x
-
- def calc_std(self, mean, mean_sq):
- var = mean_sq - np.square(mean)
- # some time floating point errors can lead to small negative numbers
- var = np.maximum(var, 0)
- std = np.sqrt(var)
- std = np.maximum(std, self.eps)
- return std
-
- def calc_mean_sq(self, mean, std):
- return np.square(std) + np.square(self.mean)
-
- def check_synced(self):
- synced = True
- if MPIUtil.is_root_proc():
- vars = np.concatenate([self.mean, self.mean_sq])
- MPIUtil.bcast(vars)
- else:
- vars_local = np.concatenate([self.mean, self.mean_sq])
- vars_root = np.empty_like(vars_local)
- MPIUtil.bcast(vars_root)
- synced = (vars_local == vars_root).all()
- return synced
-
- def _build_groups(self, groups_ids):
- groups = []
- if groups_ids is None:
- curr_id = self.NORM_GROUP_SINGLE
- curr_list = np.arange(self.get_size()).astype(np.int32)
- groups.append(self.Group(curr_id, curr_list))
- else:
- ids = np.unique(groups_ids)
- for id in ids:
- curr_list = np.nonzero(groups_ids == id)[0].astype(np.int32)
- groups.append(self.Group(id, curr_list))
-
- return groups
-
- def _process_group_data(self, new_data, old_data):
- proc_data = new_data.copy()
- for group in self.groups:
- if group.id == self.NORM_GROUP_NONE:
- proc_data[group.indices] = old_data[group.indices]
- elif group.id != self.NORM_GROUP_SINGLE:
- avg = np.mean(new_data[group.indices])
- proc_data[group.indices] = avg
- return proc_data \ No newline at end of file
+ CHECK_SYNC_COUNT = 50000 # check synchronization after a certain number of entries
+
+ # these group IDs must be the same as those in CharController.h
+ NORM_GROUP_SINGLE = 0
+ NORM_GROUP_NONE = -1
+
+ class Group(object):
+
+ def __init__(self, id, indices):
+ self.id = id
+ self.indices = indices
+ return
+
+ def __init__(self, size, groups_ids=None, eps=0.02, clip=np.inf):
+ self.eps = eps
+ self.clip = clip
+ self.mean = np.zeros(size)
+ self.mean_sq = np.zeros(size)
+ self.std = np.ones(size)
+ self.count = 0
+ self.groups = self._build_groups(groups_ids)
+
+ self.new_count = 0
+ self.new_sum = np.zeros_like(self.mean)
+ self.new_sum_sq = np.zeros_like(self.mean_sq)
+ return
+
+ def record(self, x):
+ size = self.get_size()
+ is_array = isinstance(x, np.ndarray)
+ if not is_array:
+ assert (size == 1)
+ x = np.array([[x]])
+
+ assert x.shape[-1] == size, \
+ Logger.print2('Normalizer shape mismatch, expecting size {:d}, but got {:d}'.format(size, x.shape[-1]))
+ x = np.reshape(x, [-1, size])
+
+ self.new_count += x.shape[0]
+ self.new_sum += np.sum(x, axis=0)
+ self.new_sum_sq += np.sum(np.square(x), axis=0)
+ return
+
+ def update(self):
+ new_count = MPIUtil.reduce_sum(self.new_count)
+ new_sum = MPIUtil.reduce_sum(self.new_sum)
+ new_sum_sq = MPIUtil.reduce_sum(self.new_sum_sq)
+
+ new_total = self.count + new_count
+ if (self.count // self.CHECK_SYNC_COUNT != new_total // self.CHECK_SYNC_COUNT):
+ assert self.check_synced(), Logger.print2('Normalizer parameters desynchronized')
+
+ if new_count > 0:
+ new_mean = self._process_group_data(new_sum / new_count, self.mean)
+ new_mean_sq = self._process_group_data(new_sum_sq / new_count, self.mean_sq)
+ w_old = float(self.count) / new_total
+ w_new = float(new_count) / new_total
+
+ self.mean = w_old * self.mean + w_new * new_mean
+ self.mean_sq = w_old * self.mean_sq + w_new * new_mean_sq
+ self.count = new_total
+ self.std = self.calc_std(self.mean, self.mean_sq)
+
+ self.new_count = 0
+ self.new_sum.fill(0)
+ self.new_sum_sq.fill(0)
+
+ return
+
+ def get_size(self):
+ return self.mean.size
+
+ def set_mean_std(self, mean, std):
+ size = self.get_size()
+ is_array = isinstance(mean, np.ndarray) and isinstance(std, np.ndarray)
+
+ if not is_array:
+ assert (size == 1)
+ mean = np.array([mean])
+ std = np.array([std])
+
+ assert len(mean) == size and len(std) == size, \
+ Logger.print2('Normalizer shape mismatch, expecting size {:d}, but got {:d} and {:d}'.format(size, len(mean), len(std)))
+
+ self.mean = mean
+ self.std = std
+ self.mean_sq = self.calc_mean_sq(self.mean, self.std)
+ return
+
+ def normalize(self, x):
+ norm_x = (x - self.mean) / self.std
+ norm_x = np.clip(norm_x, -self.clip, self.clip)
+ return norm_x
+
+ def unnormalize(self, norm_x):
+ x = norm_x * self.std + self.mean
+ return x
+
+ def calc_std(self, mean, mean_sq):
+ var = mean_sq - np.square(mean)
+ # some time floating point errors can lead to small negative numbers
+ var = np.maximum(var, 0)
+ std = np.sqrt(var)
+ std = np.maximum(std, self.eps)
+ return std
+
+ def calc_mean_sq(self, mean, std):
+ return np.square(std) + np.square(self.mean)
+
+ def check_synced(self):
+ synced = True
+ if MPIUtil.is_root_proc():
+ vars = np.concatenate([self.mean, self.mean_sq])
+ MPIUtil.bcast(vars)
+ else:
+ vars_local = np.concatenate([self.mean, self.mean_sq])
+ vars_root = np.empty_like(vars_local)
+ MPIUtil.bcast(vars_root)
+ synced = (vars_local == vars_root).all()
+ return synced
+
+ def _build_groups(self, groups_ids):
+ groups = []
+ if groups_ids is None:
+ curr_id = self.NORM_GROUP_SINGLE
+ curr_list = np.arange(self.get_size()).astype(np.int32)
+ groups.append(self.Group(curr_id, curr_list))
+ else:
+ ids = np.unique(groups_ids)
+ for id in ids:
+ curr_list = np.nonzero(groups_ids == id)[0].astype(np.int32)
+ groups.append(self.Group(id, curr_list))
+
+ return groups
+
+ def _process_group_data(self, new_data, old_data):
+ proc_data = new_data.copy()
+ for group in self.groups:
+ if group.id == self.NORM_GROUP_NONE:
+ proc_data[group.indices] = old_data[group.indices]
+ elif group.id != self.NORM_GROUP_SINGLE:
+ avg = np.mean(new_data[group.indices])
+ proc_data[group.indices] = avg
+ return proc_data
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/path.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/path.py
index c6855491e..37ae1146c 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/path.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/path.py
@@ -1,46 +1,47 @@
import numpy as np
from pybullet_envs.deep_mimic.env.env import Env
+
class Path(object):
- def __init__(self):
- self.clear()
- return
-
- def pathlength(self):
- return len(self.actions)
-
- def is_valid(self):
- valid = True
- l = self.pathlength()
- valid &= len(self.states) == l + 1
- valid &= len(self.goals) == l + 1
- valid &= len(self.actions) == l
- valid &= len(self.logps) == l
- valid &= len(self.rewards) == l
- valid &= len(self.flags) == l
-
- return valid
-
- def check_vals(self):
- for vals in [self.states, self.goals, self.actions, self.logps,
- self.rewards]:
- for v in vals:
- if not np.isfinite(v).all():
- return False
- return True
-
- def clear(self):
- self.states = []
- self.goals = []
- self.actions = []
- self.logps = []
- self.rewards = []
- self.flags = []
- self.terminate = Env.Terminate.Null
- return
-
- def get_pathlen(self):
- return len(self.rewards)
-
- def calc_return(self):
- return sum(self.rewards) \ No newline at end of file
+
+ def __init__(self):
+ self.clear()
+ return
+
+ def pathlength(self):
+ return len(self.actions)
+
+ def is_valid(self):
+ valid = True
+ l = self.pathlength()
+ valid &= len(self.states) == l + 1
+ valid &= len(self.goals) == l + 1
+ valid &= len(self.actions) == l
+ valid &= len(self.logps) == l
+ valid &= len(self.rewards) == l
+ valid &= len(self.flags) == l
+
+ return valid
+
+ def check_vals(self):
+ for vals in [self.states, self.goals, self.actions, self.logps, self.rewards]:
+ for v in vals:
+ if not np.isfinite(v).all():
+ return False
+ return True
+
+ def clear(self):
+ self.states = []
+ self.goals = []
+ self.actions = []
+ self.logps = []
+ self.rewards = []
+ self.flags = []
+ self.terminate = Env.Terminate.Null
+ return
+
+ def get_pathlen(self):
+ return len(self.rewards)
+
+ def calc_return(self):
+ return sum(self.rewards)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/pg_agent.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/pg_agent.py
index 75d1bae9a..2787e2356 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/pg_agent.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/pg_agent.py
@@ -13,341 +13,343 @@ import pybullet_utils.mpi_util as MPIUtil
import pybullet_utils.math_util as MathUtil
from pybullet_envs.deep_mimic.env.action_space import ActionSpace
from pybullet_envs.deep_mimic.env.env import Env
-
'''
Policy Gradient Agent
'''
+
class PGAgent(TFAgent):
- NAME = 'PG'
-
- ACTOR_NET_KEY = 'ActorNet'
- ACTOR_STEPSIZE_KEY = 'ActorStepsize'
- ACTOR_MOMENTUM_KEY = 'ActorMomentum'
- ACTOR_WEIGHT_DECAY_KEY = 'ActorWeightDecay'
- ACTOR_INIT_OUTPUT_SCALE_KEY = 'ActorInitOutputScale'
-
- CRITIC_NET_KEY = 'CriticNet'
- CRITIC_STEPSIZE_KEY = 'CriticStepsize'
- CRITIC_MOMENTUM_KEY = 'CriticMomentum'
- CRITIC_WEIGHT_DECAY_KEY = 'CriticWeightDecay'
-
- EXP_ACTION_FLAG = 1 << 0
-
- def __init__(self, world, id, json_data):
- self._exp_action = False
- super().__init__(world, id, json_data)
- return
-
- def reset(self):
- super().reset()
- self._exp_action = False
- return
-
- def _check_action_space(self):
- action_space = self.get_action_space()
- return action_space == ActionSpace.Continuous
-
- def _load_params(self, json_data):
- super()._load_params(json_data)
- self.val_min, self.val_max = self._calc_val_bounds(self.discount)
- self.val_fail, self.val_succ = self._calc_term_vals(self.discount)
- return
-
- def _build_nets(self, json_data):
- assert self.ACTOR_NET_KEY in json_data
- assert self.CRITIC_NET_KEY in json_data
-
- actor_net_name = json_data[self.ACTOR_NET_KEY]
- critic_net_name = json_data[self.CRITIC_NET_KEY]
- actor_init_output_scale = 1 if (self.ACTOR_INIT_OUTPUT_SCALE_KEY not in json_data) else json_data[self.ACTOR_INIT_OUTPUT_SCALE_KEY]
-
- s_size = self.get_state_size()
- g_size = self.get_goal_size()
- a_size = self.get_action_size()
-
- # setup input tensors
- self.s_tf = tf.placeholder(tf.float32, shape=[None, s_size], name="s") # observations
- self.tar_val_tf = tf.placeholder(tf.float32, shape=[None], name="tar_val") # target value s
- self.adv_tf = tf.placeholder(tf.float32, shape=[None], name="adv") # advantage
- self.a_tf = tf.placeholder(tf.float32, shape=[None, a_size], name="a") # target actions
- self.g_tf = tf.placeholder(tf.float32, shape=([None, g_size] if self.has_goal() else None), name="g") # goals
-
- with tf.variable_scope('main'):
- with tf.variable_scope('actor'):
- self.actor_tf = self._build_net_actor(actor_net_name, actor_init_output_scale)
- with tf.variable_scope('critic'):
- self.critic_tf = self._build_net_critic(critic_net_name)
-
- if (self.actor_tf != None):
- Logger.print2('Built actor net: ' + actor_net_name)
-
- if (self.critic_tf != None):
- Logger.print2('Built critic net: ' + critic_net_name)
-
- return
-
- def _build_normalizers(self):
- super()._build_normalizers()
- with self.sess.as_default(), self.graph.as_default(), tf.variable_scope(self.tf_scope):
- with tf.variable_scope(self.RESOURCE_SCOPE):
- val_offset, val_scale = self._calc_val_offset_scale(self.discount)
- self.val_norm = TFNormalizer(self.sess, 'val_norm', 1)
- self.val_norm.set_mean_std(-val_offset, 1.0 / val_scale)
- return
-
- def _init_normalizers(self):
- super()._init_normalizers()
- with self.sess.as_default(), self.graph.as_default():
- self.val_norm.update()
- return
-
- def _load_normalizers(self):
- super()._load_normalizers()
- self.val_norm.load()
- return
-
- def _build_losses(self, json_data):
- actor_weight_decay = 0 if (self.ACTOR_WEIGHT_DECAY_KEY not in json_data) else json_data[self.ACTOR_WEIGHT_DECAY_KEY]
- critic_weight_decay = 0 if (self.CRITIC_WEIGHT_DECAY_KEY not in json_data) else json_data[self.CRITIC_WEIGHT_DECAY_KEY]
-
- norm_val_diff = self.val_norm.normalize_tf(self.tar_val_tf) - self.val_norm.normalize_tf(self.critic_tf)
- self.critic_loss_tf = 0.5 * tf.reduce_mean(tf.square(norm_val_diff))
-
- if (critic_weight_decay != 0):
- self.critic_loss_tf += critic_weight_decay * self._weight_decay_loss('main/critic')
-
- norm_a_mean_tf = self.a_norm.normalize_tf(self.actor_tf)
- norm_a_diff = self.a_norm.normalize_tf(self.a_tf) - norm_a_mean_tf
-
- self.actor_loss_tf = tf.reduce_sum(tf.square(norm_a_diff), axis=-1)
- self.actor_loss_tf *= self.adv_tf
- self.actor_loss_tf = 0.5 * tf.reduce_mean(self.actor_loss_tf)
-
- norm_a_bound_min = self.a_norm.normalize(self.a_bound_min)
- norm_a_bound_max = self.a_norm.normalize(self.a_bound_max)
- a_bound_loss = TFUtil.calc_bound_loss(norm_a_mean_tf, norm_a_bound_min, norm_a_bound_max)
- a_bound_loss /= self.exp_params_curr.noise
- self.actor_loss_tf += a_bound_loss
-
- if (actor_weight_decay != 0):
- self.actor_loss_tf += actor_weight_decay * self._weight_decay_loss('main/actor')
-
- return
-
- def _build_solvers(self, json_data):
- actor_stepsize = 0.001 if (self.ACTOR_STEPSIZE_KEY not in json_data) else json_data[self.ACTOR_STEPSIZE_KEY]
- actor_momentum = 0.9 if (self.ACTOR_MOMENTUM_KEY not in json_data) else json_data[self.ACTOR_MOMENTUM_KEY]
- critic_stepsize = 0.01 if (self.CRITIC_STEPSIZE_KEY not in json_data) else json_data[self.CRITIC_STEPSIZE_KEY]
- critic_momentum = 0.9 if (self.CRITIC_MOMENTUM_KEY not in json_data) else json_data[self.CRITIC_MOMENTUM_KEY]
-
- critic_vars = self._tf_vars('main/critic')
- critic_opt = tf.train.MomentumOptimizer(learning_rate=critic_stepsize, momentum=critic_momentum)
- self.critic_grad_tf = tf.gradients(self.critic_loss_tf, critic_vars)
- self.critic_solver = MPISolver(self.sess, critic_opt, critic_vars)
-
- actor_vars = self._tf_vars('main/actor')
- actor_opt = tf.train.MomentumOptimizer(learning_rate=actor_stepsize, momentum=actor_momentum)
- self.actor_grad_tf = tf.gradients(self.actor_loss_tf, actor_vars)
- self.actor_solver = MPISolver(self.sess, actor_opt, actor_vars)
-
- return
-
- def _build_net_actor(self, net_name, init_output_scale):
- norm_s_tf = self.s_norm.normalize_tf(self.s_tf)
- input_tfs = [norm_s_tf]
- if (self.has_goal()):
- norm_g_tf = self.g_norm.normalize_tf(self.g_tf)
- input_tfs += [norm_g_tf]
-
- h = NetBuilder.build_net(net_name, input_tfs)
- norm_a_tf = tf.layers.dense(inputs=h, units=self.get_action_size(), activation=None,
- kernel_initializer=tf.random_uniform_initializer(minval=-init_output_scale, maxval=init_output_scale))
-
- a_tf = self.a_norm.unnormalize_tf(norm_a_tf)
- return a_tf
-
- def _build_net_critic(self, net_name):
- norm_s_tf = self.s_norm.normalize_tf(self.s_tf)
- input_tfs = [norm_s_tf]
- if (self.has_goal()):
- norm_g_tf = self.g_norm.normalize_tf(self.g_tf)
- input_tfs += [norm_g_tf]
-
- h = NetBuilder.build_net(net_name, input_tfs)
- norm_val_tf = tf.layers.dense(inputs=h, units=1, activation=None,
- kernel_initializer=TFUtil.xavier_initializer);
-
- norm_val_tf = tf.reshape(norm_val_tf, [-1])
- val_tf = self.val_norm.unnormalize_tf(norm_val_tf)
- return val_tf
-
- def _initialize_vars(self):
- super()._initialize_vars()
- self._sync_solvers()
- return
-
- def _sync_solvers(self):
- self.actor_solver.sync()
- self.critic_solver.sync()
- return
-
- def _decide_action(self, s, g):
- with self.sess.as_default(), self.graph.as_default():
- self._exp_action = False
- a = self._eval_actor(s, g)[0]
- logp = 0
-
- if self._enable_stoch_policy():
- # epsilon-greedy
- rand_action = MathUtil.flip_coin(self.exp_params_curr.rate)
- if rand_action:
- norm_exp_noise = np.random.randn(*a.shape)
- norm_exp_noise *= self.exp_params_curr.noise
- exp_noise = norm_exp_noise * self.a_norm.std
- a += exp_noise
-
- logp = self._calc_action_logp(norm_exp_noise)
- self._exp_action = True
-
- return a, logp
-
- def _enable_stoch_policy(self):
- return self.enable_training and (self._mode == self.Mode.TRAIN or self._mode == self.Mode.TRAIN_END)
-
- def _eval_actor(self, s, g):
- s = np.reshape(s, [-1, self.get_state_size()])
- g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
-
- feed = {
- self.s_tf : s,
- self.g_tf : g
- }
-
- a = self.actor_tf.eval(feed)
- return a
-
- def _eval_critic(self, s, g):
- with self.sess.as_default(), self.graph.as_default():
- s = np.reshape(s, [-1, self.get_state_size()])
- g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
-
- feed = {
- self.s_tf : s,
- self.g_tf : g
- }
-
- val = self.critic_tf.eval(feed)
- return val
-
- def _record_flags(self):
- flags = int(0)
- if (self._exp_action):
- flags = flags | self.EXP_ACTION_FLAG
- return flags
-
- def _train_step(self):
- super()._train_step()
-
- critic_loss = self._update_critic()
- actor_loss = self._update_actor()
- critic_loss = MPIUtil.reduce_avg(critic_loss)
- actor_loss = MPIUtil.reduce_avg(actor_loss)
-
- critic_stepsize = self.critic_solver.get_stepsize()
- actor_stepsize = self.actor_solver.get_stepsize()
-
- self.logger.log_tabular('Critic_Loss', critic_loss)
- self.logger.log_tabular('Critic_Stepsize', critic_stepsize)
- self.logger.log_tabular('Actor_Loss', actor_loss)
- self.logger.log_tabular('Actor_Stepsize', actor_stepsize)
-
- return
-
- def _update_critic(self):
- idx = self.replay_buffer.sample(self._local_mini_batch_size)
- s = self.replay_buffer.get('states', idx)
- g = self.replay_buffer.get('goals', idx) if self.has_goal() else None
-
- tar_V = self._calc_updated_vals(idx)
- tar_V = np.clip(tar_V, self.val_min, self.val_max)
-
- feed = {
- self.s_tf: s,
- self.g_tf: g,
- self.tar_val_tf: tar_V
- }
-
- loss, grads = self.sess.run([self.critic_loss_tf, self.critic_grad_tf], feed)
- self.critic_solver.update(grads)
- return loss
-
- def _update_actor(self):
- key = self.EXP_ACTION_FLAG
- idx = self.replay_buffer.sample_filtered(self._local_mini_batch_size, key)
- has_goal = self.has_goal()
-
- s = self.replay_buffer.get('states', idx)
- g = self.replay_buffer.get('goals', idx) if has_goal else None
- a = self.replay_buffer.get('actions', idx)
-
- V_new = self._calc_updated_vals(idx)
- V_old = self._eval_critic(s, g)
- adv = V_new - V_old
-
- feed = {
- self.s_tf: s,
- self.g_tf: g,
- self.a_tf: a,
- self.adv_tf: adv
- }
-
- loss, grads = self.sess.run([self.actor_loss_tf, self.actor_grad_tf], feed)
- self.actor_solver.update(grads)
-
- return loss
-
- def _calc_updated_vals(self, idx):
- r = self.replay_buffer.get('rewards', idx)
-
- if self.discount == 0:
- new_V = r
- else:
- next_idx = self.replay_buffer.get_next_idx(idx)
- s_next = self.replay_buffer.get('states', next_idx)
- g_next = self.replay_buffer.get('goals', next_idx) if self.has_goal() else None
-
- is_end = self.replay_buffer.is_path_end(idx)
- is_fail = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Fail)
- is_succ = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Succ)
- is_fail = np.logical_and(is_end, is_fail)
- is_succ = np.logical_and(is_end, is_succ)
-
- V_next = self._eval_critic(s_next, g_next)
- V_next[is_fail] = self.val_fail
- V_next[is_succ] = self.val_succ
-
- new_V = r + self.discount * V_next
- return new_V
-
- def _calc_action_logp(self, norm_action_deltas):
- # norm action delta are for the normalized actions (scaled by self.a_norm.std)
- stdev = self.exp_params_curr.noise
- assert stdev > 0
-
- a_size = self.get_action_size()
- logp = -0.5 / (stdev * stdev) * np.sum(np.square(norm_action_deltas), axis=-1)
- logp += -0.5 * a_size * np.log(2 * np.pi)
- logp += -a_size * np.log(stdev)
- return logp
-
- def _log_val(self, s, g):
- val = self._eval_critic(s, g)
- norm_val = self.val_norm.normalize(val)
- self.world.env.log_val(self.id, norm_val[0])
- return
-
- def _build_replay_buffer(self, buffer_size):
- super()._build_replay_buffer(buffer_size)
- self.replay_buffer.add_filter_key(self.EXP_ACTION_FLAG)
- return
+ NAME = 'PG'
+
+ ACTOR_NET_KEY = 'ActorNet'
+ ACTOR_STEPSIZE_KEY = 'ActorStepsize'
+ ACTOR_MOMENTUM_KEY = 'ActorMomentum'
+ ACTOR_WEIGHT_DECAY_KEY = 'ActorWeightDecay'
+ ACTOR_INIT_OUTPUT_SCALE_KEY = 'ActorInitOutputScale'
+
+ CRITIC_NET_KEY = 'CriticNet'
+ CRITIC_STEPSIZE_KEY = 'CriticStepsize'
+ CRITIC_MOMENTUM_KEY = 'CriticMomentum'
+ CRITIC_WEIGHT_DECAY_KEY = 'CriticWeightDecay'
+
+ EXP_ACTION_FLAG = 1 << 0
+
+ def __init__(self, world, id, json_data):
+ self._exp_action = False
+ super().__init__(world, id, json_data)
+ return
+
+ def reset(self):
+ super().reset()
+ self._exp_action = False
+ return
+
+ def _check_action_space(self):
+ action_space = self.get_action_space()
+ return action_space == ActionSpace.Continuous
+
+ def _load_params(self, json_data):
+ super()._load_params(json_data)
+ self.val_min, self.val_max = self._calc_val_bounds(self.discount)
+ self.val_fail, self.val_succ = self._calc_term_vals(self.discount)
+ return
+
+ def _build_nets(self, json_data):
+ assert self.ACTOR_NET_KEY in json_data
+ assert self.CRITIC_NET_KEY in json_data
+
+ actor_net_name = json_data[self.ACTOR_NET_KEY]
+ critic_net_name = json_data[self.CRITIC_NET_KEY]
+ actor_init_output_scale = 1 if (self.ACTOR_INIT_OUTPUT_SCALE_KEY not in json_data
+ ) else json_data[self.ACTOR_INIT_OUTPUT_SCALE_KEY]
+
+ s_size = self.get_state_size()
+ g_size = self.get_goal_size()
+ a_size = self.get_action_size()
+
+ # setup input tensors
+ self.s_tf = tf.placeholder(tf.float32, shape=[None, s_size], name="s") # observations
+ self.tar_val_tf = tf.placeholder(tf.float32, shape=[None], name="tar_val") # target value s
+ self.adv_tf = tf.placeholder(tf.float32, shape=[None], name="adv") # advantage
+ self.a_tf = tf.placeholder(tf.float32, shape=[None, a_size], name="a") # target actions
+ self.g_tf = tf.placeholder(tf.float32,
+ shape=([None, g_size] if self.has_goal() else None),
+ name="g") # goals
+
+ with tf.variable_scope('main'):
+ with tf.variable_scope('actor'):
+ self.actor_tf = self._build_net_actor(actor_net_name, actor_init_output_scale)
+ with tf.variable_scope('critic'):
+ self.critic_tf = self._build_net_critic(critic_net_name)
+
+ if (self.actor_tf != None):
+ Logger.print2('Built actor net: ' + actor_net_name)
+
+ if (self.critic_tf != None):
+ Logger.print2('Built critic net: ' + critic_net_name)
+
+ return
+
+ def _build_normalizers(self):
+ super()._build_normalizers()
+ with self.sess.as_default(), self.graph.as_default(), tf.variable_scope(self.tf_scope):
+ with tf.variable_scope(self.RESOURCE_SCOPE):
+ val_offset, val_scale = self._calc_val_offset_scale(self.discount)
+ self.val_norm = TFNormalizer(self.sess, 'val_norm', 1)
+ self.val_norm.set_mean_std(-val_offset, 1.0 / val_scale)
+ return
+
+ def _init_normalizers(self):
+ super()._init_normalizers()
+ with self.sess.as_default(), self.graph.as_default():
+ self.val_norm.update()
+ return
+
+ def _load_normalizers(self):
+ super()._load_normalizers()
+ self.val_norm.load()
+ return
+
+ def _build_losses(self, json_data):
+ actor_weight_decay = 0 if (
+ self.ACTOR_WEIGHT_DECAY_KEY not in json_data) else json_data[self.ACTOR_WEIGHT_DECAY_KEY]
+ critic_weight_decay = 0 if (
+ self.CRITIC_WEIGHT_DECAY_KEY not in json_data) else json_data[self.CRITIC_WEIGHT_DECAY_KEY]
+
+ norm_val_diff = self.val_norm.normalize_tf(self.tar_val_tf) - self.val_norm.normalize_tf(
+ self.critic_tf)
+ self.critic_loss_tf = 0.5 * tf.reduce_mean(tf.square(norm_val_diff))
+
+ if (critic_weight_decay != 0):
+ self.critic_loss_tf += critic_weight_decay * self._weight_decay_loss('main/critic')
+
+ norm_a_mean_tf = self.a_norm.normalize_tf(self.actor_tf)
+ norm_a_diff = self.a_norm.normalize_tf(self.a_tf) - norm_a_mean_tf
+
+ self.actor_loss_tf = tf.reduce_sum(tf.square(norm_a_diff), axis=-1)
+ self.actor_loss_tf *= self.adv_tf
+ self.actor_loss_tf = 0.5 * tf.reduce_mean(self.actor_loss_tf)
+
+ norm_a_bound_min = self.a_norm.normalize(self.a_bound_min)
+ norm_a_bound_max = self.a_norm.normalize(self.a_bound_max)
+ a_bound_loss = TFUtil.calc_bound_loss(norm_a_mean_tf, norm_a_bound_min, norm_a_bound_max)
+ a_bound_loss /= self.exp_params_curr.noise
+ self.actor_loss_tf += a_bound_loss
+
+ if (actor_weight_decay != 0):
+ self.actor_loss_tf += actor_weight_decay * self._weight_decay_loss('main/actor')
+
+ return
+
+ def _build_solvers(self, json_data):
+ actor_stepsize = 0.001 if (
+ self.ACTOR_STEPSIZE_KEY not in json_data) else json_data[self.ACTOR_STEPSIZE_KEY]
+ actor_momentum = 0.9 if (
+ self.ACTOR_MOMENTUM_KEY not in json_data) else json_data[self.ACTOR_MOMENTUM_KEY]
+ critic_stepsize = 0.01 if (
+ self.CRITIC_STEPSIZE_KEY not in json_data) else json_data[self.CRITIC_STEPSIZE_KEY]
+ critic_momentum = 0.9 if (
+ self.CRITIC_MOMENTUM_KEY not in json_data) else json_data[self.CRITIC_MOMENTUM_KEY]
+
+ critic_vars = self._tf_vars('main/critic')
+ critic_opt = tf.train.MomentumOptimizer(learning_rate=critic_stepsize,
+ momentum=critic_momentum)
+ self.critic_grad_tf = tf.gradients(self.critic_loss_tf, critic_vars)
+ self.critic_solver = MPISolver(self.sess, critic_opt, critic_vars)
+
+ actor_vars = self._tf_vars('main/actor')
+ actor_opt = tf.train.MomentumOptimizer(learning_rate=actor_stepsize, momentum=actor_momentum)
+ self.actor_grad_tf = tf.gradients(self.actor_loss_tf, actor_vars)
+ self.actor_solver = MPISolver(self.sess, actor_opt, actor_vars)
+
+ return
+
+ def _build_net_actor(self, net_name, init_output_scale):
+ norm_s_tf = self.s_norm.normalize_tf(self.s_tf)
+ input_tfs = [norm_s_tf]
+ if (self.has_goal()):
+ norm_g_tf = self.g_norm.normalize_tf(self.g_tf)
+ input_tfs += [norm_g_tf]
+
+ h = NetBuilder.build_net(net_name, input_tfs)
+ norm_a_tf = tf.layers.dense(inputs=h,
+ units=self.get_action_size(),
+ activation=None,
+ kernel_initializer=tf.random_uniform_initializer(
+ minval=-init_output_scale, maxval=init_output_scale))
+
+ a_tf = self.a_norm.unnormalize_tf(norm_a_tf)
+ return a_tf
+
+ def _build_net_critic(self, net_name):
+ norm_s_tf = self.s_norm.normalize_tf(self.s_tf)
+ input_tfs = [norm_s_tf]
+ if (self.has_goal()):
+ norm_g_tf = self.g_norm.normalize_tf(self.g_tf)
+ input_tfs += [norm_g_tf]
+
+ h = NetBuilder.build_net(net_name, input_tfs)
+ norm_val_tf = tf.layers.dense(inputs=h,
+ units=1,
+ activation=None,
+ kernel_initializer=TFUtil.xavier_initializer)
+
+ norm_val_tf = tf.reshape(norm_val_tf, [-1])
+ val_tf = self.val_norm.unnormalize_tf(norm_val_tf)
+ return val_tf
+
+ def _initialize_vars(self):
+ super()._initialize_vars()
+ self._sync_solvers()
+ return
+
+ def _sync_solvers(self):
+ self.actor_solver.sync()
+ self.critic_solver.sync()
+ return
+
+ def _decide_action(self, s, g):
+ with self.sess.as_default(), self.graph.as_default():
+ self._exp_action = False
+ a = self._eval_actor(s, g)[0]
+ logp = 0
+
+ if self._enable_stoch_policy():
+ # epsilon-greedy
+ rand_action = MathUtil.flip_coin(self.exp_params_curr.rate)
+ if rand_action:
+ norm_exp_noise = np.random.randn(*a.shape)
+ norm_exp_noise *= self.exp_params_curr.noise
+ exp_noise = norm_exp_noise * self.a_norm.std
+ a += exp_noise
+
+ logp = self._calc_action_logp(norm_exp_noise)
+ self._exp_action = True
+
+ return a, logp
+
+ def _enable_stoch_policy(self):
+ return self.enable_training and (self._mode == self.Mode.TRAIN or
+ self._mode == self.Mode.TRAIN_END)
+
+ def _eval_actor(self, s, g):
+ s = np.reshape(s, [-1, self.get_state_size()])
+ g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
+
+ feed = {self.s_tf: s, self.g_tf: g}
+
+ a = self.actor_tf.eval(feed)
+ return a
+
+ def _eval_critic(self, s, g):
+ with self.sess.as_default(), self.graph.as_default():
+ s = np.reshape(s, [-1, self.get_state_size()])
+ g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
+
+ feed = {self.s_tf: s, self.g_tf: g}
+
+ val = self.critic_tf.eval(feed)
+ return val
+
+ def _record_flags(self):
+ flags = int(0)
+ if (self._exp_action):
+ flags = flags | self.EXP_ACTION_FLAG
+ return flags
+
+ def _train_step(self):
+ super()._train_step()
+
+ critic_loss = self._update_critic()
+ actor_loss = self._update_actor()
+ critic_loss = MPIUtil.reduce_avg(critic_loss)
+ actor_loss = MPIUtil.reduce_avg(actor_loss)
+
+ critic_stepsize = self.critic_solver.get_stepsize()
+ actor_stepsize = self.actor_solver.get_stepsize()
+
+ self.logger.log_tabular('Critic_Loss', critic_loss)
+ self.logger.log_tabular('Critic_Stepsize', critic_stepsize)
+ self.logger.log_tabular('Actor_Loss', actor_loss)
+ self.logger.log_tabular('Actor_Stepsize', actor_stepsize)
+
+ return
+
+ def _update_critic(self):
+ idx = self.replay_buffer.sample(self._local_mini_batch_size)
+ s = self.replay_buffer.get('states', idx)
+ g = self.replay_buffer.get('goals', idx) if self.has_goal() else None
+
+ tar_V = self._calc_updated_vals(idx)
+ tar_V = np.clip(tar_V, self.val_min, self.val_max)
+
+ feed = {self.s_tf: s, self.g_tf: g, self.tar_val_tf: tar_V}
+
+ loss, grads = self.sess.run([self.critic_loss_tf, self.critic_grad_tf], feed)
+ self.critic_solver.update(grads)
+ return loss
+
+ def _update_actor(self):
+ key = self.EXP_ACTION_FLAG
+ idx = self.replay_buffer.sample_filtered(self._local_mini_batch_size, key)
+ has_goal = self.has_goal()
+
+ s = self.replay_buffer.get('states', idx)
+ g = self.replay_buffer.get('goals', idx) if has_goal else None
+ a = self.replay_buffer.get('actions', idx)
+
+ V_new = self._calc_updated_vals(idx)
+ V_old = self._eval_critic(s, g)
+ adv = V_new - V_old
+
+ feed = {self.s_tf: s, self.g_tf: g, self.a_tf: a, self.adv_tf: adv}
+
+ loss, grads = self.sess.run([self.actor_loss_tf, self.actor_grad_tf], feed)
+ self.actor_solver.update(grads)
+
+ return loss
+
+ def _calc_updated_vals(self, idx):
+ r = self.replay_buffer.get('rewards', idx)
+
+ if self.discount == 0:
+ new_V = r
+ else:
+ next_idx = self.replay_buffer.get_next_idx(idx)
+ s_next = self.replay_buffer.get('states', next_idx)
+ g_next = self.replay_buffer.get('goals', next_idx) if self.has_goal() else None
+
+ is_end = self.replay_buffer.is_path_end(idx)
+ is_fail = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Fail)
+ is_succ = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Succ)
+ is_fail = np.logical_and(is_end, is_fail)
+ is_succ = np.logical_and(is_end, is_succ)
+
+ V_next = self._eval_critic(s_next, g_next)
+ V_next[is_fail] = self.val_fail
+ V_next[is_succ] = self.val_succ
+
+ new_V = r + self.discount * V_next
+ return new_V
+
+ def _calc_action_logp(self, norm_action_deltas):
+ # norm action delta are for the normalized actions (scaled by self.a_norm.std)
+ stdev = self.exp_params_curr.noise
+ assert stdev > 0
+
+ a_size = self.get_action_size()
+ logp = -0.5 / (stdev * stdev) * np.sum(np.square(norm_action_deltas), axis=-1)
+ logp += -0.5 * a_size * np.log(2 * np.pi)
+ logp += -a_size * np.log(stdev)
+ return logp
+
+ def _log_val(self, s, g):
+ val = self._eval_critic(s, g)
+ norm_val = self.val_norm.normalize(val)
+ self.world.env.log_val(self.id, norm_val[0])
+ return
+
+ def _build_replay_buffer(self, buffer_size):
+ super()._build_replay_buffer(buffer_size)
+ self.replay_buffer.add_filter_key(self.EXP_ACTION_FLAG)
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/ppo_agent.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/ppo_agent.py
index ff66ba004..125a1bb38 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/ppo_agent.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/ppo_agent.py
@@ -10,359 +10,374 @@ from pybullet_utils.logger import Logger
import pybullet_utils.mpi_util as MPIUtil
import pybullet_utils.math_util as MathUtil
from pybullet_envs.deep_mimic.env.env import Env
-
'''
Proximal Policy Optimization Agent
'''
+
class PPOAgent(PGAgent):
- NAME = "PPO"
- EPOCHS_KEY = "Epochs"
- BATCH_SIZE_KEY = "BatchSize"
- RATIO_CLIP_KEY = "RatioClip"
- NORM_ADV_CLIP_KEY = "NormAdvClip"
- TD_LAMBDA_KEY = "TDLambda"
- TAR_CLIP_FRAC = "TarClipFrac"
- ACTOR_STEPSIZE_DECAY = "ActorStepsizeDecay"
-
- def __init__(self, world, id, json_data):
- super().__init__(world, id, json_data)
- return
-
- def _load_params(self, json_data):
- super()._load_params(json_data)
-
- self.epochs = 1 if (self.EPOCHS_KEY not in json_data) else json_data[self.EPOCHS_KEY]
- self.batch_size = 1024 if (self.BATCH_SIZE_KEY not in json_data) else json_data[self.BATCH_SIZE_KEY]
- self.ratio_clip = 0.2 if (self.RATIO_CLIP_KEY not in json_data) else json_data[self.RATIO_CLIP_KEY]
- self.norm_adv_clip = 5 if (self.NORM_ADV_CLIP_KEY not in json_data) else json_data[self.NORM_ADV_CLIP_KEY]
- self.td_lambda = 0.95 if (self.TD_LAMBDA_KEY not in json_data) else json_data[self.TD_LAMBDA_KEY]
- self.tar_clip_frac = -1 if (self.TAR_CLIP_FRAC not in json_data) else json_data[self.TAR_CLIP_FRAC]
- self.actor_stepsize_decay = 0.5 if (self.ACTOR_STEPSIZE_DECAY not in json_data) else json_data[self.ACTOR_STEPSIZE_DECAY]
-
- num_procs = MPIUtil.get_num_procs()
- local_batch_size = int(self.batch_size / num_procs)
- min_replay_size = 2 * local_batch_size # needed to prevent buffer overflow
- assert(self.replay_buffer_size > min_replay_size)
-
- self.replay_buffer_size = np.maximum(min_replay_size, self.replay_buffer_size)
-
- return
-
- def _build_nets(self, json_data):
- assert self.ACTOR_NET_KEY in json_data
- assert self.CRITIC_NET_KEY in json_data
-
- actor_net_name = json_data[self.ACTOR_NET_KEY]
- critic_net_name = json_data[self.CRITIC_NET_KEY]
- actor_init_output_scale = 1 if (self.ACTOR_INIT_OUTPUT_SCALE_KEY not in json_data) else json_data[self.ACTOR_INIT_OUTPUT_SCALE_KEY]
-
- s_size = self.get_state_size()
- g_size = self.get_goal_size()
- a_size = self.get_action_size()
-
- # setup input tensors
- self.s_tf = tf.placeholder(tf.float32, shape=[None, s_size], name="s")
- self.a_tf = tf.placeholder(tf.float32, shape=[None, a_size], name="a")
- self.tar_val_tf = tf.placeholder(tf.float32, shape=[None], name="tar_val")
- self.adv_tf = tf.placeholder(tf.float32, shape=[None], name="adv")
- self.g_tf = tf.placeholder(tf.float32, shape=([None, g_size] if self.has_goal() else None), name="g")
- self.old_logp_tf = tf.placeholder(tf.float32, shape=[None], name="old_logp")
- self.exp_mask_tf = tf.placeholder(tf.float32, shape=[None], name="exp_mask")
-
- with tf.variable_scope('main'):
- with tf.variable_scope('actor'):
- self.a_mean_tf = self._build_net_actor(actor_net_name, actor_init_output_scale)
- with tf.variable_scope('critic'):
- self.critic_tf = self._build_net_critic(critic_net_name)
-
- if (self.a_mean_tf != None):
- Logger.print2('Built actor net: ' + actor_net_name)
-
- if (self.critic_tf != None):
- Logger.print2('Built critic net: ' + critic_net_name)
-
- self.norm_a_std_tf = self.exp_params_curr.noise * tf.ones(a_size)
- norm_a_noise_tf = self.norm_a_std_tf * tf.random_normal(shape=tf.shape(self.a_mean_tf))
- norm_a_noise_tf *= tf.expand_dims(self.exp_mask_tf, axis=-1)
- self.sample_a_tf = self.a_mean_tf + norm_a_noise_tf * self.a_norm.std_tf
- self.sample_a_logp_tf = TFUtil.calc_logp_gaussian(x_tf=norm_a_noise_tf, mean_tf=None, std_tf=self.norm_a_std_tf)
-
- return
-
- def _build_losses(self, json_data):
- actor_weight_decay = 0 if (self.ACTOR_WEIGHT_DECAY_KEY not in json_data) else json_data[self.ACTOR_WEIGHT_DECAY_KEY]
- critic_weight_decay = 0 if (self.CRITIC_WEIGHT_DECAY_KEY not in json_data) else json_data[self.CRITIC_WEIGHT_DECAY_KEY]
-
- norm_val_diff = self.val_norm.normalize_tf(self.tar_val_tf) - self.val_norm.normalize_tf(self.critic_tf)
- self.critic_loss_tf = 0.5 * tf.reduce_mean(tf.square(norm_val_diff))
-
- if (critic_weight_decay != 0):
- self.critic_loss_tf += critic_weight_decay * self._weight_decay_loss('main/critic')
-
- norm_tar_a_tf = self.a_norm.normalize_tf(self.a_tf)
- self._norm_a_mean_tf = self.a_norm.normalize_tf(self.a_mean_tf)
-
- self.logp_tf = TFUtil.calc_logp_gaussian(norm_tar_a_tf, self._norm_a_mean_tf, self.norm_a_std_tf)
- ratio_tf = tf.exp(self.logp_tf - self.old_logp_tf)
- actor_loss0 = self.adv_tf * ratio_tf
- actor_loss1 = self.adv_tf * tf.clip_by_value(ratio_tf, 1.0 - self.ratio_clip, 1 + self.ratio_clip)
- self.actor_loss_tf = -tf.reduce_mean(tf.minimum(actor_loss0, actor_loss1))
-
- norm_a_bound_min = self.a_norm.normalize(self.a_bound_min)
- norm_a_bound_max = self.a_norm.normalize(self.a_bound_max)
- a_bound_loss = TFUtil.calc_bound_loss(self._norm_a_mean_tf, norm_a_bound_min, norm_a_bound_max)
- self.actor_loss_tf += a_bound_loss
-
- if (actor_weight_decay != 0):
- self.actor_loss_tf += actor_weight_decay * self._weight_decay_loss('main/actor')
-
- # for debugging
- self.clip_frac_tf = tf.reduce_mean(tf.to_float(tf.greater(tf.abs(ratio_tf - 1.0), self.ratio_clip)))
-
- return
-
- def _build_solvers(self, json_data):
- actor_stepsize = 0.001 if (self.ACTOR_STEPSIZE_KEY not in json_data) else json_data[self.ACTOR_STEPSIZE_KEY]
- actor_momentum = 0.9 if (self.ACTOR_MOMENTUM_KEY not in json_data) else json_data[self.ACTOR_MOMENTUM_KEY]
- critic_stepsize = 0.01 if (self.CRITIC_STEPSIZE_KEY not in json_data) else json_data[self.CRITIC_STEPSIZE_KEY]
- critic_momentum = 0.9 if (self.CRITIC_MOMENTUM_KEY not in json_data) else json_data[self.CRITIC_MOMENTUM_KEY]
-
- critic_vars = self._tf_vars('main/critic')
- critic_opt = tf.train.MomentumOptimizer(learning_rate=critic_stepsize, momentum=critic_momentum)
- self.critic_grad_tf = tf.gradients(self.critic_loss_tf, critic_vars)
- self.critic_solver = MPISolver(self.sess, critic_opt, critic_vars)
-
- self._actor_stepsize_tf = tf.get_variable(dtype=tf.float32, name='actor_stepsize', initializer=actor_stepsize, trainable=False)
- self._actor_stepsize_ph = tf.get_variable(dtype=tf.float32, name='actor_stepsize_ph', shape=[])
- self._actor_stepsize_update_op = self._actor_stepsize_tf.assign(self._actor_stepsize_ph)
-
- actor_vars = self._tf_vars('main/actor')
- actor_opt = tf.train.MomentumOptimizer(learning_rate=self._actor_stepsize_tf, momentum=actor_momentum)
- self.actor_grad_tf = tf.gradients(self.actor_loss_tf, actor_vars)
- self.actor_solver = MPISolver(self.sess, actor_opt, actor_vars)
-
- return
-
- def _decide_action(self, s, g):
- with self.sess.as_default(), self.graph.as_default():
- self._exp_action = self._enable_stoch_policy() and MathUtil.flip_coin(self.exp_params_curr.rate)
- #print("_decide_action._exp_action=",self._exp_action)
- a, logp = self._eval_actor(s, g, self._exp_action)
- return a[0], logp[0]
-
- def _eval_actor(self, s, g, enable_exp):
- s = np.reshape(s, [-1, self.get_state_size()])
- g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
-
- feed = {
- self.s_tf : s,
- self.g_tf : g,
- self.exp_mask_tf: np.array([1 if enable_exp else 0])
- }
-
- a, logp = self.sess.run([self.sample_a_tf, self.sample_a_logp_tf], feed_dict=feed)
- return a, logp
-
- def _train_step(self):
- adv_eps = 1e-5
-
- start_idx = self.replay_buffer.buffer_tail
- end_idx = self.replay_buffer.buffer_head
- assert(start_idx == 0)
- assert(self.replay_buffer.get_current_size() <= self.replay_buffer.buffer_size) # must avoid overflow
- assert(start_idx < end_idx)
-
- idx = np.array(list(range(start_idx, end_idx)))
- end_mask = self.replay_buffer.is_path_end(idx)
- end_mask = np.logical_not(end_mask)
-
- vals = self._compute_batch_vals(start_idx, end_idx)
- new_vals = self._compute_batch_new_vals(start_idx, end_idx, vals)
-
- valid_idx = idx[end_mask]
- exp_idx = self.replay_buffer.get_idx_filtered(self.EXP_ACTION_FLAG).copy()
- num_valid_idx = valid_idx.shape[0]
- num_exp_idx = exp_idx.shape[0]
- exp_idx = np.column_stack([exp_idx, np.array(list(range(0, num_exp_idx)), dtype=np.int32)])
-
- local_sample_count = valid_idx.size
- global_sample_count = int(MPIUtil.reduce_sum(local_sample_count))
- mini_batches = int(np.ceil(global_sample_count / self.mini_batch_size))
-
- adv = new_vals[exp_idx[:,0]] - vals[exp_idx[:,0]]
- new_vals = np.clip(new_vals, self.val_min, self.val_max)
-
- adv_mean = np.mean(adv)
- adv_std = np.std(adv)
- adv = (adv - adv_mean) / (adv_std + adv_eps)
- adv = np.clip(adv, -self.norm_adv_clip, self.norm_adv_clip)
-
- critic_loss = 0
- actor_loss = 0
- actor_clip_frac = 0
-
- for e in range(self.epochs):
- np.random.shuffle(valid_idx)
- np.random.shuffle(exp_idx)
-
- for b in range(mini_batches):
- batch_idx_beg = b * self._local_mini_batch_size
- batch_idx_end = batch_idx_beg + self._local_mini_batch_size
-
- critic_batch = np.array(range(batch_idx_beg, batch_idx_end), dtype=np.int32)
- actor_batch = critic_batch.copy()
- critic_batch = np.mod(critic_batch, num_valid_idx)
- actor_batch = np.mod(actor_batch, num_exp_idx)
- shuffle_actor = (actor_batch[-1] < actor_batch[0]) or (actor_batch[-1] == num_exp_idx - 1)
-
- critic_batch = valid_idx[critic_batch]
- actor_batch = exp_idx[actor_batch]
- critic_batch_vals = new_vals[critic_batch]
- actor_batch_adv = adv[actor_batch[:,1]]
-
- critic_s = self.replay_buffer.get('states', critic_batch)
- critic_g = self.replay_buffer.get('goals', critic_batch) if self.has_goal() else None
- curr_critic_loss = self._update_critic(critic_s, critic_g, critic_batch_vals)
-
- actor_s = self.replay_buffer.get("states", actor_batch[:,0])
- actor_g = self.replay_buffer.get("goals", actor_batch[:,0]) if self.has_goal() else None
- actor_a = self.replay_buffer.get("actions", actor_batch[:,0])
- actor_logp = self.replay_buffer.get("logps", actor_batch[:,0])
- curr_actor_loss, curr_actor_clip_frac = self._update_actor(actor_s, actor_g, actor_a, actor_logp, actor_batch_adv)
-
- critic_loss += curr_critic_loss
- actor_loss += np.abs(curr_actor_loss)
- actor_clip_frac += curr_actor_clip_frac
-
- if (shuffle_actor):
- np.random.shuffle(exp_idx)
-
- total_batches = mini_batches * self.epochs
- critic_loss /= total_batches
- actor_loss /= total_batches
- actor_clip_frac /= total_batches
-
- critic_loss = MPIUtil.reduce_avg(critic_loss)
- actor_loss = MPIUtil.reduce_avg(actor_loss)
- actor_clip_frac = MPIUtil.reduce_avg(actor_clip_frac)
-
- critic_stepsize = self.critic_solver.get_stepsize()
- actor_stepsize = self.update_actor_stepsize(actor_clip_frac)
-
- self.logger.log_tabular('Critic_Loss', critic_loss)
- self.logger.log_tabular('Critic_Stepsize', critic_stepsize)
- self.logger.log_tabular('Actor_Loss', actor_loss)
- self.logger.log_tabular('Actor_Stepsize', actor_stepsize)
- self.logger.log_tabular('Clip_Frac', actor_clip_frac)
- self.logger.log_tabular('Adv_Mean', adv_mean)
- self.logger.log_tabular('Adv_Std', adv_std)
-
- self.replay_buffer.clear()
-
- return
-
- def _get_iters_per_update(self):
- return 1
-
- def _valid_train_step(self):
- samples = self.replay_buffer.get_current_size()
- exp_samples = self.replay_buffer.count_filtered(self.EXP_ACTION_FLAG)
- global_sample_count = int(MPIUtil.reduce_sum(samples))
- global_exp_min = int(MPIUtil.reduce_min(exp_samples))
- return (global_sample_count > self.batch_size) and (global_exp_min > 0)
-
- def _compute_batch_vals(self, start_idx, end_idx):
- states = self.replay_buffer.get_all("states")[start_idx:end_idx]
- goals = self.replay_buffer.get_all("goals")[start_idx:end_idx] if self.has_goal() else None
-
- idx = np.array(list(range(start_idx, end_idx)))
- is_end = self.replay_buffer.is_path_end(idx)
- is_fail = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Fail)
- is_succ = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Succ)
- is_fail = np.logical_and(is_end, is_fail)
- is_succ = np.logical_and(is_end, is_succ)
-
- vals = self._eval_critic(states, goals)
- vals[is_fail] = self.val_fail
- vals[is_succ] = self.val_succ
-
- return vals
-
- def _compute_batch_new_vals(self, start_idx, end_idx, val_buffer):
- rewards = self.replay_buffer.get_all("rewards")[start_idx:end_idx]
-
- if self.discount == 0:
- new_vals = rewards.copy()
+ NAME = "PPO"
+ EPOCHS_KEY = "Epochs"
+ BATCH_SIZE_KEY = "BatchSize"
+ RATIO_CLIP_KEY = "RatioClip"
+ NORM_ADV_CLIP_KEY = "NormAdvClip"
+ TD_LAMBDA_KEY = "TDLambda"
+ TAR_CLIP_FRAC = "TarClipFrac"
+ ACTOR_STEPSIZE_DECAY = "ActorStepsizeDecay"
+
+ def __init__(self, world, id, json_data):
+ super().__init__(world, id, json_data)
+ return
+
+ def _load_params(self, json_data):
+ super()._load_params(json_data)
+
+ self.epochs = 1 if (self.EPOCHS_KEY not in json_data) else json_data[self.EPOCHS_KEY]
+ self.batch_size = 1024 if (
+ self.BATCH_SIZE_KEY not in json_data) else json_data[self.BATCH_SIZE_KEY]
+ self.ratio_clip = 0.2 if (
+ self.RATIO_CLIP_KEY not in json_data) else json_data[self.RATIO_CLIP_KEY]
+ self.norm_adv_clip = 5 if (
+ self.NORM_ADV_CLIP_KEY not in json_data) else json_data[self.NORM_ADV_CLIP_KEY]
+ self.td_lambda = 0.95 if (
+ self.TD_LAMBDA_KEY not in json_data) else json_data[self.TD_LAMBDA_KEY]
+ self.tar_clip_frac = -1 if (
+ self.TAR_CLIP_FRAC not in json_data) else json_data[self.TAR_CLIP_FRAC]
+ self.actor_stepsize_decay = 0.5 if (
+ self.ACTOR_STEPSIZE_DECAY not in json_data) else json_data[self.ACTOR_STEPSIZE_DECAY]
+
+ num_procs = MPIUtil.get_num_procs()
+ local_batch_size = int(self.batch_size / num_procs)
+ min_replay_size = 2 * local_batch_size # needed to prevent buffer overflow
+ assert (self.replay_buffer_size > min_replay_size)
+
+ self.replay_buffer_size = np.maximum(min_replay_size, self.replay_buffer_size)
+
+ return
+
+ def _build_nets(self, json_data):
+ assert self.ACTOR_NET_KEY in json_data
+ assert self.CRITIC_NET_KEY in json_data
+
+ actor_net_name = json_data[self.ACTOR_NET_KEY]
+ critic_net_name = json_data[self.CRITIC_NET_KEY]
+ actor_init_output_scale = 1 if (self.ACTOR_INIT_OUTPUT_SCALE_KEY not in json_data
+ ) else json_data[self.ACTOR_INIT_OUTPUT_SCALE_KEY]
+
+ s_size = self.get_state_size()
+ g_size = self.get_goal_size()
+ a_size = self.get_action_size()
+
+ # setup input tensors
+ self.s_tf = tf.placeholder(tf.float32, shape=[None, s_size], name="s")
+ self.a_tf = tf.placeholder(tf.float32, shape=[None, a_size], name="a")
+ self.tar_val_tf = tf.placeholder(tf.float32, shape=[None], name="tar_val")
+ self.adv_tf = tf.placeholder(tf.float32, shape=[None], name="adv")
+ self.g_tf = tf.placeholder(tf.float32,
+ shape=([None, g_size] if self.has_goal() else None),
+ name="g")
+ self.old_logp_tf = tf.placeholder(tf.float32, shape=[None], name="old_logp")
+ self.exp_mask_tf = tf.placeholder(tf.float32, shape=[None], name="exp_mask")
+
+ with tf.variable_scope('main'):
+ with tf.variable_scope('actor'):
+ self.a_mean_tf = self._build_net_actor(actor_net_name, actor_init_output_scale)
+ with tf.variable_scope('critic'):
+ self.critic_tf = self._build_net_critic(critic_net_name)
+
+ if (self.a_mean_tf != None):
+ Logger.print2('Built actor net: ' + actor_net_name)
+
+ if (self.critic_tf != None):
+ Logger.print2('Built critic net: ' + critic_net_name)
+
+ self.norm_a_std_tf = self.exp_params_curr.noise * tf.ones(a_size)
+ norm_a_noise_tf = self.norm_a_std_tf * tf.random_normal(shape=tf.shape(self.a_mean_tf))
+ norm_a_noise_tf *= tf.expand_dims(self.exp_mask_tf, axis=-1)
+ self.sample_a_tf = self.a_mean_tf + norm_a_noise_tf * self.a_norm.std_tf
+ self.sample_a_logp_tf = TFUtil.calc_logp_gaussian(x_tf=norm_a_noise_tf,
+ mean_tf=None,
+ std_tf=self.norm_a_std_tf)
+
+ return
+
+ def _build_losses(self, json_data):
+ actor_weight_decay = 0 if (
+ self.ACTOR_WEIGHT_DECAY_KEY not in json_data) else json_data[self.ACTOR_WEIGHT_DECAY_KEY]
+ critic_weight_decay = 0 if (
+ self.CRITIC_WEIGHT_DECAY_KEY not in json_data) else json_data[self.CRITIC_WEIGHT_DECAY_KEY]
+
+ norm_val_diff = self.val_norm.normalize_tf(self.tar_val_tf) - self.val_norm.normalize_tf(
+ self.critic_tf)
+ self.critic_loss_tf = 0.5 * tf.reduce_mean(tf.square(norm_val_diff))
+
+ if (critic_weight_decay != 0):
+ self.critic_loss_tf += critic_weight_decay * self._weight_decay_loss('main/critic')
+
+ norm_tar_a_tf = self.a_norm.normalize_tf(self.a_tf)
+ self._norm_a_mean_tf = self.a_norm.normalize_tf(self.a_mean_tf)
+
+ self.logp_tf = TFUtil.calc_logp_gaussian(norm_tar_a_tf, self._norm_a_mean_tf,
+ self.norm_a_std_tf)
+ ratio_tf = tf.exp(self.logp_tf - self.old_logp_tf)
+ actor_loss0 = self.adv_tf * ratio_tf
+ actor_loss1 = self.adv_tf * tf.clip_by_value(ratio_tf, 1.0 - self.ratio_clip,
+ 1 + self.ratio_clip)
+ self.actor_loss_tf = -tf.reduce_mean(tf.minimum(actor_loss0, actor_loss1))
+
+ norm_a_bound_min = self.a_norm.normalize(self.a_bound_min)
+ norm_a_bound_max = self.a_norm.normalize(self.a_bound_max)
+ a_bound_loss = TFUtil.calc_bound_loss(self._norm_a_mean_tf, norm_a_bound_min, norm_a_bound_max)
+ self.actor_loss_tf += a_bound_loss
+
+ if (actor_weight_decay != 0):
+ self.actor_loss_tf += actor_weight_decay * self._weight_decay_loss('main/actor')
+
+ # for debugging
+ self.clip_frac_tf = tf.reduce_mean(
+ tf.to_float(tf.greater(tf.abs(ratio_tf - 1.0), self.ratio_clip)))
+
+ return
+
+ def _build_solvers(self, json_data):
+ actor_stepsize = 0.001 if (
+ self.ACTOR_STEPSIZE_KEY not in json_data) else json_data[self.ACTOR_STEPSIZE_KEY]
+ actor_momentum = 0.9 if (
+ self.ACTOR_MOMENTUM_KEY not in json_data) else json_data[self.ACTOR_MOMENTUM_KEY]
+ critic_stepsize = 0.01 if (
+ self.CRITIC_STEPSIZE_KEY not in json_data) else json_data[self.CRITIC_STEPSIZE_KEY]
+ critic_momentum = 0.9 if (
+ self.CRITIC_MOMENTUM_KEY not in json_data) else json_data[self.CRITIC_MOMENTUM_KEY]
+
+ critic_vars = self._tf_vars('main/critic')
+ critic_opt = tf.train.MomentumOptimizer(learning_rate=critic_stepsize,
+ momentum=critic_momentum)
+ self.critic_grad_tf = tf.gradients(self.critic_loss_tf, critic_vars)
+ self.critic_solver = MPISolver(self.sess, critic_opt, critic_vars)
+
+ self._actor_stepsize_tf = tf.get_variable(dtype=tf.float32,
+ name='actor_stepsize',
+ initializer=actor_stepsize,
+ trainable=False)
+ self._actor_stepsize_ph = tf.get_variable(dtype=tf.float32, name='actor_stepsize_ph', shape=[])
+ self._actor_stepsize_update_op = self._actor_stepsize_tf.assign(self._actor_stepsize_ph)
+
+ actor_vars = self._tf_vars('main/actor')
+ actor_opt = tf.train.MomentumOptimizer(learning_rate=self._actor_stepsize_tf,
+ momentum=actor_momentum)
+ self.actor_grad_tf = tf.gradients(self.actor_loss_tf, actor_vars)
+ self.actor_solver = MPISolver(self.sess, actor_opt, actor_vars)
+
+ return
+
+ def _decide_action(self, s, g):
+ with self.sess.as_default(), self.graph.as_default():
+ self._exp_action = self._enable_stoch_policy() and MathUtil.flip_coin(
+ self.exp_params_curr.rate)
+ #print("_decide_action._exp_action=",self._exp_action)
+ a, logp = self._eval_actor(s, g, self._exp_action)
+ return a[0], logp[0]
+
+ def _eval_actor(self, s, g, enable_exp):
+ s = np.reshape(s, [-1, self.get_state_size()])
+ g = np.reshape(g, [-1, self.get_goal_size()]) if self.has_goal() else None
+
+ feed = {self.s_tf: s, self.g_tf: g, self.exp_mask_tf: np.array([1 if enable_exp else 0])}
+
+ a, logp = self.sess.run([self.sample_a_tf, self.sample_a_logp_tf], feed_dict=feed)
+ return a, logp
+
+ def _train_step(self):
+ adv_eps = 1e-5
+
+ start_idx = self.replay_buffer.buffer_tail
+ end_idx = self.replay_buffer.buffer_head
+ assert (start_idx == 0)
+ assert (self.replay_buffer.get_current_size() <= self.replay_buffer.buffer_size
+ ) # must avoid overflow
+ assert (start_idx < end_idx)
+
+ idx = np.array(list(range(start_idx, end_idx)))
+ end_mask = self.replay_buffer.is_path_end(idx)
+ end_mask = np.logical_not(end_mask)
+
+ vals = self._compute_batch_vals(start_idx, end_idx)
+ new_vals = self._compute_batch_new_vals(start_idx, end_idx, vals)
+
+ valid_idx = idx[end_mask]
+ exp_idx = self.replay_buffer.get_idx_filtered(self.EXP_ACTION_FLAG).copy()
+ num_valid_idx = valid_idx.shape[0]
+ num_exp_idx = exp_idx.shape[0]
+ exp_idx = np.column_stack([exp_idx, np.array(list(range(0, num_exp_idx)), dtype=np.int32)])
+
+ local_sample_count = valid_idx.size
+ global_sample_count = int(MPIUtil.reduce_sum(local_sample_count))
+ mini_batches = int(np.ceil(global_sample_count / self.mini_batch_size))
+
+ adv = new_vals[exp_idx[:, 0]] - vals[exp_idx[:, 0]]
+ new_vals = np.clip(new_vals, self.val_min, self.val_max)
+
+ adv_mean = np.mean(adv)
+ adv_std = np.std(adv)
+ adv = (adv - adv_mean) / (adv_std + adv_eps)
+ adv = np.clip(adv, -self.norm_adv_clip, self.norm_adv_clip)
+
+ critic_loss = 0
+ actor_loss = 0
+ actor_clip_frac = 0
+
+ for e in range(self.epochs):
+ np.random.shuffle(valid_idx)
+ np.random.shuffle(exp_idx)
+
+ for b in range(mini_batches):
+ batch_idx_beg = b * self._local_mini_batch_size
+ batch_idx_end = batch_idx_beg + self._local_mini_batch_size
+
+ critic_batch = np.array(range(batch_idx_beg, batch_idx_end), dtype=np.int32)
+ actor_batch = critic_batch.copy()
+ critic_batch = np.mod(critic_batch, num_valid_idx)
+ actor_batch = np.mod(actor_batch, num_exp_idx)
+ shuffle_actor = (actor_batch[-1] < actor_batch[0]) or (actor_batch[-1] == num_exp_idx - 1)
+
+ critic_batch = valid_idx[critic_batch]
+ actor_batch = exp_idx[actor_batch]
+ critic_batch_vals = new_vals[critic_batch]
+ actor_batch_adv = adv[actor_batch[:, 1]]
+
+ critic_s = self.replay_buffer.get('states', critic_batch)
+ critic_g = self.replay_buffer.get('goals', critic_batch) if self.has_goal() else None
+ curr_critic_loss = self._update_critic(critic_s, critic_g, critic_batch_vals)
+
+ actor_s = self.replay_buffer.get("states", actor_batch[:, 0])
+ actor_g = self.replay_buffer.get("goals", actor_batch[:, 0]) if self.has_goal() else None
+ actor_a = self.replay_buffer.get("actions", actor_batch[:, 0])
+ actor_logp = self.replay_buffer.get("logps", actor_batch[:, 0])
+ curr_actor_loss, curr_actor_clip_frac = self._update_actor(actor_s, actor_g, actor_a,
+ actor_logp, actor_batch_adv)
+
+ critic_loss += curr_critic_loss
+ actor_loss += np.abs(curr_actor_loss)
+ actor_clip_frac += curr_actor_clip_frac
+
+ if (shuffle_actor):
+ np.random.shuffle(exp_idx)
+
+ total_batches = mini_batches * self.epochs
+ critic_loss /= total_batches
+ actor_loss /= total_batches
+ actor_clip_frac /= total_batches
+
+ critic_loss = MPIUtil.reduce_avg(critic_loss)
+ actor_loss = MPIUtil.reduce_avg(actor_loss)
+ actor_clip_frac = MPIUtil.reduce_avg(actor_clip_frac)
+
+ critic_stepsize = self.critic_solver.get_stepsize()
+ actor_stepsize = self.update_actor_stepsize(actor_clip_frac)
+
+ self.logger.log_tabular('Critic_Loss', critic_loss)
+ self.logger.log_tabular('Critic_Stepsize', critic_stepsize)
+ self.logger.log_tabular('Actor_Loss', actor_loss)
+ self.logger.log_tabular('Actor_Stepsize', actor_stepsize)
+ self.logger.log_tabular('Clip_Frac', actor_clip_frac)
+ self.logger.log_tabular('Adv_Mean', adv_mean)
+ self.logger.log_tabular('Adv_Std', adv_std)
+
+ self.replay_buffer.clear()
+
+ return
+
+ def _get_iters_per_update(self):
+ return 1
+
+ def _valid_train_step(self):
+ samples = self.replay_buffer.get_current_size()
+ exp_samples = self.replay_buffer.count_filtered(self.EXP_ACTION_FLAG)
+ global_sample_count = int(MPIUtil.reduce_sum(samples))
+ global_exp_min = int(MPIUtil.reduce_min(exp_samples))
+ return (global_sample_count > self.batch_size) and (global_exp_min > 0)
+
+ def _compute_batch_vals(self, start_idx, end_idx):
+ states = self.replay_buffer.get_all("states")[start_idx:end_idx]
+ goals = self.replay_buffer.get_all("goals")[start_idx:end_idx] if self.has_goal() else None
+
+ idx = np.array(list(range(start_idx, end_idx)))
+ is_end = self.replay_buffer.is_path_end(idx)
+ is_fail = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Fail)
+ is_succ = self.replay_buffer.check_terminal_flag(idx, Env.Terminate.Succ)
+ is_fail = np.logical_and(is_end, is_fail)
+ is_succ = np.logical_and(is_end, is_succ)
+
+ vals = self._eval_critic(states, goals)
+ vals[is_fail] = self.val_fail
+ vals[is_succ] = self.val_succ
+
+ return vals
+
+ def _compute_batch_new_vals(self, start_idx, end_idx, val_buffer):
+ rewards = self.replay_buffer.get_all("rewards")[start_idx:end_idx]
+
+ if self.discount == 0:
+ new_vals = rewards.copy()
+ else:
+ new_vals = np.zeros_like(val_buffer)
+
+ curr_idx = start_idx
+ while curr_idx < end_idx:
+ idx0 = curr_idx - start_idx
+ idx1 = self.replay_buffer.get_path_end(curr_idx) - start_idx
+ r = rewards[idx0:idx1]
+ v = val_buffer[idx0:(idx1 + 1)]
+
+ new_vals[idx0:idx1] = RLUtil.compute_return(r, self.discount, self.td_lambda, v)
+ curr_idx = idx1 + start_idx + 1
+
+ return new_vals
+
+ def _update_critic(self, s, g, tar_vals):
+ feed = {self.s_tf: s, self.g_tf: g, self.tar_val_tf: tar_vals}
+
+ loss, grads = self.sess.run([self.critic_loss_tf, self.critic_grad_tf], feed)
+ self.critic_solver.update(grads)
+ return loss
+
+ def _update_actor(self, s, g, a, logp, adv):
+ feed = {self.s_tf: s, self.g_tf: g, self.a_tf: a, self.adv_tf: adv, self.old_logp_tf: logp}
+
+ loss, grads, clip_frac = self.sess.run(
+ [self.actor_loss_tf, self.actor_grad_tf, self.clip_frac_tf], feed)
+ self.actor_solver.update(grads)
+
+ return loss, clip_frac
+
+ def update_actor_stepsize(self, clip_frac):
+ clip_tol = 1.5
+ step_scale = 2
+ max_stepsize = 1e-2
+ min_stepsize = 1e-8
+ warmup_iters = 5
+
+ actor_stepsize = self.actor_solver.get_stepsize()
+ if (self.tar_clip_frac >= 0 and self.iter > warmup_iters):
+ min_clip = self.tar_clip_frac / clip_tol
+ max_clip = self.tar_clip_frac * clip_tol
+ under_tol = clip_frac < min_clip
+ over_tol = clip_frac > max_clip
+
+ if (over_tol or under_tol):
+ if (over_tol):
+ actor_stepsize *= self.actor_stepsize_decay
else:
- new_vals = np.zeros_like(val_buffer)
-
- curr_idx = start_idx
- while curr_idx < end_idx:
- idx0 = curr_idx - start_idx
- idx1 = self.replay_buffer.get_path_end(curr_idx) - start_idx
- r = rewards[idx0:idx1]
- v = val_buffer[idx0:(idx1 + 1)]
-
- new_vals[idx0:idx1] = RLUtil.compute_return(r, self.discount, self.td_lambda, v)
- curr_idx = idx1 + start_idx + 1
-
- return new_vals
-
- def _update_critic(self, s, g, tar_vals):
- feed = {
- self.s_tf: s,
- self.g_tf: g,
- self.tar_val_tf: tar_vals
- }
-
- loss, grads = self.sess.run([self.critic_loss_tf, self.critic_grad_tf], feed)
- self.critic_solver.update(grads)
- return loss
-
- def _update_actor(self, s, g, a, logp, adv):
- feed = {
- self.s_tf: s,
- self.g_tf: g,
- self.a_tf: a,
- self.adv_tf: adv,
- self.old_logp_tf: logp
- }
-
- loss, grads, clip_frac = self.sess.run([self.actor_loss_tf, self.actor_grad_tf,
- self.clip_frac_tf], feed)
- self.actor_solver.update(grads)
-
- return loss, clip_frac
-
- def update_actor_stepsize(self, clip_frac):
- clip_tol = 1.5
- step_scale = 2
- max_stepsize = 1e-2
- min_stepsize = 1e-8
- warmup_iters = 5
-
- actor_stepsize = self.actor_solver.get_stepsize()
- if (self.tar_clip_frac >= 0 and self.iter > warmup_iters):
- min_clip = self.tar_clip_frac / clip_tol
- max_clip = self.tar_clip_frac * clip_tol
- under_tol = clip_frac < min_clip
- over_tol = clip_frac > max_clip
-
- if (over_tol or under_tol):
- if (over_tol):
- actor_stepsize *= self.actor_stepsize_decay
- else:
- actor_stepsize /= self.actor_stepsize_decay
-
- actor_stepsize = np.clip(actor_stepsize, min_stepsize, max_stepsize)
- self.set_actor_stepsize(actor_stepsize)
-
- return actor_stepsize
-
- def set_actor_stepsize(self, stepsize):
- feed = {
- self._actor_stepsize_ph: stepsize,
- }
- self.sess.run(self._actor_stepsize_update_op, feed)
- return
+ actor_stepsize /= self.actor_stepsize_decay
+
+ actor_stepsize = np.clip(actor_stepsize, min_stepsize, max_stepsize)
+ self.set_actor_stepsize(actor_stepsize)
+
+ return actor_stepsize
+
+ def set_actor_stepsize(self, stepsize):
+ feed = {
+ self._actor_stepsize_ph: stepsize,
+ }
+ self.sess.run(self._actor_stepsize_update_op, feed)
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/replay_buffer.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/replay_buffer.py
index 284515851..f002c7572 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/replay_buffer.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/replay_buffer.py
@@ -5,347 +5,353 @@ import inspect as inspect
from pybullet_envs.deep_mimic.env.env import Env
import pybullet_utils.math_util as MathUtil
+
class ReplayBuffer(object):
- TERMINATE_KEY = 'terminate'
- PATH_START_KEY = 'path_start'
- PATH_END_KEY = 'path_end'
-
- def __init__(self, buffer_size):
- assert buffer_size > 0
-
- self.buffer_size = buffer_size
- self.total_count = 0
- self.buffer_head = 0
- self.buffer_tail = MathUtil.INVALID_IDX
- self.num_paths = 0
- self._sample_buffers = dict()
- self.buffers = None
-
- self.clear()
- return
-
- def sample(self, n):
- curr_size = self.get_current_size()
- assert curr_size > 0
-
- idx = np.empty(n, dtype=int)
- # makes sure that the end states are not sampled
- for i in range(n):
- while True:
- curr_idx = np.random.randint(0, curr_size, size=1)[0]
- curr_idx += self.buffer_tail
- curr_idx = np.mod(curr_idx, self.buffer_size)
-
- if not self.is_path_end(curr_idx):
- break
- idx[i] = curr_idx
-
- return idx
-
- def sample_filtered(self, n, key):
- assert key in self._sample_buffers
- curr_buffer = self._sample_buffers[key]
- idx = curr_buffer.sample(n)
- return idx
-
- def count_filtered(self, key):
- curr_buffer = self._sample_buffers[key]
- return curr_buffer.count
-
- def get(self, key, idx):
- return self.buffers[key][idx]
-
- def get_all(self, key):
- return self.buffers[key]
-
- def get_idx_filtered(self, key):
- assert key in self._sample_buffers
- curr_buffer = self._sample_buffers[key]
- idx = curr_buffer.slot_to_idx[:curr_buffer.count]
- return idx
-
- def get_path_start(self, idx):
- return self.buffers[self.PATH_START_KEY][idx]
-
- def get_path_end(self, idx):
- return self.buffers[self.PATH_END_KEY][idx]
-
- def get_pathlen(self, idx):
- is_array = isinstance(idx, np.ndarray) or isinstance(idx, list)
- if not is_array:
- idx = [idx]
-
- n = len(idx)
- start_idx = self.get_path_start(idx)
- end_idx = self.get_path_end(idx)
- pathlen = np.empty(n, dtype=int)
-
- for i in range(n):
- curr_start = start_idx[i]
- curr_end = end_idx[i]
- if curr_start < curr_end:
- curr_len = curr_end - curr_start
+ TERMINATE_KEY = 'terminate'
+ PATH_START_KEY = 'path_start'
+ PATH_END_KEY = 'path_end'
+
+ def __init__(self, buffer_size):
+ assert buffer_size > 0
+
+ self.buffer_size = buffer_size
+ self.total_count = 0
+ self.buffer_head = 0
+ self.buffer_tail = MathUtil.INVALID_IDX
+ self.num_paths = 0
+ self._sample_buffers = dict()
+ self.buffers = None
+
+ self.clear()
+ return
+
+ def sample(self, n):
+ curr_size = self.get_current_size()
+ assert curr_size > 0
+
+ idx = np.empty(n, dtype=int)
+ # makes sure that the end states are not sampled
+ for i in range(n):
+ while True:
+ curr_idx = np.random.randint(0, curr_size, size=1)[0]
+ curr_idx += self.buffer_tail
+ curr_idx = np.mod(curr_idx, self.buffer_size)
+
+ if not self.is_path_end(curr_idx):
+ break
+ idx[i] = curr_idx
+
+ return idx
+
+ def sample_filtered(self, n, key):
+ assert key in self._sample_buffers
+ curr_buffer = self._sample_buffers[key]
+ idx = curr_buffer.sample(n)
+ return idx
+
+ def count_filtered(self, key):
+ curr_buffer = self._sample_buffers[key]
+ return curr_buffer.count
+
+ def get(self, key, idx):
+ return self.buffers[key][idx]
+
+ def get_all(self, key):
+ return self.buffers[key]
+
+ def get_idx_filtered(self, key):
+ assert key in self._sample_buffers
+ curr_buffer = self._sample_buffers[key]
+ idx = curr_buffer.slot_to_idx[:curr_buffer.count]
+ return idx
+
+ def get_path_start(self, idx):
+ return self.buffers[self.PATH_START_KEY][idx]
+
+ def get_path_end(self, idx):
+ return self.buffers[self.PATH_END_KEY][idx]
+
+ def get_pathlen(self, idx):
+ is_array = isinstance(idx, np.ndarray) or isinstance(idx, list)
+ if not is_array:
+ idx = [idx]
+
+ n = len(idx)
+ start_idx = self.get_path_start(idx)
+ end_idx = self.get_path_end(idx)
+ pathlen = np.empty(n, dtype=int)
+
+ for i in range(n):
+ curr_start = start_idx[i]
+ curr_end = end_idx[i]
+ if curr_start < curr_end:
+ curr_len = curr_end - curr_start
+ else:
+ curr_len = self.buffer_size - curr_start + curr_end
+ pathlen[i] = curr_len
+
+ if not is_array:
+ pathlen = pathlen[0]
+
+ return pathlen
+
+ def is_valid_path(self, idx):
+ start_idx = self.get_path_start(idx)
+ valid = start_idx != MathUtil.INVALID_IDX
+ return valid
+
+ def store(self, path):
+ start_idx = MathUtil.INVALID_IDX
+ n = path.pathlength()
+
+ if (n > 0):
+ assert path.is_valid()
+
+ if path.check_vals():
+ if self.buffers is None:
+ self._init_buffers(path)
+
+ idx = self._request_idx(n + 1)
+ self._store_path(path, idx)
+ self._add_sample_buffers(idx)
+
+ self.num_paths += 1
+ self.total_count += n + 1
+ start_idx = idx[0]
+ else:
+ Logger.print2('Invalid path data value detected')
+
+ return start_idx
+
+ def clear(self):
+ self.buffer_head = 0
+ self.buffer_tail = MathUtil.INVALID_IDX
+ self.num_paths = 0
+
+ for key in self._sample_buffers:
+ self._sample_buffers[key].clear()
+ return
+
+ def get_next_idx(self, idx):
+ next_idx = np.mod(idx + 1, self.buffer_size)
+ return next_idx
+
+ def is_terminal_state(self, idx):
+ terminate_flags = self.buffers[self.TERMINATE_KEY][idx]
+ terminate = terminate_flags != Env.Terminate.Null.value
+ is_end = self.is_path_end(idx)
+ terminal_state = np.logical_and(terminate, is_end)
+ return terminal_state
+
+ def check_terminal_flag(self, idx, flag):
+ terminate_flags = self.buffers[self.TERMINATE_KEY][idx]
+ terminate = terminate_flags == flag.value
+ return terminate
+
+ def is_path_end(self, idx):
+ is_end = self.buffers[self.PATH_END_KEY][idx] == idx
+ return is_end
+
+ def add_filter_key(self, key):
+ assert self.get_current_size() == 0
+ if key not in self._sample_buffers:
+ self._sample_buffers[key] = SampleBuffer(self.buffer_size)
+ return
+
+ def get_current_size(self):
+ if self.buffer_tail == MathUtil.INVALID_IDX:
+ return 0
+ elif self.buffer_tail < self.buffer_head:
+ return self.buffer_head - self.buffer_tail
+ else:
+ return self.buffer_size - self.buffer_tail + self.buffer_head
+
+ def _check_flags(self, key, flags):
+ return (flags & key) == key
+
+ def _add_sample_buffers(self, idx):
+ flags = self.buffers['flags']
+ for key in self._sample_buffers:
+ curr_buffer = self._sample_buffers[key]
+ filter_idx = [
+ i for i in idx if (self._check_flags(key, flags[i]) and not self.is_path_end(i))
+ ]
+ curr_buffer.add(filter_idx)
+ return
+
+ def _free_sample_buffers(self, idx):
+ for key in self._sample_buffers:
+ curr_buffer = self._sample_buffers[key]
+ curr_buffer.free(idx)
+ return
+
+ def _init_buffers(self, path):
+ self.buffers = dict()
+ self.buffers[self.PATH_START_KEY] = MathUtil.INVALID_IDX * np.ones(self.buffer_size, dtype=int)
+ self.buffers[self.PATH_END_KEY] = MathUtil.INVALID_IDX * np.ones(self.buffer_size, dtype=int)
+
+ for key in dir(path):
+ val = getattr(path, key)
+ if not key.startswith('__') and not inspect.ismethod(val):
+ if key == self.TERMINATE_KEY:
+ self.buffers[self.TERMINATE_KEY] = np.zeros(shape=[self.buffer_size], dtype=int)
+ else:
+ val_type = type(val[0])
+ is_array = val_type == np.ndarray
+ if is_array:
+ shape = [self.buffer_size, val[0].shape[0]]
+ dtype = val[0].dtype
+ else:
+ shape = [self.buffer_size]
+ dtype = val_type
+
+ self.buffers[key] = np.zeros(shape, dtype=dtype)
+ return
+
+ def _request_idx(self, n):
+ assert n + 1 < self.buffer_size # bad things can happen if path is too long
+
+ remainder = n
+ idx = []
+
+ start_idx = self.buffer_head
+ while remainder > 0:
+ end_idx = np.minimum(start_idx + remainder, self.buffer_size)
+ remainder -= (end_idx - start_idx)
+
+ free_idx = list(range(start_idx, end_idx))
+ self._free_idx(free_idx)
+ idx += free_idx
+ start_idx = 0
+
+ self.buffer_head = (self.buffer_head + n) % self.buffer_size
+ return idx
+
+ def _free_idx(self, idx):
+ assert (idx[0] <= idx[-1])
+ n = len(idx)
+ if self.buffer_tail != MathUtil.INVALID_IDX:
+ update_tail = idx[0] <= idx[-1] and idx[0] <= self.buffer_tail and idx[-1] >= self.buffer_tail
+ update_tail |= idx[0] > idx[-1] and (idx[0] <= self.buffer_tail or
+ idx[-1] >= self.buffer_tail)
+
+ if update_tail:
+ i = 0
+ while i < n:
+ curr_idx = idx[i]
+ if self.is_valid_path(curr_idx):
+ start_idx = self.get_path_start(curr_idx)
+ end_idx = self.get_path_end(curr_idx)
+ pathlen = self.get_pathlen(curr_idx)
+
+ if start_idx < end_idx:
+ self.buffers[self.PATH_START_KEY][start_idx:end_idx + 1] = MathUtil.INVALID_IDX
+ self._free_sample_buffers(list(range(start_idx, end_idx + 1)))
else:
- curr_len = self.buffer_size - curr_start + curr_end
- pathlen[i] = curr_len
-
- if not is_array:
- pathlen = pathlen[0]
-
- return pathlen
-
- def is_valid_path(self, idx):
- start_idx = self.get_path_start(idx)
- valid = start_idx != MathUtil.INVALID_IDX
- return valid
-
- def store(self, path):
- start_idx = MathUtil.INVALID_IDX
- n = path.pathlength()
-
- if (n > 0):
- assert path.is_valid()
-
- if path.check_vals():
- if self.buffers is None:
- self._init_buffers(path)
+ self.buffers[self.PATH_START_KEY][start_idx:self.buffer_size] = MathUtil.INVALID_IDX
+ self.buffers[self.PATH_START_KEY][0:end_idx + 1] = MathUtil.INVALID_IDX
+ self._free_sample_buffers(list(range(start_idx, self.buffer_size)))
+ self._free_sample_buffers(list(range(0, end_idx + 1)))
+
+ self.num_paths -= 1
+ i += pathlen + 1
+ self.buffer_tail = (end_idx + 1) % self.buffer_size
+ else:
+ i += 1
+ else:
+ self.buffer_tail = idx[0]
+ return
+
+ def _store_path(self, path, idx):
+ n = path.pathlength()
+ for key, data in self.buffers.items():
+ if key != self.PATH_START_KEY and key != self.PATH_END_KEY and key != self.TERMINATE_KEY:
+ val = getattr(path, key)
+ val_len = len(val)
+ assert val_len == n or val_len == n + 1
+ data[idx[:val_len]] = val
+
+ self.buffers[self.TERMINATE_KEY][idx] = path.terminate.value
+ self.buffers[self.PATH_START_KEY][idx] = idx[0]
+ self.buffers[self.PATH_END_KEY][idx] = idx[-1]
+ return
- idx = self._request_idx(n + 1)
- self._store_path(path, idx)
- self._add_sample_buffers(idx)
-
- self.num_paths += 1
- self.total_count += n + 1
- start_idx = idx[0]
- else:
- Logger.print2('Invalid path data value detected')
-
- return start_idx
-
- def clear(self):
- self.buffer_head = 0
- self.buffer_tail = MathUtil.INVALID_IDX
- self.num_paths = 0
-
- for key in self._sample_buffers:
- self._sample_buffers[key].clear()
- return
-
- def get_next_idx(self, idx):
- next_idx = np.mod(idx + 1, self.buffer_size)
- return next_idx
-
- def is_terminal_state(self, idx):
- terminate_flags = self.buffers[self.TERMINATE_KEY][idx]
- terminate = terminate_flags != Env.Terminate.Null.value
- is_end = self.is_path_end(idx)
- terminal_state = np.logical_and(terminate, is_end)
- return terminal_state
-
- def check_terminal_flag(self, idx, flag):
- terminate_flags = self.buffers[self.TERMINATE_KEY][idx]
- terminate = terminate_flags == flag.value
- return terminate
-
- def is_path_end(self, idx):
- is_end = self.buffers[self.PATH_END_KEY][idx] == idx
- return is_end
-
- def add_filter_key(self, key):
- assert self.get_current_size() == 0
- if key not in self._sample_buffers:
- self._sample_buffers[key] = SampleBuffer(self.buffer_size)
- return
-
- def get_current_size(self):
- if self.buffer_tail == MathUtil.INVALID_IDX:
- return 0
- elif self.buffer_tail < self.buffer_head:
- return self.buffer_head - self.buffer_tail
- else:
- return self.buffer_size - self.buffer_tail + self.buffer_head
-
- def _check_flags(self, key, flags):
- return (flags & key) == key
-
- def _add_sample_buffers(self, idx):
- flags = self.buffers['flags']
- for key in self._sample_buffers:
- curr_buffer = self._sample_buffers[key]
- filter_idx = [i for i in idx if (self._check_flags(key, flags[i]) and not self.is_path_end(i))]
- curr_buffer.add(filter_idx)
- return
-
- def _free_sample_buffers(self, idx):
- for key in self._sample_buffers:
- curr_buffer = self._sample_buffers[key]
- curr_buffer.free(idx)
- return
-
- def _init_buffers(self, path):
- self.buffers = dict()
- self.buffers[self.PATH_START_KEY] = MathUtil.INVALID_IDX * np.ones(self.buffer_size, dtype=int);
- self.buffers[self.PATH_END_KEY] = MathUtil.INVALID_IDX * np.ones(self.buffer_size, dtype=int);
-
- for key in dir(path):
- val = getattr(path, key)
- if not key.startswith('__') and not inspect.ismethod(val):
- if key == self.TERMINATE_KEY:
- self.buffers[self.TERMINATE_KEY] = np.zeros(shape=[self.buffer_size], dtype=int)
- else:
- val_type = type(val[0])
- is_array = val_type == np.ndarray
- if is_array:
- shape = [self.buffer_size, val[0].shape[0]]
- dtype = val[0].dtype
- else:
- shape = [self.buffer_size]
- dtype = val_type
-
- self.buffers[key] = np.zeros(shape, dtype=dtype)
- return
-
- def _request_idx(self, n):
- assert n + 1 < self.buffer_size # bad things can happen if path is too long
-
- remainder = n
- idx = []
-
- start_idx = self.buffer_head
- while remainder > 0:
- end_idx = np.minimum(start_idx + remainder, self.buffer_size)
- remainder -= (end_idx - start_idx)
-
- free_idx = list(range(start_idx, end_idx))
- self._free_idx(free_idx)
- idx += free_idx
- start_idx = 0
-
- self.buffer_head = (self.buffer_head + n) % self.buffer_size
- return idx
-
- def _free_idx(self, idx):
- assert(idx[0] <= idx[-1])
- n = len(idx)
- if self.buffer_tail != MathUtil.INVALID_IDX:
- update_tail = idx[0] <= idx[-1] and idx[0] <= self.buffer_tail and idx[-1] >= self.buffer_tail
- update_tail |= idx[0] > idx[-1] and (idx[0] <= self.buffer_tail or idx[-1] >= self.buffer_tail)
-
- if update_tail:
- i = 0
- while i < n:
- curr_idx = idx[i]
- if self.is_valid_path(curr_idx):
- start_idx = self.get_path_start(curr_idx)
- end_idx = self.get_path_end(curr_idx)
- pathlen = self.get_pathlen(curr_idx)
-
- if start_idx < end_idx:
- self.buffers[self.PATH_START_KEY][start_idx:end_idx + 1] = MathUtil.INVALID_IDX
- self._free_sample_buffers(list(range(start_idx, end_idx + 1)))
- else:
- self.buffers[self.PATH_START_KEY][start_idx:self.buffer_size] = MathUtil.INVALID_IDX
- self.buffers[self.PATH_START_KEY][0:end_idx + 1] = MathUtil.INVALID_IDX
- self._free_sample_buffers(list(range(start_idx, self.buffer_size)))
- self._free_sample_buffers(list(range(0, end_idx + 1)))
-
- self.num_paths -= 1
- i += pathlen + 1
- self.buffer_tail = (end_idx + 1) % self.buffer_size;
- else:
- i += 1
- else:
- self.buffer_tail = idx[0]
- return
-
- def _store_path(self, path, idx):
- n = path.pathlength()
- for key, data in self.buffers.items():
- if key != self.PATH_START_KEY and key != self.PATH_END_KEY and key != self.TERMINATE_KEY:
- val = getattr(path, key)
- val_len = len(val)
- assert val_len == n or val_len == n + 1
- data[idx[:val_len]] = val
-
- self.buffers[self.TERMINATE_KEY][idx] = path.terminate.value
- self.buffers[self.PATH_START_KEY][idx] = idx[0]
- self.buffers[self.PATH_END_KEY][idx] = idx[-1]
- return
class SampleBuffer(object):
- def __init__(self, size):
- self.idx_to_slot = np.empty(shape=[size], dtype=int)
- self.slot_to_idx = np.empty(shape=[size], dtype=int)
- self.count = 0
- self.clear()
- return
-
- def clear(self):
- self.idx_to_slot.fill(MathUtil.INVALID_IDX)
- self.slot_to_idx.fill(MathUtil.INVALID_IDX)
- self.count = 0
- return
-
- def is_valid(self, idx):
- return self.idx_to_slot[idx] != MathUtil.INVALID_IDX
-
- def get_size(self):
- return self.idx_to_slot.shape[0]
-
- def add(self, idx):
- for i in idx:
- if not self.is_valid(i):
- new_slot = self.count
- assert new_slot >= 0
-
- self.idx_to_slot[i] = new_slot
- self.slot_to_idx[new_slot] = i
- self.count += 1
- return
-
- def free(self, idx):
- for i in idx:
- if self.is_valid(i):
- slot = self.idx_to_slot[i]
- last_slot = self.count - 1
- last_idx = self.slot_to_idx[last_slot]
-
- self.idx_to_slot[last_idx] = slot
- self.slot_to_idx[slot] = last_idx
- self.idx_to_slot[i] = MathUtil.INVALID_IDX
- self.slot_to_idx[last_slot] = MathUtil.INVALID_IDX
- self.count -= 1
- return
-
- def sample(self, n):
- if self.count > 0:
- slots = np.random.randint(0, self.count, size=n)
- idx = self.slot_to_idx[slots]
- else:
- idx = np.empty(shape=[0], dtype=int)
- return idx
- def check_consistency(self):
- valid = True
- if self.count < 0:
+ def __init__(self, size):
+ self.idx_to_slot = np.empty(shape=[size], dtype=int)
+ self.slot_to_idx = np.empty(shape=[size], dtype=int)
+ self.count = 0
+ self.clear()
+ return
+
+ def clear(self):
+ self.idx_to_slot.fill(MathUtil.INVALID_IDX)
+ self.slot_to_idx.fill(MathUtil.INVALID_IDX)
+ self.count = 0
+ return
+
+ def is_valid(self, idx):
+ return self.idx_to_slot[idx] != MathUtil.INVALID_IDX
+
+ def get_size(self):
+ return self.idx_to_slot.shape[0]
+
+ def add(self, idx):
+ for i in idx:
+ if not self.is_valid(i):
+ new_slot = self.count
+ assert new_slot >= 0
+
+ self.idx_to_slot[i] = new_slot
+ self.slot_to_idx[new_slot] = i
+ self.count += 1
+ return
+
+ def free(self, idx):
+ for i in idx:
+ if self.is_valid(i):
+ slot = self.idx_to_slot[i]
+ last_slot = self.count - 1
+ last_idx = self.slot_to_idx[last_slot]
+
+ self.idx_to_slot[last_idx] = slot
+ self.slot_to_idx[slot] = last_idx
+ self.idx_to_slot[i] = MathUtil.INVALID_IDX
+ self.slot_to_idx[last_slot] = MathUtil.INVALID_IDX
+ self.count -= 1
+ return
+
+ def sample(self, n):
+ if self.count > 0:
+ slots = np.random.randint(0, self.count, size=n)
+ idx = self.slot_to_idx[slots]
+ else:
+ idx = np.empty(shape=[0], dtype=int)
+ return idx
+
+ def check_consistency(self):
+ valid = True
+ if self.count < 0:
+ valid = False
+
+ if valid:
+ for i in range(self.get_size()):
+ if self.is_valid(i):
+ s = self.idx_to_slot[i]
+ if self.slot_to_idx[s] != i:
+ valid = False
+ break
+
+ s2i = self.slot_to_idx[i]
+ if s2i != MathUtil.INVALID_IDX:
+ i2s = self.idx_to_slot[s2i]
+ if i2s != i:
valid = False
+ break
- if valid:
- for i in range(self.get_size()):
- if self.is_valid(i):
- s = self.idx_to_slot[i]
- if self.slot_to_idx[s] != i:
- valid = False
- break
-
- s2i = self.slot_to_idx[i]
- if s2i != MathUtil.INVALID_IDX:
- i2s = self.idx_to_slot[s2i]
- if i2s != i:
- valid = False
- break
-
- count0 = np.sum(self.idx_to_slot == MathUtil.INVALID_IDX)
- count1 = np.sum(self.slot_to_idx == MathUtil.INVALID_IDX)
- valid &= count0 == count1
- return valid
+ count0 = np.sum(self.idx_to_slot == MathUtil.INVALID_IDX)
+ count1 = np.sum(self.slot_to_idx == MathUtil.INVALID_IDX)
+ valid &= count0 == count1
+ return valid
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_agent.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_agent.py
index ce6b2a9f4..fe9a05d85 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_agent.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_agent.py
@@ -6,9 +6,9 @@ import sys
from abc import abstractmethod
import abc
if sys.version_info >= (3, 4):
- ABC = abc.ABC
+ ABC = abc.ABC
else:
- ABC = abc.ABCMeta('ABC', (), {})
+ ABC = abc.ABCMeta('ABC', (), {})
from enum import Enum
@@ -20,583 +20,586 @@ from pybullet_utils.logger import Logger
import pybullet_utils.mpi_util as MPIUtil
import pybullet_utils.math_util as MathUtil
+
class RLAgent(ABC):
- class Mode(Enum):
- TRAIN = 0
- TEST = 1
- TRAIN_END = 2
-
- NAME = "None"
-
- UPDATE_PERIOD_KEY = "UpdatePeriod"
- ITERS_PER_UPDATE = "ItersPerUpdate"
- DISCOUNT_KEY = "Discount"
- MINI_BATCH_SIZE_KEY = "MiniBatchSize"
- REPLAY_BUFFER_SIZE_KEY = "ReplayBufferSize"
- INIT_SAMPLES_KEY = "InitSamples"
- NORMALIZER_SAMPLES_KEY = "NormalizerSamples"
-
- OUTPUT_ITERS_KEY = "OutputIters"
- INT_OUTPUT_ITERS_KEY = "IntOutputIters"
- TEST_EPISODES_KEY = "TestEpisodes"
-
- EXP_ANNEAL_SAMPLES_KEY = "ExpAnnealSamples"
- EXP_PARAM_BEG_KEY = "ExpParamsBeg"
- EXP_PARAM_END_KEY = "ExpParamsEnd"
-
- def __init__(self, world, id, json_data):
- self.world = world
- self.id = id
- self.logger = Logger()
- self._mode = self.Mode.TRAIN
-
- assert self._check_action_space(), \
- Logger.print2("Invalid action space, got {:s}".format(str(self.get_action_space())))
-
- self._enable_training = True
- self.path = Path()
- self.iter = int(0)
- self.start_time = time.time()
- self._update_counter = 0
-
- self.update_period = 1.0 # simulated time (seconds) before each training update
- self.iters_per_update = int(1)
- self.discount = 0.95
- self.mini_batch_size = int(32)
- self.replay_buffer_size = int(50000)
- self.init_samples = int(1000)
- self.normalizer_samples = np.inf
- self._local_mini_batch_size = self.mini_batch_size # batch size for each work for multiprocessing
- self._need_normalizer_update = True
- self._total_sample_count = 0
-
- self._output_dir = ""
- self._int_output_dir = ""
- self.output_iters = 100
- self.int_output_iters = 100
-
- self.train_return = 0.0
- self.test_episodes = int(0)
- self.test_episode_count = int(0)
- self.test_return = 0.0
- self.avg_test_return = 0.0
-
- self.exp_anneal_samples = 320000
- self.exp_params_beg = ExpParams()
- self.exp_params_end = ExpParams()
- self.exp_params_curr = ExpParams()
-
- self._load_params(json_data)
- self._build_replay_buffer(self.replay_buffer_size)
- self._build_normalizers()
- self._build_bounds()
- self.reset()
-
- return
-
- def __str__(self):
- action_space_str = str(self.get_action_space())
- info_str = ""
- info_str += '"ID": {:d},\n "Type": "{:s}",\n "ActionSpace": "{:s}",\n "StateDim": {:d},\n "GoalDim": {:d},\n "ActionDim": {:d}'.format(
- self.id, self.NAME, action_space_str[action_space_str.rfind('.') + 1:], self.get_state_size(), self.get_goal_size(), self.get_action_size())
- return "{\n" + info_str + "\n}"
-
- def get_output_dir(self):
- return self._output_dir
-
- def set_output_dir(self, out_dir):
- self._output_dir = out_dir
- if (self._output_dir != ""):
- self.logger.configure_output_file(out_dir + "/agent" + str(self.id) + "_log.txt")
- return
-
- output_dir = property(get_output_dir, set_output_dir)
-
- def get_int_output_dir(self):
- return self._int_output_dir
-
- def set_int_output_dir(self, out_dir):
- self._int_output_dir = out_dir
- return
-
- int_output_dir = property(get_int_output_dir, set_int_output_dir)
-
- def reset(self):
- self.path.clear()
- return
-
- def update(self, timestep):
- if self.need_new_action():
- #print("update_new_action!!!")
- self._update_new_action()
-
-
- if (self._mode == self.Mode.TRAIN and self.enable_training):
- self._update_counter += timestep
-
- while self._update_counter >= self.update_period:
- self._train()
- self._update_exp_params()
- self.world.env.set_sample_count(self._total_sample_count)
- self._update_counter -= self.update_period
-
- return
-
- def end_episode(self):
- if (self.path.pathlength() > 0):
- self._end_path()
-
- if (self._mode == self.Mode.TRAIN or self._mode == self.Mode.TRAIN_END):
- if (self.enable_training and self.path.pathlength() > 0):
- self._store_path(self.path)
- elif (self._mode == self.Mode.TEST):
- self._update_test_return(self.path)
- else:
- assert False, Logger.print2("Unsupported RL agent mode" + str(self._mode))
-
- self._update_mode()
- return
-
- def has_goal(self):
- return self.get_goal_size() > 0
-
- def predict_val(self):
- return 0
-
- def get_enable_training(self):
- return self._enable_training
-
- def set_enable_training(self, enable):
- print("set_enable_training=", enable)
- self._enable_training = enable
- if (self._enable_training):
- self.reset()
- return
-
- enable_training = property(get_enable_training, set_enable_training)
-
- def enable_testing(self):
- return self.test_episodes > 0
-
- def get_name(self):
- return self.NAME
-
- @abstractmethod
- def save_model(self, out_path):
- pass
-
- @abstractmethod
- def load_model(self, in_path):
- pass
-
- @abstractmethod
- def _decide_action(self, s, g):
- pass
-
- @abstractmethod
- def _get_output_path(self):
- pass
-
- @abstractmethod
- def _get_int_output_path(self):
- pass
-
- @abstractmethod
- def _train_step(self):
- pass
-
- @abstractmethod
- def _check_action_space(self):
- pass
-
- def get_action_space(self):
- return self.world.env.get_action_space(self.id)
-
- def get_state_size(self):
- return self.world.env.get_state_size(self.id)
-
- def get_goal_size(self):
- return self.world.env.get_goal_size(self.id)
-
- def get_action_size(self):
- return self.world.env.get_action_size(self.id)
-
- def get_num_actions(self):
- return self.world.env.get_num_actions(self.id)
-
- def need_new_action(self):
- return self.world.env.need_new_action(self.id)
-
- def _build_normalizers(self):
- self.s_norm = Normalizer(self.get_state_size(), self.world.env.build_state_norm_groups(self.id))
- self.s_norm.set_mean_std(-self.world.env.build_state_offset(self.id),
- 1 / self.world.env.build_state_scale(self.id))
-
- self.g_norm = Normalizer(self.get_goal_size(), self.world.env.build_goal_norm_groups(self.id))
- self.g_norm.set_mean_std(-self.world.env.build_goal_offset(self.id),
- 1 / self.world.env.build_goal_scale(self.id))
-
- self.a_norm = Normalizer(self.world.env.get_action_size())
- self.a_norm.set_mean_std(-self.world.env.build_action_offset(self.id),
- 1 / self.world.env.build_action_scale(self.id))
- return
-
- def _build_bounds(self):
- self.a_bound_min = self.world.env.build_action_bound_min(self.id)
- self.a_bound_max = self.world.env.build_action_bound_max(self.id)
- return
-
- def _load_params(self, json_data):
- if (self.UPDATE_PERIOD_KEY in json_data):
- self.update_period = int(json_data[self.UPDATE_PERIOD_KEY])
-
- if (self.ITERS_PER_UPDATE in json_data):
- self.iters_per_update = int(json_data[self.ITERS_PER_UPDATE])
-
- if (self.DISCOUNT_KEY in json_data):
- self.discount = json_data[self.DISCOUNT_KEY]
-
- if (self.MINI_BATCH_SIZE_KEY in json_data):
- self.mini_batch_size = int(json_data[self.MINI_BATCH_SIZE_KEY])
-
- if (self.REPLAY_BUFFER_SIZE_KEY in json_data):
- self.replay_buffer_size = int(json_data[self.REPLAY_BUFFER_SIZE_KEY])
-
- if (self.INIT_SAMPLES_KEY in json_data):
- self.init_samples = int(json_data[self.INIT_SAMPLES_KEY])
-
- if (self.NORMALIZER_SAMPLES_KEY in json_data):
- self.normalizer_samples = int(json_data[self.NORMALIZER_SAMPLES_KEY])
-
- if (self.OUTPUT_ITERS_KEY in json_data):
- self.output_iters = json_data[self.OUTPUT_ITERS_KEY]
-
- if (self.INT_OUTPUT_ITERS_KEY in json_data):
- self.int_output_iters = json_data[self.INT_OUTPUT_ITERS_KEY]
-
- if (self.TEST_EPISODES_KEY in json_data):
- self.test_episodes = int(json_data[self.TEST_EPISODES_KEY])
-
- if (self.EXP_ANNEAL_SAMPLES_KEY in json_data):
- self.exp_anneal_samples = json_data[self.EXP_ANNEAL_SAMPLES_KEY]
-
- if (self.EXP_PARAM_BEG_KEY in json_data):
- self.exp_params_beg.load(json_data[self.EXP_PARAM_BEG_KEY])
-
- if (self.EXP_PARAM_END_KEY in json_data):
- self.exp_params_end.load(json_data[self.EXP_PARAM_END_KEY])
-
- num_procs = MPIUtil.get_num_procs()
- self._local_mini_batch_size = int(np.ceil(self.mini_batch_size / num_procs))
- self._local_mini_batch_size = np.maximum(self._local_mini_batch_size, 1)
- self.mini_batch_size = self._local_mini_batch_size * num_procs
-
- assert(self.exp_params_beg.noise == self.exp_params_end.noise) # noise std should not change
- self.exp_params_curr = copy.deepcopy(self.exp_params_beg)
- self.exp_params_end.noise = self.exp_params_beg.noise
-
- self._need_normalizer_update = self.normalizer_samples > 0
-
- return
-
- def _record_state(self):
- s = self.world.env.record_state(self.id)
- return s
-
- def _record_goal(self):
- g = self.world.env.record_goal(self.id)
- return g
-
- def _record_reward(self):
- r = self.world.env.calc_reward(self.id)
- return r
-
- def _apply_action(self, a):
- self.world.env.set_action(self.id, a)
- return
-
- def _record_flags(self):
- return int(0)
-
- def _is_first_step(self):
- return len(self.path.states) == 0
-
- def _end_path(self):
- s = self._record_state()
- g = self._record_goal()
- r = self._record_reward()
-
- self.path.rewards.append(r)
- self.path.states.append(s)
- self.path.goals.append(g)
- self.path.terminate = self.world.env.check_terminate(self.id)
-
- return
-
- def _update_new_action(self):
- #print("_update_new_action!")
- s = self._record_state()
- #np.savetxt("pb_record_state_s.csv", s, delimiter=",")
- g = self._record_goal()
-
- if not (self._is_first_step()):
- r = self._record_reward()
- self.path.rewards.append(r)
-
- a, logp = self._decide_action(s=s, g=g)
- assert len(np.shape(a)) == 1
- assert len(np.shape(logp)) <= 1
-
- flags = self._record_flags()
- self._apply_action(a)
-
- self.path.states.append(s)
- self.path.goals.append(g)
- self.path.actions.append(a)
- self.path.logps.append(logp)
- self.path.flags.append(flags)
-
- if self._enable_draw():
- self._log_val(s, g)
-
- return
-
- def _update_exp_params(self):
- lerp = float(self._total_sample_count) / self.exp_anneal_samples
- lerp = np.clip(lerp, 0.0, 1.0)
- self.exp_params_curr = self.exp_params_beg.lerp(self.exp_params_end, lerp)
- return
-
- def _update_test_return(self, path):
- path_reward = path.calc_return()
- self.test_return += path_reward
- self.test_episode_count += 1
- return
-
- def _update_mode(self):
- if (self._mode == self.Mode.TRAIN):
- self._update_mode_train()
- elif (self._mode == self.Mode.TRAIN_END):
- self._update_mode_train_end()
- elif (self._mode == self.Mode.TEST):
- self._update_mode_test()
- else:
- assert False, Logger.print2("Unsupported RL agent mode" + str(self._mode))
- return
-
- def _update_mode_train(self):
- return
-
- def _update_mode_train_end(self):
- self._init_mode_test()
- return
-
- def _update_mode_test(self):
- if (self.test_episode_count * MPIUtil.get_num_procs() >= self.test_episodes):
- global_return = MPIUtil.reduce_sum(self.test_return)
- global_count = MPIUtil.reduce_sum(self.test_episode_count)
- avg_return = global_return / global_count
- self.avg_test_return = avg_return
-
- if self.enable_training:
- self._init_mode_train()
- return
-
- def _init_mode_train(self):
- self._mode = self.Mode.TRAIN
- self.world.env.set_mode(self._mode)
- return
-
- def _init_mode_train_end(self):
- self._mode = self.Mode.TRAIN_END
- return
-
- def _init_mode_test(self):
- self._mode = self.Mode.TEST
- self.test_return = 0.0
- self.test_episode_count = 0
- self.world.env.set_mode(self._mode)
- return
-
- def _enable_output(self):
- return MPIUtil.is_root_proc() and self.output_dir != ""
-
- def _enable_int_output(self):
- return MPIUtil.is_root_proc() and self.int_output_dir != ""
-
- def _calc_val_bounds(self, discount):
- r_min = self.world.env.get_reward_min(self.id)
- r_max = self.world.env.get_reward_max(self.id)
- assert(r_min <= r_max)
-
- val_min = r_min / ( 1.0 - discount)
- val_max = r_max / ( 1.0 - discount)
- return val_min, val_max
-
- def _calc_val_offset_scale(self, discount):
- val_min, val_max = self._calc_val_bounds(discount)
- val_offset = 0
- val_scale = 1
-
- if (np.isfinite(val_min) and np.isfinite(val_max)):
- val_offset = -0.5 * (val_max + val_min)
- val_scale = 2 / (val_max - val_min)
-
- return val_offset, val_scale
-
- def _calc_term_vals(self, discount):
- r_fail = self.world.env.get_reward_fail(self.id)
- r_succ = self.world.env.get_reward_succ(self.id)
-
- r_min = self.world.env.get_reward_min(self.id)
- r_max = self.world.env.get_reward_max(self.id)
- assert(r_fail <= r_max and r_fail >= r_min)
- assert(r_succ <= r_max and r_succ >= r_min)
- assert(not np.isinf(r_fail))
- assert(not np.isinf(r_succ))
-
- if (discount == 0):
- val_fail = 0
- val_succ = 0
- else:
- val_fail = r_fail / (1.0 - discount)
- val_succ = r_succ / (1.0 - discount)
-
- return val_fail, val_succ
-
- def _update_iter(self, iter):
- if (self._enable_output() and self.iter % self.output_iters == 0):
- output_path = self._get_output_path()
- output_dir = os.path.dirname(output_path)
- if not os.path.exists(output_dir):
- os.makedirs(output_dir)
- self.save_model(output_path)
-
- if (self._enable_int_output() and self.iter % self.int_output_iters == 0):
- int_output_path = self._get_int_output_path()
- int_output_dir = os.path.dirname(int_output_path)
- if not os.path.exists(int_output_dir):
- os.makedirs(int_output_dir)
- self.save_model(int_output_path)
-
- self.iter = iter
- return
-
- def _enable_draw(self):
- return self.world.env.enable_draw
-
- def _log_val(self, s, g):
- pass
-
- def _build_replay_buffer(self, buffer_size):
- num_procs = MPIUtil.get_num_procs()
- buffer_size = int(buffer_size / num_procs)
- self.replay_buffer = ReplayBuffer(buffer_size=buffer_size)
- self.replay_buffer_initialized = False
- return
-
- def _store_path(self, path):
- path_id = self.replay_buffer.store(path)
- valid_path = path_id != MathUtil.INVALID_IDX
-
- if valid_path:
- self.train_return = path.calc_return()
-
- if self._need_normalizer_update:
- self._record_normalizers(path)
-
- return path_id
-
- def _record_normalizers(self, path):
- states = np.array(path.states)
- self.s_norm.record(states)
-
- if self.has_goal():
- goals = np.array(path.goals)
- self.g_norm.record(goals)
-
- return
-
- def _update_normalizers(self):
- self.s_norm.update()
-
- if self.has_goal():
- self.g_norm.update()
- return
-
- def _train(self):
- samples = self.replay_buffer.total_count
- self._total_sample_count = int(MPIUtil.reduce_sum(samples))
- end_training = False
-
- if (self.replay_buffer_initialized):
- if (self._valid_train_step()):
- prev_iter = self.iter
- iters = self._get_iters_per_update()
- avg_train_return = MPIUtil.reduce_avg(self.train_return)
-
- for i in range(iters):
- curr_iter = self.iter
- wall_time = time.time() - self.start_time
- wall_time /= 60 * 60 # store time in hours
-
- has_goal = self.has_goal()
- s_mean = np.mean(self.s_norm.mean)
- s_std = np.mean(self.s_norm.std)
- g_mean = np.mean(self.g_norm.mean) if has_goal else 0
- g_std = np.mean(self.g_norm.std) if has_goal else 0
-
- self.logger.log_tabular("Iteration", self.iter)
- self.logger.log_tabular("Wall_Time", wall_time)
- self.logger.log_tabular("Samples", self._total_sample_count)
- self.logger.log_tabular("Train_Return", avg_train_return)
- self.logger.log_tabular("Test_Return", self.avg_test_return)
- self.logger.log_tabular("State_Mean", s_mean)
- self.logger.log_tabular("State_Std", s_std)
- self.logger.log_tabular("Goal_Mean", g_mean)
- self.logger.log_tabular("Goal_Std", g_std)
- self._log_exp_params()
-
- self._update_iter(self.iter + 1)
- self._train_step()
-
- Logger.print2("Agent " + str(self.id))
- self.logger.print_tabular()
- Logger.print2("")
-
- if (self._enable_output() and curr_iter % self.int_output_iters == 0):
- self.logger.dump_tabular()
-
- if (prev_iter // self.int_output_iters != self.iter // self.int_output_iters):
- end_training = self.enable_testing()
-
- else:
-
- Logger.print2("Agent " + str(self.id))
- Logger.print2("Samples: " + str(self._total_sample_count))
- Logger.print2("")
-
- if (self._total_sample_count >= self.init_samples):
- self.replay_buffer_initialized = True
- end_training = self.enable_testing()
-
- if self._need_normalizer_update:
- self._update_normalizers()
- self._need_normalizer_update = self.normalizer_samples > self._total_sample_count
-
- if end_training:
- self._init_mode_train_end()
-
- return
-
- def _get_iters_per_update(self):
- return MPIUtil.get_num_procs() * self.iters_per_update
-
- def _valid_train_step(self):
- return True
-
- def _log_exp_params(self):
- self.logger.log_tabular("Exp_Rate", self.exp_params_curr.rate)
- self.logger.log_tabular("Exp_Noise", self.exp_params_curr.noise)
- self.logger.log_tabular("Exp_Temp", self.exp_params_curr.temp)
- return
+
+ class Mode(Enum):
+ TRAIN = 0
+ TEST = 1
+ TRAIN_END = 2
+
+ NAME = "None"
+
+ UPDATE_PERIOD_KEY = "UpdatePeriod"
+ ITERS_PER_UPDATE = "ItersPerUpdate"
+ DISCOUNT_KEY = "Discount"
+ MINI_BATCH_SIZE_KEY = "MiniBatchSize"
+ REPLAY_BUFFER_SIZE_KEY = "ReplayBufferSize"
+ INIT_SAMPLES_KEY = "InitSamples"
+ NORMALIZER_SAMPLES_KEY = "NormalizerSamples"
+
+ OUTPUT_ITERS_KEY = "OutputIters"
+ INT_OUTPUT_ITERS_KEY = "IntOutputIters"
+ TEST_EPISODES_KEY = "TestEpisodes"
+
+ EXP_ANNEAL_SAMPLES_KEY = "ExpAnnealSamples"
+ EXP_PARAM_BEG_KEY = "ExpParamsBeg"
+ EXP_PARAM_END_KEY = "ExpParamsEnd"
+
+ def __init__(self, world, id, json_data):
+ self.world = world
+ self.id = id
+ self.logger = Logger()
+ self._mode = self.Mode.TRAIN
+
+ assert self._check_action_space(), \
+ Logger.print2("Invalid action space, got {:s}".format(str(self.get_action_space())))
+
+ self._enable_training = True
+ self.path = Path()
+ self.iter = int(0)
+ self.start_time = time.time()
+ self._update_counter = 0
+
+ self.update_period = 1.0 # simulated time (seconds) before each training update
+ self.iters_per_update = int(1)
+ self.discount = 0.95
+ self.mini_batch_size = int(32)
+ self.replay_buffer_size = int(50000)
+ self.init_samples = int(1000)
+ self.normalizer_samples = np.inf
+ self._local_mini_batch_size = self.mini_batch_size # batch size for each work for multiprocessing
+ self._need_normalizer_update = True
+ self._total_sample_count = 0
+
+ self._output_dir = ""
+ self._int_output_dir = ""
+ self.output_iters = 100
+ self.int_output_iters = 100
+
+ self.train_return = 0.0
+ self.test_episodes = int(0)
+ self.test_episode_count = int(0)
+ self.test_return = 0.0
+ self.avg_test_return = 0.0
+
+ self.exp_anneal_samples = 320000
+ self.exp_params_beg = ExpParams()
+ self.exp_params_end = ExpParams()
+ self.exp_params_curr = ExpParams()
+
+ self._load_params(json_data)
+ self._build_replay_buffer(self.replay_buffer_size)
+ self._build_normalizers()
+ self._build_bounds()
+ self.reset()
+
+ return
+
+ def __str__(self):
+ action_space_str = str(self.get_action_space())
+ info_str = ""
+ info_str += '"ID": {:d},\n "Type": "{:s}",\n "ActionSpace": "{:s}",\n "StateDim": {:d},\n "GoalDim": {:d},\n "ActionDim": {:d}'.format(
+ self.id, self.NAME, action_space_str[action_space_str.rfind('.') + 1:],
+ self.get_state_size(), self.get_goal_size(), self.get_action_size())
+ return "{\n" + info_str + "\n}"
+
+ def get_output_dir(self):
+ return self._output_dir
+
+ def set_output_dir(self, out_dir):
+ self._output_dir = out_dir
+ if (self._output_dir != ""):
+ self.logger.configure_output_file(out_dir + "/agent" + str(self.id) + "_log.txt")
+ return
+
+ output_dir = property(get_output_dir, set_output_dir)
+
+ def get_int_output_dir(self):
+ return self._int_output_dir
+
+ def set_int_output_dir(self, out_dir):
+ self._int_output_dir = out_dir
+ return
+
+ int_output_dir = property(get_int_output_dir, set_int_output_dir)
+
+ def reset(self):
+ self.path.clear()
+ return
+
+ def update(self, timestep):
+ if self.need_new_action():
+ #print("update_new_action!!!")
+ self._update_new_action()
+
+ if (self._mode == self.Mode.TRAIN and self.enable_training):
+ self._update_counter += timestep
+
+ while self._update_counter >= self.update_period:
+ self._train()
+ self._update_exp_params()
+ self.world.env.set_sample_count(self._total_sample_count)
+ self._update_counter -= self.update_period
+
+ return
+
+ def end_episode(self):
+ if (self.path.pathlength() > 0):
+ self._end_path()
+
+ if (self._mode == self.Mode.TRAIN or self._mode == self.Mode.TRAIN_END):
+ if (self.enable_training and self.path.pathlength() > 0):
+ self._store_path(self.path)
+ elif (self._mode == self.Mode.TEST):
+ self._update_test_return(self.path)
+ else:
+ assert False, Logger.print2("Unsupported RL agent mode" + str(self._mode))
+
+ self._update_mode()
+ return
+
+ def has_goal(self):
+ return self.get_goal_size() > 0
+
+ def predict_val(self):
+ return 0
+
+ def get_enable_training(self):
+ return self._enable_training
+
+ def set_enable_training(self, enable):
+ print("set_enable_training=", enable)
+ self._enable_training = enable
+ if (self._enable_training):
+ self.reset()
+ return
+
+ enable_training = property(get_enable_training, set_enable_training)
+
+ def enable_testing(self):
+ return self.test_episodes > 0
+
+ def get_name(self):
+ return self.NAME
+
+ @abstractmethod
+ def save_model(self, out_path):
+ pass
+
+ @abstractmethod
+ def load_model(self, in_path):
+ pass
+
+ @abstractmethod
+ def _decide_action(self, s, g):
+ pass
+
+ @abstractmethod
+ def _get_output_path(self):
+ pass
+
+ @abstractmethod
+ def _get_int_output_path(self):
+ pass
+
+ @abstractmethod
+ def _train_step(self):
+ pass
+
+ @abstractmethod
+ def _check_action_space(self):
+ pass
+
+ def get_action_space(self):
+ return self.world.env.get_action_space(self.id)
+
+ def get_state_size(self):
+ return self.world.env.get_state_size(self.id)
+
+ def get_goal_size(self):
+ return self.world.env.get_goal_size(self.id)
+
+ def get_action_size(self):
+ return self.world.env.get_action_size(self.id)
+
+ def get_num_actions(self):
+ return self.world.env.get_num_actions(self.id)
+
+ def need_new_action(self):
+ return self.world.env.need_new_action(self.id)
+
+ def _build_normalizers(self):
+ self.s_norm = Normalizer(self.get_state_size(),
+ self.world.env.build_state_norm_groups(self.id))
+ self.s_norm.set_mean_std(-self.world.env.build_state_offset(self.id),
+ 1 / self.world.env.build_state_scale(self.id))
+
+ self.g_norm = Normalizer(self.get_goal_size(), self.world.env.build_goal_norm_groups(self.id))
+ self.g_norm.set_mean_std(-self.world.env.build_goal_offset(self.id),
+ 1 / self.world.env.build_goal_scale(self.id))
+
+ self.a_norm = Normalizer(self.world.env.get_action_size())
+ self.a_norm.set_mean_std(-self.world.env.build_action_offset(self.id),
+ 1 / self.world.env.build_action_scale(self.id))
+ return
+
+ def _build_bounds(self):
+ self.a_bound_min = self.world.env.build_action_bound_min(self.id)
+ self.a_bound_max = self.world.env.build_action_bound_max(self.id)
+ return
+
+ def _load_params(self, json_data):
+ if (self.UPDATE_PERIOD_KEY in json_data):
+ self.update_period = int(json_data[self.UPDATE_PERIOD_KEY])
+
+ if (self.ITERS_PER_UPDATE in json_data):
+ self.iters_per_update = int(json_data[self.ITERS_PER_UPDATE])
+
+ if (self.DISCOUNT_KEY in json_data):
+ self.discount = json_data[self.DISCOUNT_KEY]
+
+ if (self.MINI_BATCH_SIZE_KEY in json_data):
+ self.mini_batch_size = int(json_data[self.MINI_BATCH_SIZE_KEY])
+
+ if (self.REPLAY_BUFFER_SIZE_KEY in json_data):
+ self.replay_buffer_size = int(json_data[self.REPLAY_BUFFER_SIZE_KEY])
+
+ if (self.INIT_SAMPLES_KEY in json_data):
+ self.init_samples = int(json_data[self.INIT_SAMPLES_KEY])
+
+ if (self.NORMALIZER_SAMPLES_KEY in json_data):
+ self.normalizer_samples = int(json_data[self.NORMALIZER_SAMPLES_KEY])
+
+ if (self.OUTPUT_ITERS_KEY in json_data):
+ self.output_iters = json_data[self.OUTPUT_ITERS_KEY]
+
+ if (self.INT_OUTPUT_ITERS_KEY in json_data):
+ self.int_output_iters = json_data[self.INT_OUTPUT_ITERS_KEY]
+
+ if (self.TEST_EPISODES_KEY in json_data):
+ self.test_episodes = int(json_data[self.TEST_EPISODES_KEY])
+
+ if (self.EXP_ANNEAL_SAMPLES_KEY in json_data):
+ self.exp_anneal_samples = json_data[self.EXP_ANNEAL_SAMPLES_KEY]
+
+ if (self.EXP_PARAM_BEG_KEY in json_data):
+ self.exp_params_beg.load(json_data[self.EXP_PARAM_BEG_KEY])
+
+ if (self.EXP_PARAM_END_KEY in json_data):
+ self.exp_params_end.load(json_data[self.EXP_PARAM_END_KEY])
+
+ num_procs = MPIUtil.get_num_procs()
+ self._local_mini_batch_size = int(np.ceil(self.mini_batch_size / num_procs))
+ self._local_mini_batch_size = np.maximum(self._local_mini_batch_size, 1)
+ self.mini_batch_size = self._local_mini_batch_size * num_procs
+
+ assert (self.exp_params_beg.noise == self.exp_params_end.noise) # noise std should not change
+ self.exp_params_curr = copy.deepcopy(self.exp_params_beg)
+ self.exp_params_end.noise = self.exp_params_beg.noise
+
+ self._need_normalizer_update = self.normalizer_samples > 0
+
+ return
+
+ def _record_state(self):
+ s = self.world.env.record_state(self.id)
+ return s
+
+ def _record_goal(self):
+ g = self.world.env.record_goal(self.id)
+ return g
+
+ def _record_reward(self):
+ r = self.world.env.calc_reward(self.id)
+ return r
+
+ def _apply_action(self, a):
+ self.world.env.set_action(self.id, a)
+ return
+
+ def _record_flags(self):
+ return int(0)
+
+ def _is_first_step(self):
+ return len(self.path.states) == 0
+
+ def _end_path(self):
+ s = self._record_state()
+ g = self._record_goal()
+ r = self._record_reward()
+
+ self.path.rewards.append(r)
+ self.path.states.append(s)
+ self.path.goals.append(g)
+ self.path.terminate = self.world.env.check_terminate(self.id)
+
+ return
+
+ def _update_new_action(self):
+ #print("_update_new_action!")
+ s = self._record_state()
+ #np.savetxt("pb_record_state_s.csv", s, delimiter=",")
+ g = self._record_goal()
+
+ if not (self._is_first_step()):
+ r = self._record_reward()
+ self.path.rewards.append(r)
+
+ a, logp = self._decide_action(s=s, g=g)
+ assert len(np.shape(a)) == 1
+ assert len(np.shape(logp)) <= 1
+
+ flags = self._record_flags()
+ self._apply_action(a)
+
+ self.path.states.append(s)
+ self.path.goals.append(g)
+ self.path.actions.append(a)
+ self.path.logps.append(logp)
+ self.path.flags.append(flags)
+
+ if self._enable_draw():
+ self._log_val(s, g)
+
+ return
+
+ def _update_exp_params(self):
+ lerp = float(self._total_sample_count) / self.exp_anneal_samples
+ lerp = np.clip(lerp, 0.0, 1.0)
+ self.exp_params_curr = self.exp_params_beg.lerp(self.exp_params_end, lerp)
+ return
+
+ def _update_test_return(self, path):
+ path_reward = path.calc_return()
+ self.test_return += path_reward
+ self.test_episode_count += 1
+ return
+
+ def _update_mode(self):
+ if (self._mode == self.Mode.TRAIN):
+ self._update_mode_train()
+ elif (self._mode == self.Mode.TRAIN_END):
+ self._update_mode_train_end()
+ elif (self._mode == self.Mode.TEST):
+ self._update_mode_test()
+ else:
+ assert False, Logger.print2("Unsupported RL agent mode" + str(self._mode))
+ return
+
+ def _update_mode_train(self):
+ return
+
+ def _update_mode_train_end(self):
+ self._init_mode_test()
+ return
+
+ def _update_mode_test(self):
+ if (self.test_episode_count * MPIUtil.get_num_procs() >= self.test_episodes):
+ global_return = MPIUtil.reduce_sum(self.test_return)
+ global_count = MPIUtil.reduce_sum(self.test_episode_count)
+ avg_return = global_return / global_count
+ self.avg_test_return = avg_return
+
+ if self.enable_training:
+ self._init_mode_train()
+ return
+
+ def _init_mode_train(self):
+ self._mode = self.Mode.TRAIN
+ self.world.env.set_mode(self._mode)
+ return
+
+ def _init_mode_train_end(self):
+ self._mode = self.Mode.TRAIN_END
+ return
+
+ def _init_mode_test(self):
+ self._mode = self.Mode.TEST
+ self.test_return = 0.0
+ self.test_episode_count = 0
+ self.world.env.set_mode(self._mode)
+ return
+
+ def _enable_output(self):
+ return MPIUtil.is_root_proc() and self.output_dir != ""
+
+ def _enable_int_output(self):
+ return MPIUtil.is_root_proc() and self.int_output_dir != ""
+
+ def _calc_val_bounds(self, discount):
+ r_min = self.world.env.get_reward_min(self.id)
+ r_max = self.world.env.get_reward_max(self.id)
+ assert (r_min <= r_max)
+
+ val_min = r_min / (1.0 - discount)
+ val_max = r_max / (1.0 - discount)
+ return val_min, val_max
+
+ def _calc_val_offset_scale(self, discount):
+ val_min, val_max = self._calc_val_bounds(discount)
+ val_offset = 0
+ val_scale = 1
+
+ if (np.isfinite(val_min) and np.isfinite(val_max)):
+ val_offset = -0.5 * (val_max + val_min)
+ val_scale = 2 / (val_max - val_min)
+
+ return val_offset, val_scale
+
+ def _calc_term_vals(self, discount):
+ r_fail = self.world.env.get_reward_fail(self.id)
+ r_succ = self.world.env.get_reward_succ(self.id)
+
+ r_min = self.world.env.get_reward_min(self.id)
+ r_max = self.world.env.get_reward_max(self.id)
+ assert (r_fail <= r_max and r_fail >= r_min)
+ assert (r_succ <= r_max and r_succ >= r_min)
+ assert (not np.isinf(r_fail))
+ assert (not np.isinf(r_succ))
+
+ if (discount == 0):
+ val_fail = 0
+ val_succ = 0
+ else:
+ val_fail = r_fail / (1.0 - discount)
+ val_succ = r_succ / (1.0 - discount)
+
+ return val_fail, val_succ
+
+ def _update_iter(self, iter):
+ if (self._enable_output() and self.iter % self.output_iters == 0):
+ output_path = self._get_output_path()
+ output_dir = os.path.dirname(output_path)
+ if not os.path.exists(output_dir):
+ os.makedirs(output_dir)
+ self.save_model(output_path)
+
+ if (self._enable_int_output() and self.iter % self.int_output_iters == 0):
+ int_output_path = self._get_int_output_path()
+ int_output_dir = os.path.dirname(int_output_path)
+ if not os.path.exists(int_output_dir):
+ os.makedirs(int_output_dir)
+ self.save_model(int_output_path)
+
+ self.iter = iter
+ return
+
+ def _enable_draw(self):
+ return self.world.env.enable_draw
+
+ def _log_val(self, s, g):
+ pass
+
+ def _build_replay_buffer(self, buffer_size):
+ num_procs = MPIUtil.get_num_procs()
+ buffer_size = int(buffer_size / num_procs)
+ self.replay_buffer = ReplayBuffer(buffer_size=buffer_size)
+ self.replay_buffer_initialized = False
+ return
+
+ def _store_path(self, path):
+ path_id = self.replay_buffer.store(path)
+ valid_path = path_id != MathUtil.INVALID_IDX
+
+ if valid_path:
+ self.train_return = path.calc_return()
+
+ if self._need_normalizer_update:
+ self._record_normalizers(path)
+
+ return path_id
+
+ def _record_normalizers(self, path):
+ states = np.array(path.states)
+ self.s_norm.record(states)
+
+ if self.has_goal():
+ goals = np.array(path.goals)
+ self.g_norm.record(goals)
+
+ return
+
+ def _update_normalizers(self):
+ self.s_norm.update()
+
+ if self.has_goal():
+ self.g_norm.update()
+ return
+
+ def _train(self):
+ samples = self.replay_buffer.total_count
+ self._total_sample_count = int(MPIUtil.reduce_sum(samples))
+ end_training = False
+
+ if (self.replay_buffer_initialized):
+ if (self._valid_train_step()):
+ prev_iter = self.iter
+ iters = self._get_iters_per_update()
+ avg_train_return = MPIUtil.reduce_avg(self.train_return)
+
+ for i in range(iters):
+ curr_iter = self.iter
+ wall_time = time.time() - self.start_time
+ wall_time /= 60 * 60 # store time in hours
+
+ has_goal = self.has_goal()
+ s_mean = np.mean(self.s_norm.mean)
+ s_std = np.mean(self.s_norm.std)
+ g_mean = np.mean(self.g_norm.mean) if has_goal else 0
+ g_std = np.mean(self.g_norm.std) if has_goal else 0
+
+ self.logger.log_tabular("Iteration", self.iter)
+ self.logger.log_tabular("Wall_Time", wall_time)
+ self.logger.log_tabular("Samples", self._total_sample_count)
+ self.logger.log_tabular("Train_Return", avg_train_return)
+ self.logger.log_tabular("Test_Return", self.avg_test_return)
+ self.logger.log_tabular("State_Mean", s_mean)
+ self.logger.log_tabular("State_Std", s_std)
+ self.logger.log_tabular("Goal_Mean", g_mean)
+ self.logger.log_tabular("Goal_Std", g_std)
+ self._log_exp_params()
+
+ self._update_iter(self.iter + 1)
+ self._train_step()
+
+ Logger.print2("Agent " + str(self.id))
+ self.logger.print_tabular()
+ Logger.print2("")
+
+ if (self._enable_output() and curr_iter % self.int_output_iters == 0):
+ self.logger.dump_tabular()
+
+ if (prev_iter // self.int_output_iters != self.iter // self.int_output_iters):
+ end_training = self.enable_testing()
+
+ else:
+
+ Logger.print2("Agent " + str(self.id))
+ Logger.print2("Samples: " + str(self._total_sample_count))
+ Logger.print2("")
+
+ if (self._total_sample_count >= self.init_samples):
+ self.replay_buffer_initialized = True
+ end_training = self.enable_testing()
+
+ if self._need_normalizer_update:
+ self._update_normalizers()
+ self._need_normalizer_update = self.normalizer_samples > self._total_sample_count
+
+ if end_training:
+ self._init_mode_train_end()
+
+ return
+
+ def _get_iters_per_update(self):
+ return MPIUtil.get_num_procs() * self.iters_per_update
+
+ def _valid_train_step(self):
+ return True
+
+ def _log_exp_params(self):
+ self.logger.log_tabular("Exp_Rate", self.exp_params_curr.rate)
+ self.logger.log_tabular("Exp_Noise", self.exp_params_curr.noise)
+ self.logger.log_tabular("Exp_Temp", self.exp_params_curr.temp)
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_util.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_util.py
index 12c682a19..71132e15d 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_util.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_util.py
@@ -1,18 +1,19 @@
import numpy as np
+
def compute_return(rewards, gamma, td_lambda, val_t):
- # computes td-lambda return of path
- path_len = len(rewards)
- assert len(val_t) == path_len + 1
+ # computes td-lambda return of path
+ path_len = len(rewards)
+ assert len(val_t) == path_len + 1
+
+ return_t = np.zeros(path_len)
+ last_val = rewards[-1] + gamma * val_t[-1]
+ return_t[-1] = last_val
- return_t = np.zeros(path_len)
- last_val = rewards[-1] + gamma * val_t[-1]
- return_t[-1] = last_val
+ for i in reversed(range(0, path_len - 1)):
+ curr_r = rewards[i]
+ next_ret = return_t[i + 1]
+ curr_val = curr_r + gamma * ((1.0 - td_lambda) * val_t[i + 1] + td_lambda * next_ret)
+ return_t[i] = curr_val
- for i in reversed(range(0, path_len - 1)):
- curr_r = rewards[i]
- next_ret = return_t[i + 1]
- curr_val = curr_r + gamma * ((1.0 - td_lambda) * val_t[i + 1] + td_lambda * next_ret)
- return_t[i] = curr_val
-
- return return_t \ No newline at end of file
+ return return_t
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_world.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_world.py
index a1761bc30..32841eade 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_world.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/rl_world.py
@@ -5,139 +5,140 @@ from pybullet_envs.deep_mimic.learning.rl_agent import RLAgent
from pybullet_utils.logger import Logger
import pybullet_data
+
class RLWorld(object):
- def __init__(self, env, arg_parser):
- TFUtil.disable_gpu()
-
- self.env = env
- self.arg_parser = arg_parser
- self._enable_training = True
- self.train_agents = []
- self.parse_args(arg_parser)
-
- self.build_agents()
-
- return
-
- def get_enable_training(self):
- return self._enable_training
-
- def set_enable_training(self, enable):
- self._enable_training = enable
- for i in range(len(self.agents)):
- curr_agent = self.agents[i]
- if curr_agent is not None:
- enable_curr_train = self.train_agents[i] if (len(self.train_agents) > 0) else True
- curr_agent.enable_training = self.enable_training and enable_curr_train
-
- if (self._enable_training):
- self.env.set_mode(RLAgent.Mode.TRAIN)
- else:
- self.env.set_mode(RLAgent.Mode.TEST)
-
- return
-
- enable_training = property(get_enable_training, set_enable_training)
-
- def parse_args(self, arg_parser):
- self.train_agents = self.arg_parser.parse_bools('train_agents')
- num_agents = self.env.get_num_agents()
- assert(len(self.train_agents) == num_agents or len(self.train_agents) == 0)
-
- return
-
- def shutdown(self):
- self.env.shutdown()
- return
-
- def build_agents(self):
- num_agents = self.env.get_num_agents()
- print("num_agents=",num_agents)
- self.agents = []
-
- Logger.print2('')
- Logger.print2('Num Agents: {:d}'.format(num_agents))
-
- agent_files = self.arg_parser.parse_strings('agent_files')
- print("len(agent_files)=",len(agent_files))
- assert(len(agent_files) == num_agents or len(agent_files) == 0)
-
- model_files = self.arg_parser.parse_strings('model_files')
- assert(len(model_files) == num_agents or len(model_files) == 0)
-
- output_path = self.arg_parser.parse_string('output_path')
- int_output_path = self.arg_parser.parse_string('int_output_path')
-
- for i in range(num_agents):
- curr_file = agent_files[i]
- curr_agent = self._build_agent(i, curr_file)
-
- if curr_agent is not None:
- curr_agent.output_dir = output_path
- curr_agent.int_output_dir = int_output_path
- Logger.print2(str(curr_agent))
-
- if (len(model_files) > 0):
- curr_model_file = model_files[i]
- if curr_model_file != 'none':
- curr_agent.load_model(pybullet_data.getDataPath()+"/"+curr_model_file)
-
- self.agents.append(curr_agent)
- Logger.print2('')
-
- self.set_enable_training(self.enable_training)
-
- return
-
- def update(self, timestep):
- #print("world update!\n")
- self._update_agents(timestep)
- self._update_env(timestep)
- return
-
- def reset(self):
- self._reset_agents()
- self._reset_env()
- return
-
- def end_episode(self):
- self._end_episode_agents();
- return
-
- def _update_env(self, timestep):
- self.env.update(timestep)
- return
-
- def _update_agents(self, timestep):
- #print("len(agents)=",len(self.agents))
- for agent in self.agents:
- if (agent is not None):
- agent.update(timestep)
- return
-
- def _reset_env(self):
- self.env.reset()
- return
-
- def _reset_agents(self):
- for agent in self.agents:
- if (agent != None):
- agent.reset()
- return
-
- def _end_episode_agents(self):
- for agent in self.agents:
- if (agent != None):
- agent.end_episode()
- return
-
- def _build_agent(self, id, agent_file):
- Logger.print2('Agent {:d}: {}'.format(id, agent_file))
- if (agent_file == 'none'):
- agent = None
- else:
- agent = AgentBuilder.build_agent(self, id, agent_file)
- assert (agent != None), 'Failed to build agent {:d} from: {}'.format(id, agent_file)
-
- return agent
-
+
+ def __init__(self, env, arg_parser):
+ TFUtil.disable_gpu()
+
+ self.env = env
+ self.arg_parser = arg_parser
+ self._enable_training = True
+ self.train_agents = []
+ self.parse_args(arg_parser)
+
+ self.build_agents()
+
+ return
+
+ def get_enable_training(self):
+ return self._enable_training
+
+ def set_enable_training(self, enable):
+ self._enable_training = enable
+ for i in range(len(self.agents)):
+ curr_agent = self.agents[i]
+ if curr_agent is not None:
+ enable_curr_train = self.train_agents[i] if (len(self.train_agents) > 0) else True
+ curr_agent.enable_training = self.enable_training and enable_curr_train
+
+ if (self._enable_training):
+ self.env.set_mode(RLAgent.Mode.TRAIN)
+ else:
+ self.env.set_mode(RLAgent.Mode.TEST)
+
+ return
+
+ enable_training = property(get_enable_training, set_enable_training)
+
+ def parse_args(self, arg_parser):
+ self.train_agents = self.arg_parser.parse_bools('train_agents')
+ num_agents = self.env.get_num_agents()
+ assert (len(self.train_agents) == num_agents or len(self.train_agents) == 0)
+
+ return
+
+ def shutdown(self):
+ self.env.shutdown()
+ return
+
+ def build_agents(self):
+ num_agents = self.env.get_num_agents()
+ print("num_agents=", num_agents)
+ self.agents = []
+
+ Logger.print2('')
+ Logger.print2('Num Agents: {:d}'.format(num_agents))
+
+ agent_files = self.arg_parser.parse_strings('agent_files')
+ print("len(agent_files)=", len(agent_files))
+ assert (len(agent_files) == num_agents or len(agent_files) == 0)
+
+ model_files = self.arg_parser.parse_strings('model_files')
+ assert (len(model_files) == num_agents or len(model_files) == 0)
+
+ output_path = self.arg_parser.parse_string('output_path')
+ int_output_path = self.arg_parser.parse_string('int_output_path')
+
+ for i in range(num_agents):
+ curr_file = agent_files[i]
+ curr_agent = self._build_agent(i, curr_file)
+
+ if curr_agent is not None:
+ curr_agent.output_dir = output_path
+ curr_agent.int_output_dir = int_output_path
+ Logger.print2(str(curr_agent))
+
+ if (len(model_files) > 0):
+ curr_model_file = model_files[i]
+ if curr_model_file != 'none':
+ curr_agent.load_model(pybullet_data.getDataPath() + "/" + curr_model_file)
+
+ self.agents.append(curr_agent)
+ Logger.print2('')
+
+ self.set_enable_training(self.enable_training)
+
+ return
+
+ def update(self, timestep):
+ #print("world update!\n")
+ self._update_agents(timestep)
+ self._update_env(timestep)
+ return
+
+ def reset(self):
+ self._reset_agents()
+ self._reset_env()
+ return
+
+ def end_episode(self):
+ self._end_episode_agents()
+ return
+
+ def _update_env(self, timestep):
+ self.env.update(timestep)
+ return
+
+ def _update_agents(self, timestep):
+ #print("len(agents)=",len(self.agents))
+ for agent in self.agents:
+ if (agent is not None):
+ agent.update(timestep)
+ return
+
+ def _reset_env(self):
+ self.env.reset()
+ return
+
+ def _reset_agents(self):
+ for agent in self.agents:
+ if (agent != None):
+ agent.reset()
+ return
+
+ def _end_episode_agents(self):
+ for agent in self.agents:
+ if (agent != None):
+ agent.end_episode()
+ return
+
+ def _build_agent(self, id, agent_file):
+ Logger.print2('Agent {:d}: {}'.format(id, agent_file))
+ if (agent_file == 'none'):
+ agent = None
+ else:
+ agent = AgentBuilder.build_agent(self, id, agent_file)
+ assert (agent != None), 'Failed to build agent {:d} from: {}'.format(id, agent_file)
+
+ return agent
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/mpi_solver.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/mpi_solver.py
index f2d18051c..0077f4b11 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/mpi_solver.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/mpi_solver.py
@@ -8,96 +8,97 @@ from pybullet_utils.logger import Logger
from pybullet_envs.deep_mimic.learning.solvers.solver import Solver
+
class MPISolver(Solver):
- CHECK_SYNC_ITERS = 1000
-
- def __init__(self, sess, optimizer, vars):
- super().__init__(vars)
- self.sess = sess
- self.optimizer = optimizer
- self._build_grad_feed(vars)
- self._update = optimizer.apply_gradients(zip(self._grad_tf_list, self.vars))
- self._set_flat_vars = TFUtil.SetFromFlat(sess, self.vars)
- self._get_flat_vars = TFUtil.GetFlat(sess, self.vars)
-
- self.iter = 0
- grad_dim = self._calc_grad_dim()
- self._flat_grad = np.zeros(grad_dim, dtype=np.float32)
- self._global_flat_grad = np.zeros(grad_dim, dtype=np.float32)
-
- return
-
- def get_stepsize(self):
- return self.optimizer._learning_rate_tensor.eval()
-
- def update(self, grads=None, grad_scale=1.0):
- if grads is not None:
- self._flat_grad = MathUtil.flatten(grads)
- else:
- self._flat_grad.fill(0)
- return self.update_flatgrad(self._flat_grad, grad_scale)
-
- def update_flatgrad(self, flat_grad, grad_scale=1.0):
- if self.iter % self.CHECK_SYNC_ITERS == 0:
- assert self.check_synced(), Logger.print2('Network parameters desynchronized')
-
- if grad_scale != 1.0:
- flat_grad *= grad_scale
-
- MPI.COMM_WORLD.Allreduce(flat_grad, self._global_flat_grad, op=MPI.SUM)
- self._global_flat_grad /= MPIUtil.get_num_procs()
-
- self._load_flat_grad(self._global_flat_grad)
- self.sess.run([self._update], self._grad_feed)
- self.iter += 1
-
- return
-
- def sync(self):
- vars = self._get_flat_vars()
- MPIUtil.bcast(vars)
- self._set_flat_vars(vars)
- return
-
- def check_synced(self):
- synced = True
- if self._is_root():
- vars = self._get_flat_vars()
- MPIUtil.bcast(vars)
- else:
- vars_local = self._get_flat_vars()
- vars_root = np.empty_like(vars_local)
- MPIUtil.bcast(vars_root)
- synced = (vars_local == vars_root).all()
- return synced
-
- def _is_root(self):
- return MPIUtil.is_root_proc()
-
- def _build_grad_feed(self, vars):
- self._grad_tf_list = []
- self._grad_buffers = []
- for v in self.vars:
- shape = v.get_shape()
- grad = np.zeros(shape)
- grad_tf = tf.placeholder(tf.float32, shape=shape)
- self._grad_buffers.append(grad)
- self._grad_tf_list.append(grad_tf)
-
- self._grad_feed = dict({g_tf: g for g_tf, g in zip(self._grad_tf_list, self._grad_buffers)})
-
- return
-
- def _calc_grad_dim(self):
- grad_dim = 0
- for grad in self._grad_buffers:
- grad_dim += grad.size
- return grad_dim
-
- def _load_flat_grad(self, flat_grad):
- start = 0
- for g in self._grad_buffers:
- size = g.size
- np.copyto(g, np.reshape(flat_grad[start:start + size], g.shape))
- start += size
- return \ No newline at end of file
+ CHECK_SYNC_ITERS = 1000
+
+ def __init__(self, sess, optimizer, vars):
+ super().__init__(vars)
+ self.sess = sess
+ self.optimizer = optimizer
+ self._build_grad_feed(vars)
+ self._update = optimizer.apply_gradients(zip(self._grad_tf_list, self.vars))
+ self._set_flat_vars = TFUtil.SetFromFlat(sess, self.vars)
+ self._get_flat_vars = TFUtil.GetFlat(sess, self.vars)
+
+ self.iter = 0
+ grad_dim = self._calc_grad_dim()
+ self._flat_grad = np.zeros(grad_dim, dtype=np.float32)
+ self._global_flat_grad = np.zeros(grad_dim, dtype=np.float32)
+
+ return
+
+ def get_stepsize(self):
+ return self.optimizer._learning_rate_tensor.eval()
+
+ def update(self, grads=None, grad_scale=1.0):
+ if grads is not None:
+ self._flat_grad = MathUtil.flatten(grads)
+ else:
+ self._flat_grad.fill(0)
+ return self.update_flatgrad(self._flat_grad, grad_scale)
+
+ def update_flatgrad(self, flat_grad, grad_scale=1.0):
+ if self.iter % self.CHECK_SYNC_ITERS == 0:
+ assert self.check_synced(), Logger.print2('Network parameters desynchronized')
+
+ if grad_scale != 1.0:
+ flat_grad *= grad_scale
+
+ MPI.COMM_WORLD.Allreduce(flat_grad, self._global_flat_grad, op=MPI.SUM)
+ self._global_flat_grad /= MPIUtil.get_num_procs()
+
+ self._load_flat_grad(self._global_flat_grad)
+ self.sess.run([self._update], self._grad_feed)
+ self.iter += 1
+
+ return
+
+ def sync(self):
+ vars = self._get_flat_vars()
+ MPIUtil.bcast(vars)
+ self._set_flat_vars(vars)
+ return
+
+ def check_synced(self):
+ synced = True
+ if self._is_root():
+ vars = self._get_flat_vars()
+ MPIUtil.bcast(vars)
+ else:
+ vars_local = self._get_flat_vars()
+ vars_root = np.empty_like(vars_local)
+ MPIUtil.bcast(vars_root)
+ synced = (vars_local == vars_root).all()
+ return synced
+
+ def _is_root(self):
+ return MPIUtil.is_root_proc()
+
+ def _build_grad_feed(self, vars):
+ self._grad_tf_list = []
+ self._grad_buffers = []
+ for v in self.vars:
+ shape = v.get_shape()
+ grad = np.zeros(shape)
+ grad_tf = tf.placeholder(tf.float32, shape=shape)
+ self._grad_buffers.append(grad)
+ self._grad_tf_list.append(grad_tf)
+
+ self._grad_feed = dict({g_tf: g for g_tf, g in zip(self._grad_tf_list, self._grad_buffers)})
+
+ return
+
+ def _calc_grad_dim(self):
+ grad_dim = 0
+ for grad in self._grad_buffers:
+ grad_dim += grad.size
+ return grad_dim
+
+ def _load_flat_grad(self, flat_grad):
+ start = 0
+ for g in self._grad_buffers:
+ size = g.size
+ np.copyto(g, np.reshape(flat_grad[start:start + size], g.shape))
+ start += size
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/solver.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/solver.py
index cd2765272..3491b40ed 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/solver.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/solvers/solver.py
@@ -1,15 +1,17 @@
from abc import abstractmethod
import sys, abc
if sys.version_info >= (3, 4):
- ABC = abc.ABC
+ ABC = abc.ABC
else:
- ABC = abc.ABCMeta('ABC', (), {})
+ ABC = abc.ABCMeta('ABC', (), {})
+
class Solver(ABC):
- def __init__(self, vars):
- self.vars = vars
- return
- @abstractmethod
- def update(self, grads):
- pass
+ def __init__(self, vars):
+ self.vars = vars
+ return
+
+ @abstractmethod
+ def update(self, grads):
+ pass
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_agent.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_agent.py
index 95d707140..1770e5329 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_agent.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_agent.py
@@ -6,144 +6,148 @@ from pybullet_envs.deep_mimic.learning.rl_agent import RLAgent
from pybullet_utils.logger import Logger
from pybullet_envs.deep_mimic.learning.tf_normalizer import TFNormalizer
+
class TFAgent(RLAgent):
- RESOURCE_SCOPE = 'resource'
- SOLVER_SCOPE = 'solvers'
-
- def __init__(self, world, id, json_data):
- self.tf_scope = 'agent'
- self.graph = tf.Graph()
- self.sess = tf.Session(graph=self.graph)
-
- super().__init__(world, id, json_data)
- self._build_graph(json_data)
- self._init_normalizers()
- return
-
- def __del__(self):
- self.sess.close()
- return
-
- def save_model(self, out_path):
- with self.sess.as_default(), self.graph.as_default():
- try:
- save_path = self.saver.save(self.sess, out_path, write_meta_graph=False, write_state=False)
- Logger.print2('Model saved to: ' + save_path)
- except:
- Logger.print2("Failed to save model to: " + save_path)
- return
-
- def load_model(self, in_path):
- with self.sess.as_default(), self.graph.as_default():
- self.saver.restore(self.sess, in_path)
- self._load_normalizers()
- Logger.print2('Model loaded from: ' + in_path)
- return
-
- def _get_output_path(self):
- assert(self.output_dir != '')
- file_path = self.output_dir + '/agent' + str(self.id) + '_model.ckpt'
- return file_path
-
- def _get_int_output_path(self):
- assert(self.int_output_dir != '')
- file_path = self.int_output_dir + ('/agent{:d}_models/agent{:d}_int_model_{:010d}.ckpt').format(self.id, self.id, self.iter)
- return file_path
-
- def _build_graph(self, json_data):
- with self.sess.as_default(), self.graph.as_default():
- with tf.variable_scope(self.tf_scope):
- self._build_nets(json_data)
-
- with tf.variable_scope(self.SOLVER_SCOPE):
- self._build_losses(json_data)
- self._build_solvers(json_data)
-
- self._initialize_vars()
- self._build_saver()
- return
-
- def _init_normalizers(self):
- with self.sess.as_default(), self.graph.as_default():
- # update normalizers to sync the tensorflow tensors
- self.s_norm.update()
- self.g_norm.update()
- self.a_norm.update()
- return
-
- @abstractmethod
- def _build_nets(self, json_data):
- pass
-
- @abstractmethod
- def _build_losses(self, json_data):
- pass
-
- @abstractmethod
- def _build_solvers(self, json_data):
- pass
-
- def _tf_vars(self, scope=''):
- with self.sess.as_default(), self.graph.as_default():
- res = tf.get_collection(tf.GraphKeys.TRAINABLE_VARIABLES, scope=self.tf_scope + '/' + scope)
- assert len(res) > 0
- return res
-
- def _build_normalizers(self):
- with self.sess.as_default(), self.graph.as_default(), tf.variable_scope(self.tf_scope):
- with tf.variable_scope(self.RESOURCE_SCOPE):
- self.s_norm = TFNormalizer(self.sess, 's_norm', self.get_state_size(), self.world.env.build_state_norm_groups(self.id))
- state_offset = -self.world.env.build_state_offset(self.id)
- print("state_offset=",state_offset)
- state_scale = 1 / self.world.env.build_state_scale(self.id)
- print("state_scale=",state_scale)
- self.s_norm.set_mean_std(-self.world.env.build_state_offset(self.id),
- 1 / self.world.env.build_state_scale(self.id))
-
- self.g_norm = TFNormalizer(self.sess, 'g_norm', self.get_goal_size(), self.world.env.build_goal_norm_groups(self.id))
- self.g_norm.set_mean_std(-self.world.env.build_goal_offset(self.id),
- 1 / self.world.env.build_goal_scale(self.id))
-
- self.a_norm = TFNormalizer(self.sess, 'a_norm', self.get_action_size())
- self.a_norm.set_mean_std(-self.world.env.build_action_offset(self.id),
- 1 / self.world.env.build_action_scale(self.id))
- return
-
- def _load_normalizers(self):
- self.s_norm.load()
- self.g_norm.load()
- self.a_norm.load()
- return
-
- def _update_normalizers(self):
- with self.sess.as_default(), self.graph.as_default():
- super()._update_normalizers()
- return
-
- def _initialize_vars(self):
- self.sess.run(tf.global_variables_initializer())
- return
-
- def _build_saver(self):
- vars = self._get_saver_vars()
- self.saver = tf.train.Saver(vars, max_to_keep=0)
- return
-
- def _get_saver_vars(self):
- with self.sess.as_default(), self.graph.as_default():
- vars = tf.get_collection(tf.GraphKeys.GLOBAL_VARIABLES, scope=self.tf_scope)
- vars = [v for v in vars if '/' + self.SOLVER_SCOPE + '/' not in v.name]
- #vars = [v for v in vars if '/target/' not in v.name]
- assert len(vars) > 0
- return vars
-
- def _weight_decay_loss(self, scope):
- vars = self._tf_vars(scope)
- vars_no_bias = [v for v in vars if 'bias' not in v.name]
- loss = tf.add_n([tf.nn.l2_loss(v) for v in vars_no_bias])
- return loss
-
- def _train(self):
- with self.sess.as_default(), self.graph.as_default():
- super()._train()
- return \ No newline at end of file
+ RESOURCE_SCOPE = 'resource'
+ SOLVER_SCOPE = 'solvers'
+
+ def __init__(self, world, id, json_data):
+ self.tf_scope = 'agent'
+ self.graph = tf.Graph()
+ self.sess = tf.Session(graph=self.graph)
+
+ super().__init__(world, id, json_data)
+ self._build_graph(json_data)
+ self._init_normalizers()
+ return
+
+ def __del__(self):
+ self.sess.close()
+ return
+
+ def save_model(self, out_path):
+ with self.sess.as_default(), self.graph.as_default():
+ try:
+ save_path = self.saver.save(self.sess, out_path, write_meta_graph=False, write_state=False)
+ Logger.print2('Model saved to: ' + save_path)
+ except:
+ Logger.print2("Failed to save model to: " + save_path)
+ return
+
+ def load_model(self, in_path):
+ with self.sess.as_default(), self.graph.as_default():
+ self.saver.restore(self.sess, in_path)
+ self._load_normalizers()
+ Logger.print2('Model loaded from: ' + in_path)
+ return
+
+ def _get_output_path(self):
+ assert (self.output_dir != '')
+ file_path = self.output_dir + '/agent' + str(self.id) + '_model.ckpt'
+ return file_path
+
+ def _get_int_output_path(self):
+ assert (self.int_output_dir != '')
+ file_path = self.int_output_dir + (
+ '/agent{:d}_models/agent{:d}_int_model_{:010d}.ckpt').format(self.id, self.id, self.iter)
+ return file_path
+
+ def _build_graph(self, json_data):
+ with self.sess.as_default(), self.graph.as_default():
+ with tf.variable_scope(self.tf_scope):
+ self._build_nets(json_data)
+
+ with tf.variable_scope(self.SOLVER_SCOPE):
+ self._build_losses(json_data)
+ self._build_solvers(json_data)
+
+ self._initialize_vars()
+ self._build_saver()
+ return
+
+ def _init_normalizers(self):
+ with self.sess.as_default(), self.graph.as_default():
+ # update normalizers to sync the tensorflow tensors
+ self.s_norm.update()
+ self.g_norm.update()
+ self.a_norm.update()
+ return
+
+ @abstractmethod
+ def _build_nets(self, json_data):
+ pass
+
+ @abstractmethod
+ def _build_losses(self, json_data):
+ pass
+
+ @abstractmethod
+ def _build_solvers(self, json_data):
+ pass
+
+ def _tf_vars(self, scope=''):
+ with self.sess.as_default(), self.graph.as_default():
+ res = tf.get_collection(tf.GraphKeys.TRAINABLE_VARIABLES, scope=self.tf_scope + '/' + scope)
+ assert len(res) > 0
+ return res
+
+ def _build_normalizers(self):
+ with self.sess.as_default(), self.graph.as_default(), tf.variable_scope(self.tf_scope):
+ with tf.variable_scope(self.RESOURCE_SCOPE):
+ self.s_norm = TFNormalizer(self.sess, 's_norm', self.get_state_size(),
+ self.world.env.build_state_norm_groups(self.id))
+ state_offset = -self.world.env.build_state_offset(self.id)
+ print("state_offset=", state_offset)
+ state_scale = 1 / self.world.env.build_state_scale(self.id)
+ print("state_scale=", state_scale)
+ self.s_norm.set_mean_std(-self.world.env.build_state_offset(self.id),
+ 1 / self.world.env.build_state_scale(self.id))
+
+ self.g_norm = TFNormalizer(self.sess, 'g_norm', self.get_goal_size(),
+ self.world.env.build_goal_norm_groups(self.id))
+ self.g_norm.set_mean_std(-self.world.env.build_goal_offset(self.id),
+ 1 / self.world.env.build_goal_scale(self.id))
+
+ self.a_norm = TFNormalizer(self.sess, 'a_norm', self.get_action_size())
+ self.a_norm.set_mean_std(-self.world.env.build_action_offset(self.id),
+ 1 / self.world.env.build_action_scale(self.id))
+ return
+
+ def _load_normalizers(self):
+ self.s_norm.load()
+ self.g_norm.load()
+ self.a_norm.load()
+ return
+
+ def _update_normalizers(self):
+ with self.sess.as_default(), self.graph.as_default():
+ super()._update_normalizers()
+ return
+
+ def _initialize_vars(self):
+ self.sess.run(tf.global_variables_initializer())
+ return
+
+ def _build_saver(self):
+ vars = self._get_saver_vars()
+ self.saver = tf.train.Saver(vars, max_to_keep=0)
+ return
+
+ def _get_saver_vars(self):
+ with self.sess.as_default(), self.graph.as_default():
+ vars = tf.get_collection(tf.GraphKeys.GLOBAL_VARIABLES, scope=self.tf_scope)
+ vars = [v for v in vars if '/' + self.SOLVER_SCOPE + '/' not in v.name]
+ #vars = [v for v in vars if '/target/' not in v.name]
+ assert len(vars) > 0
+ return vars
+
+ def _weight_decay_loss(self, scope):
+ vars = self._tf_vars(scope)
+ vars_no_bias = [v for v in vars if 'bias' not in v.name]
+ loss = tf.add_n([tf.nn.l2_loss(v) for v in vars_no_bias])
+ return loss
+
+ def _train(self):
+ with self.sess.as_default(), self.graph.as_default():
+ super()._train()
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_normalizer.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_normalizer.py
index 82f5745f0..907eec85b 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_normalizer.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_normalizer.py
@@ -3,65 +3,72 @@ import copy
import tensorflow as tf
from pybullet_envs.deep_mimic.learning.normalizer import Normalizer
+
class TFNormalizer(Normalizer):
- def __init__(self, sess, scope, size, groups_ids=None, eps=0.02, clip=np.inf):
- self.sess = sess
- self.scope = scope
- super().__init__(size, groups_ids, eps, clip)
+ def __init__(self, sess, scope, size, groups_ids=None, eps=0.02, clip=np.inf):
+ self.sess = sess
+ self.scope = scope
+ super().__init__(size, groups_ids, eps, clip)
+
+ with tf.variable_scope(self.scope):
+ self._build_resource_tf()
+ return
+
+ # initialze count when loading saved values so that things don't change to quickly during updates
+ def load(self):
+ self.count = self.count_tf.eval()[0]
+ self.mean = self.mean_tf.eval()
+ self.std = self.std_tf.eval()
+ self.mean_sq = self.calc_mean_sq(self.mean, self.std)
+ return
+
+ def update(self):
+ super().update()
+ self._update_resource_tf()
+ return
- with tf.variable_scope(self.scope):
- self._build_resource_tf()
- return
+ def set_mean_std(self, mean, std):
+ super().set_mean_std(mean, std)
+ self._update_resource_tf()
+ return
- # initialze count when loading saved values so that things don't change to quickly during updates
- def load(self):
- self.count = self.count_tf.eval()[0]
- self.mean = self.mean_tf.eval()
- self.std = self.std_tf.eval()
- self.mean_sq = self.calc_mean_sq(self.mean, self.std)
- return
+ def normalize_tf(self, x):
+ norm_x = (x - self.mean_tf) / self.std_tf
+ norm_x = tf.clip_by_value(norm_x, -self.clip, self.clip)
+ return norm_x
- def update(self):
- super().update()
- self._update_resource_tf()
- return
+ def unnormalize_tf(self, norm_x):
+ x = norm_x * self.std_tf + self.mean_tf
+ return x
- def set_mean_std(self, mean, std):
- super().set_mean_std(mean, std)
- self._update_resource_tf()
- return
+ def _build_resource_tf(self):
+ self.count_tf = tf.get_variable(dtype=tf.int32,
+ name='count',
+ initializer=np.array([self.count], dtype=np.int32),
+ trainable=False)
+ self.mean_tf = tf.get_variable(dtype=tf.float32,
+ name='mean',
+ initializer=self.mean.astype(np.float32),
+ trainable=False)
+ self.std_tf = tf.get_variable(dtype=tf.float32,
+ name='std',
+ initializer=self.std.astype(np.float32),
+ trainable=False)
- def normalize_tf(self, x):
- norm_x = (x - self.mean_tf) / self.std_tf
- norm_x = tf.clip_by_value(norm_x, -self.clip, self.clip)
- return norm_x
+ self.count_ph = tf.get_variable(dtype=tf.int32, name='count_ph', shape=[1])
+ self.mean_ph = tf.get_variable(dtype=tf.float32, name='mean_ph', shape=self.mean.shape)
+ self.std_ph = tf.get_variable(dtype=tf.float32, name='std_ph', shape=self.std.shape)
- def unnormalize_tf(self, norm_x):
- x = norm_x * self.std_tf + self.mean_tf
- return x
-
- def _build_resource_tf(self):
- self.count_tf = tf.get_variable(dtype=tf.int32, name='count', initializer=np.array([self.count], dtype=np.int32), trainable=False)
- self.mean_tf = tf.get_variable(dtype=tf.float32, name='mean', initializer=self.mean.astype(np.float32), trainable=False)
- self.std_tf = tf.get_variable(dtype=tf.float32, name='std', initializer=self.std.astype(np.float32), trainable=False)
-
- self.count_ph = tf.get_variable(dtype=tf.int32, name='count_ph', shape=[1])
- self.mean_ph = tf.get_variable(dtype=tf.float32, name='mean_ph', shape=self.mean.shape)
- self.std_ph = tf.get_variable(dtype=tf.float32, name='std_ph', shape=self.std.shape)
-
- self._update_op = tf.group(
- self.count_tf.assign(self.count_ph),
- self.mean_tf.assign(self.mean_ph),
- self.std_tf.assign(self.std_ph)
- )
- return
+ self._update_op = tf.group(self.count_tf.assign(self.count_ph),
+ self.mean_tf.assign(self.mean_ph), self.std_tf.assign(self.std_ph))
+ return
- def _update_resource_tf(self):
- feed = {
- self.count_ph: np.array([self.count], dtype=np.int32),
- self.mean_ph: self.mean,
- self.std_ph: self.std
- }
- self.sess.run(self._update_op, feed_dict=feed)
- return
+ def _update_resource_tf(self):
+ feed = {
+ self.count_ph: np.array([self.count], dtype=np.int32),
+ self.mean_ph: self.mean,
+ self.std_ph: self.std
+ }
+ self.sess.run(self._update_op, feed_dict=feed)
+ return
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_util.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_util.py
index b0a315bc3..043d8dcd9 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_util.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/learning/tf_util.py
@@ -4,101 +4,116 @@ import os
xavier_initializer = tf.contrib.layers.xavier_initializer()
+
def disable_gpu():
- os.environ["CUDA_VISIBLE_DEVICES"] = '-1'
- return
+ os.environ["CUDA_VISIBLE_DEVICES"] = '-1'
+ return
+
def var_shape(x):
- out = [k.value for k in x.get_shape()]
- assert all(isinstance(a, int) for a in out), "shape function assumes that shape is fully known"
- return out
+ out = [k.value for k in x.get_shape()]
+ assert all(isinstance(a, int) for a in out), "shape function assumes that shape is fully known"
+ return out
+
def intprod(x):
- return int(np.prod(x))
+ return int(np.prod(x))
+
def numel(x):
- n = intprod(var_shape(x))
- return n
+ n = intprod(var_shape(x))
+ return n
+
def flat_grad(loss, var_list, grad_ys=None):
- grads = tf.gradients(loss, var_list, grad_ys)
- return tf.concat([tf.reshape(grad, [numel(v)]) for (v, grad) in zip(var_list, grads)], axis=0)
-
-def fc_net(input, layers_sizes, activation, reuse=None, flatten=False): # build fully connected network
- curr_tf = input
- for i, size in enumerate(layers_sizes):
- with tf.variable_scope(str(i), reuse=reuse):
- curr_tf = tf.layers.dense(inputs=curr_tf,
- units=size,
- kernel_initializer=xavier_initializer,
- activation = activation if i < len(layers_sizes)-1 else None)
- if flatten:
- assert layers_sizes[-1] == 1
- curr_tf = tf.reshape(curr_tf, [-1])
-
- return curr_tf
+ grads = tf.gradients(loss, var_list, grad_ys)
+ return tf.concat([tf.reshape(grad, [numel(v)]) for (v, grad) in zip(var_list, grads)], axis=0)
+
+
+def fc_net(input, layers_sizes, activation, reuse=None,
+ flatten=False): # build fully connected network
+ curr_tf = input
+ for i, size in enumerate(layers_sizes):
+ with tf.variable_scope(str(i), reuse=reuse):
+ curr_tf = tf.layers.dense(inputs=curr_tf,
+ units=size,
+ kernel_initializer=xavier_initializer,
+ activation=activation if i < len(layers_sizes) - 1 else None)
+ if flatten:
+ assert layers_sizes[-1] == 1
+ curr_tf = tf.reshape(curr_tf, [-1])
+
+ return curr_tf
+
def copy(sess, src, dst):
- assert len(src) == len(dst)
- sess.run(list(map(lambda v: v[1].assign(v[0]), zip(src, dst))))
- return
+ assert len(src) == len(dst)
+ sess.run(list(map(lambda v: v[1].assign(v[0]), zip(src, dst))))
+ return
+
def flat_grad(loss, var_list):
- grads = tf.gradients(loss, var_list)
- return tf.concat(axis=0, values=[tf.reshape(grad, [numel(v)])
- for (v, grad) in zip(var_list, grads)])
+ grads = tf.gradients(loss, var_list)
+ return tf.concat(axis=0,
+ values=[tf.reshape(grad, [numel(v)]) for (v, grad) in zip(var_list, grads)])
def calc_logp_gaussian(x_tf, mean_tf, std_tf):
- dim = tf.to_float(tf.shape(x_tf)[-1])
+ dim = tf.to_float(tf.shape(x_tf)[-1])
+
+ if mean_tf is None:
+ diff_tf = x_tf
+ else:
+ diff_tf = x_tf - mean_tf
+
+ logp_tf = -0.5 * tf.reduce_sum(tf.square(diff_tf / std_tf), axis=-1)
+ logp_tf += -0.5 * dim * np.log(2 * np.pi) - tf.reduce_sum(tf.log(std_tf), axis=-1)
- if mean_tf is None:
- diff_tf = x_tf
- else:
- diff_tf = x_tf - mean_tf
+ return logp_tf
- logp_tf = -0.5 * tf.reduce_sum(tf.square(diff_tf / std_tf), axis=-1)
- logp_tf += -0.5 * dim * np.log(2 * np.pi) - tf.reduce_sum(tf.log(std_tf), axis=-1)
-
- return logp_tf
def calc_bound_loss(x_tf, bound_min, bound_max):
- # penalty for violating bounds
- violation_min = tf.minimum(x_tf - bound_min, 0)
- violation_max = tf.maximum(x_tf - bound_max, 0)
- violation = tf.reduce_sum(tf.square(violation_min), axis=-1) + tf.reduce_sum(tf.square(violation_max), axis=-1)
- loss = 0.5 * tf.reduce_mean(violation)
- return loss
+ # penalty for violating bounds
+ violation_min = tf.minimum(x_tf - bound_min, 0)
+ violation_max = tf.maximum(x_tf - bound_max, 0)
+ violation = tf.reduce_sum(tf.square(violation_min), axis=-1) + tf.reduce_sum(
+ tf.square(violation_max), axis=-1)
+ loss = 0.5 * tf.reduce_mean(violation)
+ return loss
+
class SetFromFlat(object):
- def __init__(self, sess, var_list, dtype=tf.float32):
- assigns = []
- shapes = list(map(var_shape, var_list))
- total_size = np.sum([intprod(shape) for shape in shapes])
- self.sess = sess
- self.theta = tf.placeholder(dtype,[total_size])
- start=0
- assigns = []
+ def __init__(self, sess, var_list, dtype=tf.float32):
+ assigns = []
+ shapes = list(map(var_shape, var_list))
+ total_size = np.sum([intprod(shape) for shape in shapes])
+
+ self.sess = sess
+ self.theta = tf.placeholder(dtype, [total_size])
+ start = 0
+ assigns = []
- for (shape,v) in zip(shapes,var_list):
- size = intprod(shape)
- assigns.append(tf.assign(v, tf.reshape(self.theta[start:start+size],shape)))
- start += size
+ for (shape, v) in zip(shapes, var_list):
+ size = intprod(shape)
+ assigns.append(tf.assign(v, tf.reshape(self.theta[start:start + size], shape)))
+ start += size
- self.op = tf.group(*assigns)
+ self.op = tf.group(*assigns)
- return
+ return
+
+ def __call__(self, theta):
+ self.sess.run(self.op, feed_dict={self.theta: theta})
+ return
- def __call__(self, theta):
- self.sess.run(self.op, feed_dict={self.theta:theta})
- return
class GetFlat(object):
- def __init__(self, sess, var_list):
- self.sess = sess
- self.op = tf.concat(axis=0, values=[tf.reshape(v, [numel(v)]) for v in var_list])
- return
- def __call__(self):
- return self.sess.run(self.op) \ No newline at end of file
+ def __init__(self, sess, var_list):
+ self.sess = sess
+ self.op = tf.concat(axis=0, values=[tf.reshape(v, [numel(v)]) for v in var_list])
+ return
+
+ def __call__(self):
+ return self.sess.run(self.op)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/camera.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/camera.py
index 329eb4b65..d98993b61 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/camera.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/camera.py
@@ -1,26 +1,28 @@
-import numpy as np
+import numpy as np
from quaternion import qrot, qinverse
-def normalize_screen_coordinates(X, w, h):
- assert X.shape[-1] == 2
- # Normalize so that [0, w] is mapped to [-1, 1], while preserving the aspect ratio
- return X/w*2 - [1, h/w]
+def normalize_screen_coordinates(X, w, h):
+ assert X.shape[-1] == 2
+ # Normalize so that [0, w] is mapped to [-1, 1], while preserving the aspect ratio
+ return X / w * 2 - [1, h / w]
+
def image_coordinates(X, w, h):
- assert X.shape[-1] == 2
- # Reverse camera frame normalization
- return (X + [1, h/w])*w/2
+ assert X.shape[-1] == 2
+ # Reverse camera frame normalization
+ return (X + [1, h / w]) * w / 2
+
def world_to_camera(X, R, t):
- Rt = qinverse(R)
- Q = np.tile(Rt, (*X.shape[:-1], 1))
- V = X - t
- return qrot(Q, V)
-
-def camera_to_world(X, R, t):
- Q = np.tile(R, (*X.shape[:-1], 1))
- V = X
- return qrot(Q, V) + t
+ Rt = qinverse(R)
+ Q = np.tile(Rt, (*X.shape[:-1], 1))
+ V = X - t
+ return qrot(Q, V)
+
+def camera_to_world(X, R, t):
+ Q = np.tile(R, (*X.shape[:-1], 1))
+ V = X
+ return qrot(Q, V) + t
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/deepmimic_json_generator.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/deepmimic_json_generator.py
index 23525cd72..872bac78b 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/deepmimic_json_generator.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/deepmimic_json_generator.py
@@ -3,54 +3,63 @@ from h36m_dataset import Human36mDataset
from camera import *
import numpy as np
-# In[2]:
+# In[2]:
joint_info = {
- 'joint_name':['root', 'right_hip', 'right_knee', 'right_ankle', 'left_hip', 'left_knee', 'left_ankle', 'chest', 'neck', 'nose', 'eye', 'left_shoulder', 'left_elbow', 'left_wrist', 'right_shoulder', 'right_elbow', 'right_wrist'],
- 'father':[0, 0, 1, 2, 0, 4, 5, 0, 7, 8, 9, 8, 11, 12, 8, 14, 15],
- 'side':['middle', 'right', 'right', 'right', 'left', 'left', 'left', 'middle', 'middle', 'middle', 'middle', 'left', 'left', 'left', 'right', 'right', 'right']
+ 'joint_name': [
+ 'root', 'right_hip', 'right_knee', 'right_ankle', 'left_hip', 'left_knee', 'left_ankle',
+ 'chest', 'neck', 'nose', 'eye', 'left_shoulder', 'left_elbow', 'left_wrist',
+ 'right_shoulder', 'right_elbow', 'right_wrist'
+ ],
+ 'father': [0, 0, 1, 2, 0, 4, 5, 0, 7, 8, 9, 8, 11, 12, 8, 14, 15],
+ 'side': [
+ 'middle', 'right', 'right', 'right', 'left', 'left', 'left', 'middle', 'middle', 'middle',
+ 'middle', 'left', 'left', 'left', 'right', 'right', 'right'
+ ]
}
# In[3]:
+
def init_fb_h36m_dataset(dataset_path):
- dataset = Human36mDataset(dataset_path)
- print('Preparing Facebook Human3.6M Dataset...')
- for subject in dataset.subjects():
- for action in dataset[subject].keys():
- anim = dataset[subject][action]
- positions_3d = []
- for cam in anim['cameras']:
- pos_3d = world_to_camera(anim['positions'], R=cam['orientation'], t=cam['translation'])
- pos_3d[:, 1:] -= pos_3d[:, :1] # Remove global offset, but keep trajectory in first position
- positions_3d.append(pos_3d)
- anim['positions_3d'] = positions_3d
- return dataset
+ dataset = Human36mDataset(dataset_path)
+ print('Preparing Facebook Human3.6M Dataset...')
+ for subject in dataset.subjects():
+ for action in dataset[subject].keys():
+ anim = dataset[subject][action]
+ positions_3d = []
+ for cam in anim['cameras']:
+ pos_3d = world_to_camera(anim['positions'], R=cam['orientation'], t=cam['translation'])
+ pos_3d[:, 1:] -= pos_3d[:, :
+ 1] # Remove global offset, but keep trajectory in first position
+ positions_3d.append(pos_3d)
+ anim['positions_3d'] = positions_3d
+ return dataset
+
def pose3D_from_fb_h36m(dataset, subject, action, shift):
- pose_seq = dataset[subject][action]['positions_3d'][0].copy()
- trajectory = pose_seq[:, :1]
- pose_seq[:, 1:] += trajectory
- # Invert camera transformation
- cam = dataset.cameras()[subject][0]
- pose_seq = camera_to_world(pose_seq,
- R=cam['orientation'],
- t=cam['translation'])
- x = pose_seq[:,:,0:1]
- y = pose_seq[:,:,1:2] * -1
- z = pose_seq[:,:,2:3]
- pose_seq = np.concatenate((x,z,y),axis=2)
- # plus shift
- pose_seq += np.array([[shift for i in range(pose_seq.shape[1])] for j in range(pose_seq.shape[0])])
- return pose_seq
+ pose_seq = dataset[subject][action]['positions_3d'][0].copy()
+ trajectory = pose_seq[:, :1]
+ pose_seq[:, 1:] += trajectory
+ # Invert camera transformation
+ cam = dataset.cameras()[subject][0]
+ pose_seq = camera_to_world(pose_seq, R=cam['orientation'], t=cam['translation'])
+ x = pose_seq[:, :, 0:1]
+ y = pose_seq[:, :, 1:2] * -1
+ z = pose_seq[:, :, 2:3]
+ pose_seq = np.concatenate((x, z, y), axis=2)
+ # plus shift
+ pose_seq += np.array([[shift for i in range(pose_seq.shape[1])] for j in range(pose_seq.shape[0])
+ ])
+ return pose_seq
-def rot_seq_to_deepmimic_json(rot_seq, loop, json_path):
- to_json = {"Loop": loop, "Frames":[]}
- rot_seq = np.around(rot_seq, decimals=6)
- to_json["Frames"] = rot_seq.tolist()
- # In[14]:
- to_file = json.dumps(to_json)
- file = open(json_path,"w")
- file.write(to_file)
- file.close()
+def rot_seq_to_deepmimic_json(rot_seq, loop, json_path):
+ to_json = {"Loop": loop, "Frames": []}
+ rot_seq = np.around(rot_seq, decimals=6)
+ to_json["Frames"] = rot_seq.tolist()
+ # In[14]:
+ to_file = json.dumps(to_json)
+ file = open(json_path, "w")
+ file.write(to_file)
+ file.close()
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/h36m_dataset.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/h36m_dataset.py
index bc961fbf4..9dd95f902 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/h36m_dataset.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/h36m_dataset.py
@@ -3,11 +3,13 @@ import copy
from skeleton import Skeleton
from mocap_dataset import MocapDataset
from camera import normalize_screen_coordinates, image_coordinates
-
-h36m_skeleton = Skeleton(parents=[-1, 0, 1, 2, 3, 4, 0, 6, 7, 8, 9, 0, 11, 12, 13, 14, 12,
- 16, 17, 18, 19, 20, 19, 22, 12, 24, 25, 26, 27, 28, 27, 30],
- joints_left=[6, 7, 8, 9, 10, 16, 17, 18, 19, 20, 21, 22, 23],
- joints_right=[1, 2, 3, 4, 5, 24, 25, 26, 27, 28, 29, 30, 31])
+
+h36m_skeleton = Skeleton(parents=[
+ -1, 0, 1, 2, 3, 4, 0, 6, 7, 8, 9, 0, 11, 12, 13, 14, 12, 16, 17, 18, 19, 20, 19, 22, 12, 24,
+ 25, 26, 27, 28, 27, 30
+],
+ joints_left=[6, 7, 8, 9, 10, 16, 17, 18, 19, 20, 21, 22, 23],
+ joints_right=[1, 2, 3, 4, 5, 24, 25, 26, 27, 28, 29, 30, 31])
h36m_cameras_intrinsic_params = [
{
@@ -18,7 +20,7 @@ h36m_cameras_intrinsic_params = [
'tangential_distortion': [-0.0009756988729350269, -0.00142447161488235],
'res_w': 1000,
'res_h': 1002,
- 'azimuth': 70, # Only used for visualization
+ 'azimuth': 70, # Only used for visualization
},
{
'id': '55011271',
@@ -28,7 +30,7 @@ h36m_cameras_intrinsic_params = [
'tangential_distortion': [-0.0016190266469493508, -0.0027408944442868233],
'res_w': 1000,
'res_h': 1000,
- 'azimuth': -70, # Only used for visualization
+ 'azimuth': -70, # Only used for visualization
},
{
'id': '58860488',
@@ -38,7 +40,7 @@ h36m_cameras_intrinsic_params = [
'tangential_distortion': [0.0014843869721516967, -0.0007599993259645998],
'res_w': 1000,
'res_h': 1000,
- 'azimuth': 110, # Only used for visualization
+ 'azimuth': 110, # Only used for visualization
},
{
'id': '60457274',
@@ -48,26 +50,34 @@ h36m_cameras_intrinsic_params = [
'tangential_distortion': [-0.0005872055771760643, -0.0018133620033040643],
'res_w': 1000,
'res_h': 1002,
- 'azimuth': -110, # Only used for visualization
+ 'azimuth': -110, # Only used for visualization
},
]
h36m_cameras_extrinsic_params = {
'S1': [
{
- 'orientation': [0.1407056450843811, -0.1500701755285263, -0.755240797996521, 0.6223280429840088],
+ 'orientation': [
+ 0.1407056450843811, -0.1500701755285263, -0.755240797996521, 0.6223280429840088
+ ],
'translation': [1841.1070556640625, 4955.28466796875, 1563.4454345703125],
},
{
- 'orientation': [0.6157187819480896, -0.764836311340332, -0.14833825826644897, 0.11794740706682205],
+ 'orientation': [
+ 0.6157187819480896, -0.764836311340332, -0.14833825826644897, 0.11794740706682205
+ ],
'translation': [1761.278564453125, -5078.0068359375, 1606.2650146484375],
},
{
- 'orientation': [0.14651472866535187, -0.14647851884365082, 0.7653023600578308, -0.6094175577163696],
+ 'orientation': [
+ 0.14651472866535187, -0.14647851884365082, 0.7653023600578308, -0.6094175577163696
+ ],
'translation': [-1846.7777099609375, 5215.04638671875, 1491.972412109375],
},
{
- 'orientation': [0.5834008455276489, -0.7853162288665771, 0.14548823237419128, -0.14749594032764435],
+ 'orientation': [
+ 0.5834008455276489, -0.7853162288665771, 0.14548823237419128, -0.14749594032764435
+ ],
'translation': [-1794.7896728515625, -3722.698974609375, 1574.8927001953125],
},
],
@@ -91,158 +101,206 @@ h36m_cameras_extrinsic_params = {
],
'S5': [
{
- 'orientation': [0.1467377245426178, -0.162370964884758, -0.7551892995834351, 0.6178938746452332],
+ 'orientation': [
+ 0.1467377245426178, -0.162370964884758, -0.7551892995834351, 0.6178938746452332
+ ],
'translation': [2097.3916015625, 4880.94482421875, 1605.732421875],
},
{
- 'orientation': [0.6159758567810059, -0.7626792192459106, -0.15728192031383514, 0.1189815029501915],
+ 'orientation': [
+ 0.6159758567810059, -0.7626792192459106, -0.15728192031383514, 0.1189815029501915
+ ],
'translation': [2031.7008056640625, -5167.93310546875, 1612.923095703125],
},
{
- 'orientation': [0.14291371405124664, -0.12907841801643372, 0.7678384780883789, -0.6110143065452576],
+ 'orientation': [
+ 0.14291371405124664, -0.12907841801643372, 0.7678384780883789, -0.6110143065452576
+ ],
'translation': [-1620.5948486328125, 5171.65869140625, 1496.43701171875],
},
{
- 'orientation': [0.5920479893684387, -0.7814217805862427, 0.1274748593568802, -0.15036417543888092],
+ 'orientation': [
+ 0.5920479893684387, -0.7814217805862427, 0.1274748593568802, -0.15036417543888092
+ ],
'translation': [-1637.1737060546875, -3867.3173828125, 1547.033203125],
},
],
'S6': [
{
- 'orientation': [0.1337897777557373, -0.15692396461963654, -0.7571090459823608, 0.6198879480361938],
+ 'orientation': [
+ 0.1337897777557373, -0.15692396461963654, -0.7571090459823608, 0.6198879480361938
+ ],
'translation': [1935.4517822265625, 4950.24560546875, 1618.0838623046875],
},
{
- 'orientation': [0.6147197484970093, -0.7628812789916992, -0.16174767911434174, 0.11819244921207428],
+ 'orientation': [
+ 0.6147197484970093, -0.7628812789916992, -0.16174767911434174, 0.11819244921207428
+ ],
'translation': [1969.803955078125, -5128.73876953125, 1632.77880859375],
},
{
- 'orientation': [0.1529948115348816, -0.13529130816459656, 0.7646096348762512, -0.6112781167030334],
+ 'orientation': [
+ 0.1529948115348816, -0.13529130816459656, 0.7646096348762512, -0.6112781167030334
+ ],
'translation': [-1769.596435546875, 5185.361328125, 1476.993408203125],
},
{
- 'orientation': [0.5916101336479187, -0.7804774045944214, 0.12832270562648773, -0.1561593860387802],
+ 'orientation': [
+ 0.5916101336479187, -0.7804774045944214, 0.12832270562648773, -0.1561593860387802
+ ],
'translation': [-1721.668701171875, -3884.13134765625, 1540.4879150390625],
},
],
'S7': [
{
- 'orientation': [0.1435241848230362, -0.1631336808204651, -0.7548328638076782, 0.6188824772834778],
+ 'orientation': [
+ 0.1435241848230362, -0.1631336808204651, -0.7548328638076782, 0.6188824772834778
+ ],
'translation': [1974.512939453125, 4926.3544921875, 1597.8326416015625],
},
{
- 'orientation': [0.6141672730445862, -0.7638262510299683, -0.1596645563840866, 0.1177929937839508],
+ 'orientation': [
+ 0.6141672730445862, -0.7638262510299683, -0.1596645563840866, 0.1177929937839508
+ ],
'translation': [1937.0584716796875, -5119.7900390625, 1631.5665283203125],
},
{
- 'orientation': [0.14550060033798218, -0.12874816358089447, 0.7660516500473022, -0.6127139329910278],
+ 'orientation': [
+ 0.14550060033798218, -0.12874816358089447, 0.7660516500473022, -0.6127139329910278
+ ],
'translation': [-1741.8111572265625, 5208.24951171875, 1464.8245849609375],
},
{
- 'orientation': [0.5912848114967346, -0.7821764349937439, 0.12445473670959473, -0.15196487307548523],
+ 'orientation': [
+ 0.5912848114967346, -0.7821764349937439, 0.12445473670959473, -0.15196487307548523
+ ],
'translation': [-1734.7105712890625, -3832.42138671875, 1548.5830078125],
},
],
'S8': [
{
- 'orientation': [0.14110587537288666, -0.15589867532253265, -0.7561917304992676, 0.619644045829773],
+ 'orientation': [
+ 0.14110587537288666, -0.15589867532253265, -0.7561917304992676, 0.619644045829773
+ ],
'translation': [2150.65185546875, 4896.1611328125, 1611.9046630859375],
},
{
- 'orientation': [0.6169601678848267, -0.7647668123245239, -0.14846350252628326, 0.11158157885074615],
+ 'orientation': [
+ 0.6169601678848267, -0.7647668123245239, -0.14846350252628326, 0.11158157885074615
+ ],
'translation': [2219.965576171875, -5148.453125, 1613.0440673828125],
},
{
- 'orientation': [0.1471444070339203, -0.13377119600772858, 0.7670128345489502, -0.6100369691848755],
+ 'orientation': [
+ 0.1471444070339203, -0.13377119600772858, 0.7670128345489502, -0.6100369691848755
+ ],
'translation': [-1571.2215576171875, 5137.0185546875, 1498.1761474609375],
},
{
- 'orientation': [0.5927824378013611, -0.7825870513916016, 0.12147816270589828, -0.14631995558738708],
+ 'orientation': [
+ 0.5927824378013611, -0.7825870513916016, 0.12147816270589828, -0.14631995558738708
+ ],
'translation': [-1476.913330078125, -3896.7412109375, 1547.97216796875],
},
],
'S9': [
{
- 'orientation': [0.15540587902069092, -0.15548215806484222, -0.7532095313072205, 0.6199594736099243],
+ 'orientation': [
+ 0.15540587902069092, -0.15548215806484222, -0.7532095313072205, 0.6199594736099243
+ ],
'translation': [2044.45849609375, 4935.1171875, 1481.2275390625],
},
{
- 'orientation': [0.618784487247467, -0.7634735107421875, -0.14132238924503326, 0.11933968216180801],
+ 'orientation': [
+ 0.618784487247467, -0.7634735107421875, -0.14132238924503326, 0.11933968216180801
+ ],
'translation': [1990.959716796875, -5123.810546875, 1568.8048095703125],
},
{
- 'orientation': [0.13357827067375183, -0.1367100477218628, 0.7689454555511475, -0.6100738644599915],
+ 'orientation': [
+ 0.13357827067375183, -0.1367100477218628, 0.7689454555511475, -0.6100738644599915
+ ],
'translation': [-1670.9921875, 5211.98583984375, 1528.387939453125],
},
{
- 'orientation': [0.5879399180412292, -0.7823407053947449, 0.1427614390850067, -0.14794869720935822],
+ 'orientation': [
+ 0.5879399180412292, -0.7823407053947449, 0.1427614390850067, -0.14794869720935822
+ ],
'translation': [-1696.04345703125, -3827.099853515625, 1591.4127197265625],
},
],
'S11': [
{
- 'orientation': [0.15232472121715546, -0.15442320704460144, -0.7547563314437866, 0.6191070079803467],
+ 'orientation': [
+ 0.15232472121715546, -0.15442320704460144, -0.7547563314437866, 0.6191070079803467
+ ],
'translation': [2098.440185546875, 4926.5546875, 1500.278564453125],
},
{
- 'orientation': [0.6189449429512024, -0.7600917220115662, -0.15300633013248444, 0.1255258321762085],
+ 'orientation': [
+ 0.6189449429512024, -0.7600917220115662, -0.15300633013248444, 0.1255258321762085
+ ],
'translation': [2083.182373046875, -4912.1728515625, 1561.07861328125],
},
{
- 'orientation': [0.14943228662014008, -0.15650227665901184, 0.7681233882904053, -0.6026304364204407],
+ 'orientation': [
+ 0.14943228662014008, -0.15650227665901184, 0.7681233882904053, -0.6026304364204407
+ ],
'translation': [-1609.8153076171875, 5177.3359375, 1537.896728515625],
},
{
- 'orientation': [0.5894251465797424, -0.7818877100944519, 0.13991211354732513, -0.14715361595153809],
+ 'orientation': [
+ 0.5894251465797424, -0.7818877100944519, 0.13991211354732513, -0.14715361595153809
+ ],
'translation': [-1590.738037109375, -3854.1689453125, 1578.017578125],
},
],
}
+
class Human36mDataset(MocapDataset):
- def __init__(self, path, remove_static_joints=True):
- super().__init__(fps=50, skeleton=h36m_skeleton)
-
- self._cameras = copy.deepcopy(h36m_cameras_extrinsic_params)
- for cameras in self._cameras.values():
- for i, cam in enumerate(cameras):
- cam.update(h36m_cameras_intrinsic_params[i])
- for k, v in cam.items():
- if k not in ['id', 'res_w', 'res_h']:
- cam[k] = np.array(v, dtype='float32')
-
- # Normalize camera frame
- cam['center'] = normalize_screen_coordinates(cam['center'], w=cam['res_w'], h=cam['res_h']).astype('float32')
- cam['focal_length'] = cam['focal_length']/cam['res_w']*2
- if 'translation' in cam:
- cam['translation'] = cam['translation']/1000 # mm to meters
-
- # Add intrinsic parameters vector
- cam['intrinsic'] = np.concatenate((cam['focal_length'],
- cam['center'],
- cam['radial_distortion'],
- cam['tangential_distortion']))
-
- # Load serialized dataset
- data = np.load(path)['positions_3d'].item()
-
- self._data = {}
- for subject, actions in data.items():
- self._data[subject] = {}
- for action_name, positions in actions.items():
- self._data[subject][action_name] = {
- 'positions': positions,
- 'cameras': self._cameras[subject],
- }
-
- if remove_static_joints:
- # Bring the skeleton to 17 joints instead of the original 32
- self.remove_joints([4, 5, 9, 10, 11, 16, 20, 21, 22, 23, 24, 28, 29, 30, 31])
-
- # Rewire shoulders to the correct parents
- self._skeleton._parents[11] = 8
- self._skeleton._parents[14] = 8
-
- def supports_semi_supervised(self):
- return True
- \ No newline at end of file
+
+ def __init__(self, path, remove_static_joints=True):
+ super().__init__(fps=50, skeleton=h36m_skeleton)
+
+ self._cameras = copy.deepcopy(h36m_cameras_extrinsic_params)
+ for cameras in self._cameras.values():
+ for i, cam in enumerate(cameras):
+ cam.update(h36m_cameras_intrinsic_params[i])
+ for k, v in cam.items():
+ if k not in ['id', 'res_w', 'res_h']:
+ cam[k] = np.array(v, dtype='float32')
+
+ # Normalize camera frame
+ cam['center'] = normalize_screen_coordinates(cam['center'], w=cam['res_w'],
+ h=cam['res_h']).astype('float32')
+ cam['focal_length'] = cam['focal_length'] / cam['res_w'] * 2
+ if 'translation' in cam:
+ cam['translation'] = cam['translation'] / 1000 # mm to meters
+
+ # Add intrinsic parameters vector
+ cam['intrinsic'] = np.concatenate((cam['focal_length'], cam['center'],
+ cam['radial_distortion'], cam['tangential_distortion']))
+
+ # Load serialized dataset
+ data = np.load(path)['positions_3d'].item()
+
+ self._data = {}
+ for subject, actions in data.items():
+ self._data[subject] = {}
+ for action_name, positions in actions.items():
+ self._data[subject][action_name] = {
+ 'positions': positions,
+ 'cameras': self._cameras[subject],
+ }
+
+ if remove_static_joints:
+ # Bring the skeleton to 17 joints instead of the original 32
+ self.remove_joints([4, 5, 9, 10, 11, 16, 20, 21, 22, 23, 24, 28, 29, 30, 31])
+
+ # Rewire shoulders to the correct parents
+ self._skeleton._parents[11] = 8
+ self._skeleton._parents[14] = 8
+
+ def supports_semi_supervised(self):
+ return True
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/humanoid.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/humanoid.py
index f55e3cadb..c9f89c4a1 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/humanoid.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/humanoid.py
@@ -1,166 +1,198 @@
-import os, inspect
+import os, inspect
import math
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_utils.bullet_client import BulletClient
import pybullet_data
-jointTypes = ["JOINT_REVOLUTE","JOINT_PRISMATIC",
- "JOINT_SPHERICAL","JOINT_PLANAR","JOINT_FIXED"]
-
+jointTypes = [
+ "JOINT_REVOLUTE", "JOINT_PRISMATIC", "JOINT_SPHERICAL", "JOINT_PLANAR", "JOINT_FIXED"
+]
+
+
class HumanoidPose(object):
+
def __init__(self):
pass
-
+
def Reset(self):
-
- self._basePos = [0,0,0]
- self._baseLinVel = [0,0,0]
- self._baseOrn = [0,0,0,1]
- self._baseAngVel = [0,0,0]
-
- self._chestRot = [0,0,0,1]
- self._chestVel = [0,0,0]
- self._neckRot = [0,0,0,1]
- self._neckVel = [0,0,0]
-
- self._rightHipRot = [0,0,0,1]
- self._rightHipVel = [0,0,0]
+
+ self._basePos = [0, 0, 0]
+ self._baseLinVel = [0, 0, 0]
+ self._baseOrn = [0, 0, 0, 1]
+ self._baseAngVel = [0, 0, 0]
+
+ self._chestRot = [0, 0, 0, 1]
+ self._chestVel = [0, 0, 0]
+ self._neckRot = [0, 0, 0, 1]
+ self._neckVel = [0, 0, 0]
+
+ self._rightHipRot = [0, 0, 0, 1]
+ self._rightHipVel = [0, 0, 0]
self._rightKneeRot = [0]
self._rightKneeVel = [0]
- self._rightAnkleRot = [0,0,0,1]
- self._rightAnkleVel = [0,0,0]
-
- self._rightShoulderRot = [0,0,0,1]
- self._rightShoulderVel = [0,0,0]
+ self._rightAnkleRot = [0, 0, 0, 1]
+ self._rightAnkleVel = [0, 0, 0]
+
+ self._rightShoulderRot = [0, 0, 0, 1]
+ self._rightShoulderVel = [0, 0, 0]
self._rightElbowRot = [0]
self._rightElbowVel = [0]
- self._leftHipRot = [0,0,0,1]
- self._leftHipVel = [0,0,0]
+ self._leftHipRot = [0, 0, 0, 1]
+ self._leftHipVel = [0, 0, 0]
self._leftKneeRot = [0]
self._leftKneeVel = [0]
- self._leftAnkleRot = [0,0,0,1]
- self._leftAnkleVel = [0,0,0]
-
- self._leftShoulderRot = [0,0,0,1]
- self._leftShoulderVel = [0,0,0]
+ self._leftAnkleRot = [0, 0, 0, 1]
+ self._leftAnkleVel = [0, 0, 0]
+
+ self._leftShoulderRot = [0, 0, 0, 1]
+ self._leftShoulderVel = [0, 0, 0]
self._leftElbowRot = [0]
self._leftElbowVel = [0]
- def ComputeLinVel(self,posStart, posEnd, deltaTime):
- vel = [(posEnd[0]-posStart[0])/deltaTime,(posEnd[1]-posStart[1])/deltaTime,(posEnd[2]-posStart[2])/deltaTime]
+ def ComputeLinVel(self, posStart, posEnd, deltaTime):
+ vel = [(posEnd[0] - posStart[0]) / deltaTime, (posEnd[1] - posStart[1]) / deltaTime,
+ (posEnd[2] - posStart[2]) / deltaTime]
return vel
-
- def ComputeAngVel(self,ornStart, ornEnd, deltaTime, bullet_client):
- dorn = bullet_client.getDifferenceQuaternion(ornStart,ornEnd)
- axis,angle = bullet_client.getAxisAngleFromQuaternion(dorn)
- angVel = [(axis[0]*angle)/deltaTime,(axis[1]*angle)/deltaTime,(axis[2]*angle)/deltaTime]
+
+ def ComputeAngVel(self, ornStart, ornEnd, deltaTime, bullet_client):
+ dorn = bullet_client.getDifferenceQuaternion(ornStart, ornEnd)
+ axis, angle = bullet_client.getAxisAngleFromQuaternion(dorn)
+ angVel = [(axis[0] * angle) / deltaTime, (axis[1] * angle) / deltaTime,
+ (axis[2] * angle) / deltaTime]
return angVel
-
+
def NormalizeQuaternion(self, orn):
- length2 = orn[0]*orn[0]+orn[1]*orn[1]+orn[2]*orn[2]+orn[3]*orn[3]
- if (length2>0):
+ length2 = orn[0] * orn[0] + orn[1] * orn[1] + orn[2] * orn[2] + orn[3] * orn[3]
+ if (length2 > 0):
length = math.sqrt(length2)
#print("Normalize? length=",length)
-
def PostProcessMotionData(self, frameData):
- baseOrn1Start = [frameData[5],frameData[6], frameData[7],frameData[4]]
+ baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
self.NormalizeQuaternion(baseOrn1Start)
- chestRotStart = [frameData[9],frameData[10],frameData[11],frameData[8]]
-
- neckRotStart = [frameData[13],frameData[14],frameData[15],frameData[12]]
- rightHipRotStart = [frameData[17],frameData[18],frameData[19],frameData[16]]
- rightAnkleRotStart = [frameData[22],frameData[23],frameData[24],frameData[21]]
- rightShoulderRotStart = [frameData[26],frameData[27],frameData[28],frameData[25]]
- leftHipRotStart = [frameData[31],frameData[32],frameData[33],frameData[30]]
- leftAnkleRotStart = [frameData[36],frameData[37],frameData[38],frameData[35]]
- leftShoulderRotStart = [frameData[40],frameData[41],frameData[42],frameData[39]]
-
-
- def Slerp(self, frameFraction, frameData, frameDataNext,bullet_client ):
+ chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]]
+
+ neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]]
+ rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]]
+ rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]]
+ rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]]
+ leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]]
+ leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]]
+ leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]]
+
+ def Slerp(self, frameFraction, frameData, frameDataNext, bullet_client):
keyFrameDuration = frameData[0]
- basePos1Start = [frameData[1],frameData[2],frameData[3]]
- basePos1End = [frameDataNext[1],frameDataNext[2],frameDataNext[3]]
- self._basePos = [basePos1Start[0]+frameFraction*(basePos1End[0]-basePos1Start[0]),
- basePos1Start[1]+frameFraction*(basePos1End[1]-basePos1Start[1]),
- basePos1Start[2]+frameFraction*(basePos1End[2]-basePos1Start[2])]
- self._baseLinVel = self.ComputeLinVel(basePos1Start,basePos1End, keyFrameDuration)
- baseOrn1Start = [frameData[5],frameData[6], frameData[7],frameData[4]]
- baseOrn1Next = [frameDataNext[5],frameDataNext[6], frameDataNext[7],frameDataNext[4]]
- self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start,baseOrn1Next,frameFraction)
- self._baseAngVel = self.ComputeAngVel(baseOrn1Start,baseOrn1Next, keyFrameDuration, bullet_client)
-
+ basePos1Start = [frameData[1], frameData[2], frameData[3]]
+ basePos1End = [frameDataNext[1], frameDataNext[2], frameDataNext[3]]
+ self._basePos = [
+ basePos1Start[0] + frameFraction * (basePos1End[0] - basePos1Start[0]),
+ basePos1Start[1] + frameFraction * (basePos1End[1] - basePos1Start[1]),
+ basePos1Start[2] + frameFraction * (basePos1End[2] - basePos1Start[2])
+ ]
+ self._baseLinVel = self.ComputeLinVel(basePos1Start, basePos1End, keyFrameDuration)
+ baseOrn1Start = [frameData[5], frameData[6], frameData[7], frameData[4]]
+ baseOrn1Next = [frameDataNext[5], frameDataNext[6], frameDataNext[7], frameDataNext[4]]
+ self._baseOrn = bullet_client.getQuaternionSlerp(baseOrn1Start, baseOrn1Next, frameFraction)
+ self._baseAngVel = self.ComputeAngVel(baseOrn1Start, baseOrn1Next, keyFrameDuration,
+ bullet_client)
+
##pre-rotate to make z-up
#y2zPos=[0,0,0.0]
#y2zOrn = p.getQuaternionFromEuler([1.57,0,0])
#basePos,baseOrn = p.multiplyTransforms(y2zPos, y2zOrn,basePos1,baseOrn1)
- chestRotStart = [frameData[9],frameData[10],frameData[11],frameData[8]]
- chestRotEnd = [frameDataNext[9],frameDataNext[10],frameDataNext[11],frameDataNext[8]]
- self._chestRot = bullet_client.getQuaternionSlerp(chestRotStart,chestRotEnd,frameFraction)
- self._chestVel = self.ComputeAngVel(chestRotStart,chestRotEnd,keyFrameDuration,bullet_client)
-
- neckRotStart = [frameData[13],frameData[14],frameData[15],frameData[12]]
- neckRotEnd= [frameDataNext[13],frameDataNext[14],frameDataNext[15],frameDataNext[12]]
- self._neckRot = bullet_client.getQuaternionSlerp(neckRotStart,neckRotEnd,frameFraction)
- self._neckVel = self.ComputeAngVel(neckRotStart,neckRotEnd,keyFrameDuration,bullet_client)
-
- rightHipRotStart = [frameData[17],frameData[18],frameData[19],frameData[16]]
- rightHipRotEnd = [frameDataNext[17],frameDataNext[18],frameDataNext[19],frameDataNext[16]]
- self._rightHipRot = bullet_client.getQuaternionSlerp(rightHipRotStart,rightHipRotEnd,frameFraction)
- self._rightHipVel = self.ComputeAngVel(rightHipRotStart,rightHipRotEnd,keyFrameDuration,bullet_client)
-
+ chestRotStart = [frameData[9], frameData[10], frameData[11], frameData[8]]
+ chestRotEnd = [frameDataNext[9], frameDataNext[10], frameDataNext[11], frameDataNext[8]]
+ self._chestRot = bullet_client.getQuaternionSlerp(chestRotStart, chestRotEnd, frameFraction)
+ self._chestVel = self.ComputeAngVel(chestRotStart, chestRotEnd, keyFrameDuration,
+ bullet_client)
+
+ neckRotStart = [frameData[13], frameData[14], frameData[15], frameData[12]]
+ neckRotEnd = [frameDataNext[13], frameDataNext[14], frameDataNext[15], frameDataNext[12]]
+ self._neckRot = bullet_client.getQuaternionSlerp(neckRotStart, neckRotEnd, frameFraction)
+ self._neckVel = self.ComputeAngVel(neckRotStart, neckRotEnd, keyFrameDuration, bullet_client)
+
+ rightHipRotStart = [frameData[17], frameData[18], frameData[19], frameData[16]]
+ rightHipRotEnd = [frameDataNext[17], frameDataNext[18], frameDataNext[19], frameDataNext[16]]
+ self._rightHipRot = bullet_client.getQuaternionSlerp(rightHipRotStart, rightHipRotEnd,
+ frameFraction)
+ self._rightHipVel = self.ComputeAngVel(rightHipRotStart, rightHipRotEnd, keyFrameDuration,
+ bullet_client)
+
rightKneeRotStart = [frameData[20]]
rightKneeRotEnd = [frameDataNext[20]]
- self._rightKneeRot = [rightKneeRotStart[0]+frameFraction*(rightKneeRotEnd[0]-rightKneeRotStart[0])]
- self._rightKneeVel = [(rightKneeRotEnd[0]-rightKneeRotStart[0])/keyFrameDuration]
-
- rightAnkleRotStart = [frameData[22],frameData[23],frameData[24],frameData[21]]
- rightAnkleRotEnd = [frameDataNext[22],frameDataNext[23],frameDataNext[24],frameDataNext[21]]
- self._rightAnkleRot = bullet_client.getQuaternionSlerp(rightAnkleRotStart,rightAnkleRotEnd,frameFraction)
- self._rightAnkleVel = self.ComputeAngVel(rightAnkleRotStart,rightAnkleRotEnd,keyFrameDuration,bullet_client)
-
- rightShoulderRotStart = [frameData[26],frameData[27],frameData[28],frameData[25]]
- rightShoulderRotEnd = [frameDataNext[26],frameDataNext[27],frameDataNext[28],frameDataNext[25]]
- self._rightShoulderRot = bullet_client.getQuaternionSlerp(rightShoulderRotStart,rightShoulderRotEnd,frameFraction)
- self._rightShoulderVel = self.ComputeAngVel(rightShoulderRotStart,rightShoulderRotEnd, keyFrameDuration,bullet_client)
-
+ self._rightKneeRot = [
+ rightKneeRotStart[0] + frameFraction * (rightKneeRotEnd[0] - rightKneeRotStart[0])
+ ]
+ self._rightKneeVel = [(rightKneeRotEnd[0] - rightKneeRotStart[0]) / keyFrameDuration]
+
+ rightAnkleRotStart = [frameData[22], frameData[23], frameData[24], frameData[21]]
+ rightAnkleRotEnd = [frameDataNext[22], frameDataNext[23], frameDataNext[24], frameDataNext[21]]
+ self._rightAnkleRot = bullet_client.getQuaternionSlerp(rightAnkleRotStart, rightAnkleRotEnd,
+ frameFraction)
+ self._rightAnkleVel = self.ComputeAngVel(rightAnkleRotStart, rightAnkleRotEnd,
+ keyFrameDuration, bullet_client)
+
+ rightShoulderRotStart = [frameData[26], frameData[27], frameData[28], frameData[25]]
+ rightShoulderRotEnd = [
+ frameDataNext[26], frameDataNext[27], frameDataNext[28], frameDataNext[25]
+ ]
+ self._rightShoulderRot = bullet_client.getQuaternionSlerp(rightShoulderRotStart,
+ rightShoulderRotEnd, frameFraction)
+ self._rightShoulderVel = self.ComputeAngVel(rightShoulderRotStart, rightShoulderRotEnd,
+ keyFrameDuration, bullet_client)
+
rightElbowRotStart = [frameData[29]]
rightElbowRotEnd = [frameDataNext[29]]
- self._rightElbowRot = [rightElbowRotStart[0]+frameFraction*(rightElbowRotEnd[0]-rightElbowRotStart[0])]
- self._rightElbowVel = [(rightElbowRotEnd[0]-rightElbowRotStart[0])/keyFrameDuration]
-
- leftHipRotStart = [frameData[31],frameData[32],frameData[33],frameData[30]]
- leftHipRotEnd = [frameDataNext[31],frameDataNext[32],frameDataNext[33],frameDataNext[30]]
- self._leftHipRot = bullet_client.getQuaternionSlerp(leftHipRotStart,leftHipRotEnd,frameFraction)
- self._leftHipVel = self.ComputeAngVel(leftHipRotStart, leftHipRotEnd,keyFrameDuration,bullet_client)
-
+ self._rightElbowRot = [
+ rightElbowRotStart[0] + frameFraction * (rightElbowRotEnd[0] - rightElbowRotStart[0])
+ ]
+ self._rightElbowVel = [(rightElbowRotEnd[0] - rightElbowRotStart[0]) / keyFrameDuration]
+
+ leftHipRotStart = [frameData[31], frameData[32], frameData[33], frameData[30]]
+ leftHipRotEnd = [frameDataNext[31], frameDataNext[32], frameDataNext[33], frameDataNext[30]]
+ self._leftHipRot = bullet_client.getQuaternionSlerp(leftHipRotStart, leftHipRotEnd,
+ frameFraction)
+ self._leftHipVel = self.ComputeAngVel(leftHipRotStart, leftHipRotEnd, keyFrameDuration,
+ bullet_client)
+
leftKneeRotStart = [frameData[34]]
leftKneeRotEnd = [frameDataNext[34]]
- self._leftKneeRot = [leftKneeRotStart[0] +frameFraction*(leftKneeRotEnd[0]-leftKneeRotStart[0]) ]
- self._leftKneeVel = [(leftKneeRotEnd[0]-leftKneeRotStart[0])/keyFrameDuration]
-
- leftAnkleRotStart = [frameData[36],frameData[37],frameData[38],frameData[35]]
- leftAnkleRotEnd = [frameDataNext[36],frameDataNext[37],frameDataNext[38],frameDataNext[35]]
- self._leftAnkleRot = bullet_client.getQuaternionSlerp(leftAnkleRotStart,leftAnkleRotEnd,frameFraction)
- self._leftAnkleVel = self.ComputeAngVel(leftAnkleRotStart,leftAnkleRotEnd,keyFrameDuration,bullet_client)
-
- leftShoulderRotStart = [frameData[40],frameData[41],frameData[42],frameData[39]]
- leftShoulderRotEnd = [frameDataNext[40],frameDataNext[41],frameDataNext[42],frameDataNext[39]]
- self._leftShoulderRot = bullet_client.getQuaternionSlerp(leftShoulderRotStart,leftShoulderRotEnd,frameFraction)
- self._leftShoulderVel = self.ComputeAngVel(leftShoulderRotStart,leftShoulderRotEnd,keyFrameDuration,bullet_client)
+ self._leftKneeRot = [
+ leftKneeRotStart[0] + frameFraction * (leftKneeRotEnd[0] - leftKneeRotStart[0])
+ ]
+ self._leftKneeVel = [(leftKneeRotEnd[0] - leftKneeRotStart[0]) / keyFrameDuration]
+
+ leftAnkleRotStart = [frameData[36], frameData[37], frameData[38], frameData[35]]
+ leftAnkleRotEnd = [frameDataNext[36], frameDataNext[37], frameDataNext[38], frameDataNext[35]]
+ self._leftAnkleRot = bullet_client.getQuaternionSlerp(leftAnkleRotStart, leftAnkleRotEnd,
+ frameFraction)
+ self._leftAnkleVel = self.ComputeAngVel(leftAnkleRotStart, leftAnkleRotEnd, keyFrameDuration,
+ bullet_client)
+
+ leftShoulderRotStart = [frameData[40], frameData[41], frameData[42], frameData[39]]
+ leftShoulderRotEnd = [
+ frameDataNext[40], frameDataNext[41], frameDataNext[42], frameDataNext[39]
+ ]
+ self._leftShoulderRot = bullet_client.getQuaternionSlerp(leftShoulderRotStart,
+ leftShoulderRotEnd, frameFraction)
+ self._leftShoulderVel = self.ComputeAngVel(leftShoulderRotStart, leftShoulderRotEnd,
+ keyFrameDuration, bullet_client)
leftElbowRotStart = [frameData[43]]
leftElbowRotEnd = [frameDataNext[43]]
- self._leftElbowRot = [leftElbowRotStart[0]+frameFraction*(leftElbowRotEnd[0]-leftElbowRotStart[0])]
- self._leftElbowVel = [(leftElbowRotEnd[0]-leftElbowRotStart[0])/keyFrameDuration]
-
+ self._leftElbowRot = [
+ leftElbowRotStart[0] + frameFraction * (leftElbowRotEnd[0] - leftElbowRotStart[0])
+ ]
+ self._leftElbowVel = [(leftElbowRotEnd[0] - leftElbowRotStart[0]) / keyFrameDuration]
+
class Humanoid(object):
+
def __init__(self, pybullet_client, motion_data, baseShift):
"""Constructs a humanoid and reset it to the initial states.
Args:
@@ -169,42 +201,46 @@ class Humanoid(object):
"""
self._baseShift = baseShift
self._pybullet_client = pybullet_client
-
- self.kin_client = BulletClient(pybullet_client.DIRECT)# use SHARED_MEMORY for visual debugging, start a GUI physics server first
+
+ self.kin_client = BulletClient(
+ pybullet_client.DIRECT
+ ) # use SHARED_MEMORY for visual debugging, start a GUI physics server first
self.kin_client.resetSimulation()
self.kin_client.setAdditionalSearchPath(pybullet_data.getDataPath())
- self.kin_client.configureDebugVisualizer(self.kin_client.COV_ENABLE_Y_AXIS_UP,1)
- self.kin_client.setGravity(0,-9.8,0)
-
+ self.kin_client.configureDebugVisualizer(self.kin_client.COV_ENABLE_Y_AXIS_UP, 1)
+ self.kin_client.setGravity(0, -9.8, 0)
+
self._motion_data = motion_data
print("LOADING humanoid!")
- self._humanoid = self._pybullet_client.loadURDF(
- "humanoid/humanoid.urdf", [0,0.9,0],globalScaling=0.25, useFixedBase=False)
-
- self._kinematicHumanoid = self.kin_client.loadURDF(
- "humanoid/humanoid.urdf", [0,0.9,0],globalScaling=0.25, useFixedBase=False)
-
-
+ self._humanoid = self._pybullet_client.loadURDF("humanoid/humanoid.urdf", [0, 0.9, 0],
+ globalScaling=0.25,
+ useFixedBase=False)
+
+ self._kinematicHumanoid = self.kin_client.loadURDF("humanoid/humanoid.urdf", [0, 0.9, 0],
+ globalScaling=0.25,
+ useFixedBase=False)
+
#print("human #joints=", self._pybullet_client.getNumJoints(self._humanoid))
pose = HumanoidPose()
-
- for i in range (self._motion_data.NumFrames()-1):
+
+ for i in range(self._motion_data.NumFrames() - 1):
frameData = self._motion_data._motion_data['Frames'][i]
pose.PostProcessMotionData(frameData)
-
- self._pybullet_client.resetBasePositionAndOrientation(self._humanoid,self._baseShift,[0,0,0,1])
+
+ self._pybullet_client.resetBasePositionAndOrientation(self._humanoid, self._baseShift,
+ [0, 0, 0, 1])
self._pybullet_client.changeDynamics(self._humanoid, -1, linearDamping=0, angularDamping=0)
- for j in range (self._pybullet_client.getNumJoints(self._humanoid)):
- ji = self._pybullet_client.getJointInfo(self._humanoid,j)
+ for j in range(self._pybullet_client.getNumJoints(self._humanoid)):
+ ji = self._pybullet_client.getJointInfo(self._humanoid, j)
self._pybullet_client.changeDynamics(self._humanoid, j, linearDamping=0, angularDamping=0)
- self._pybullet_client.changeVisualShape(self._humanoid, j , rgbaColor=[1,1,1,1])
+ self._pybullet_client.changeVisualShape(self._humanoid, j, rgbaColor=[1, 1, 1, 1])
#print("joint[",j,"].type=",jointTypes[ji[2]])
#print("joint[",j,"].name=",ji[1])
-
+
self._initial_state = self._pybullet_client.saveState()
- self._allowed_body_parts=[11,14]
+ self._allowed_body_parts = [11, 14]
self.Reset()
-
+
def Reset(self):
self._pybullet_client.restoreState(self._initial_state)
self.SetSimTime(0)
@@ -220,7 +256,7 @@ class Humanoid(object):
self.ApplyPose(pose, True, True, self._humanoid, self._pybullet_client)
def CalcCycleCount(self, simTime, cycleTime):
- phases = simTime / cycleTime;
+ phases = simTime / cycleTime
count = math.floor(phases)
loop = True
#count = (loop) ? count : cMathUtil::Clamp(count, 0, 1);
@@ -230,67 +266,67 @@ class Humanoid(object):
self._simTime = t
#print("SetTimeTime time =",t)
keyFrameDuration = self._motion_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._motion_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._motion_data.NumFrames() - 1)
#print("self._motion_data.NumFrames()=",self._motion_data.NumFrames())
#print("cycleTime=",cycleTime)
cycles = self.CalcCycleCount(t, cycleTime)
#print("cycles=",cycles)
- frameTime = t - cycles*cycleTime
- if (frameTime<0):
+ frameTime = t - cycles * cycleTime
+ if (frameTime < 0):
frameTime += cycleTime
-
- #print("keyFrameDuration=",keyFrameDuration)
+
+ #print("keyFrameDuration=",keyFrameDuration)
#print("frameTime=",frameTime)
- self._frame = int(frameTime/keyFrameDuration)
+ self._frame = int(frameTime / keyFrameDuration)
#print("self._frame=",self._frame)
-
- self._frameNext = self._frame+1
- if (self._frameNext >= self._motion_data.NumFrames()):
+
+ self._frameNext = self._frame + 1
+ if (self._frameNext >= self._motion_data.NumFrames()):
self._frameNext = self._frame
- self._frameFraction = (frameTime - self._frame*keyFrameDuration)/(keyFrameDuration)
+ self._frameFraction = (frameTime - self._frame * keyFrameDuration) / (keyFrameDuration)
#print("self._frameFraction=",self._frameFraction)
def Terminates(self):
#check if any non-allowed body part hits the ground
- terminates=False
+ terminates = False
pts = self._pybullet_client.getContactPoints()
for p in pts:
part = -1
- if (p[1]==self._humanoid):
- part=p[3]
- if (p[2]==self._humanoid):
- part=p[4]
- if (part >=0 and part not in self._allowed_body_parts):
- terminates=True
-
+ if (p[1] == self._humanoid):
+ part = p[3]
+ if (p[2] == self._humanoid):
+ part = p[4]
+ if (part >= 0 and part not in self._allowed_body_parts):
+ terminates = True
+
return terminates
-
+
def BuildHeadingTrans(self, rootOrn):
#align root transform 'forward' with world-space x axis
eul = self._pybullet_client.getEulerFromQuaternion(rootOrn)
- refDir = [1,0,0]
+ refDir = [1, 0, 0]
rotVec = self._pybullet_client.rotateVector(rootOrn, refDir)
heading = math.atan2(-rotVec[2], rotVec[0])
- heading2=eul[1]
+ heading2 = eul[1]
#print("heading=",heading)
- headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0,1,0],-heading)
+ headingOrn = self._pybullet_client.getQuaternionFromAxisAngle([0, 1, 0], -heading)
return headingOrn
def GetPhase(self):
keyFrameDuration = self._motion_data.KeyFrameDuraction()
- cycleTime = keyFrameDuration*(self._motion_data.NumFrames()-1)
+ cycleTime = keyFrameDuration * (self._motion_data.NumFrames() - 1)
phase = self._simTime / cycleTime
- phase = math.fmod(phase,1.0)
- if (phase<0):
+ phase = math.fmod(phase, 1.0)
+ if (phase < 0):
phase += 1
return phase
def BuildOriginTrans(self):
- rootPos,rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
-
+ rootPos, rootOrn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
+
#print("rootPos=",rootPos, " rootOrn=",rootOrn)
- invRootPos=[-rootPos[0], 0, -rootPos[2]]
+ invRootPos = [-rootPos[0], 0, -rootPos[2]]
#invOrigTransPos, invOrigTransOrn = self._pybullet_client.invertTransform(rootPos,rootOrn)
headingOrn = self.BuildHeadingTrans(rootOrn)
#print("headingOrn=",headingOrn)
@@ -298,166 +334,226 @@ class Humanoid(object):
#print("headingMat=",headingMat)
#dummy, rootOrnWithoutHeading = self._pybullet_client.multiplyTransforms([0,0,0],headingOrn, [0,0,0], rootOrn)
#dummy, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0,0,0],rootOrnWithoutHeading, invOrigTransPos, invOrigTransOrn)
-
- invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms( [0,0,0],headingOrn, invRootPos,[0,0,0,1])
+
+ invOrigTransPos, invOrigTransOrn = self._pybullet_client.multiplyTransforms([0, 0, 0],
+ headingOrn,
+ invRootPos,
+ [0, 0, 0, 1])
#print("invOrigTransPos=",invOrigTransPos)
#print("invOrigTransOrn=",invOrigTransOrn)
invOrigTransMat = self._pybullet_client.getMatrixFromQuaternion(invOrigTransOrn)
#print("invOrigTransMat =",invOrigTransMat )
return invOrigTransPos, invOrigTransOrn
-
+
def InitializePoseFromMotionData(self):
frameData = self._motion_data._motion_data['Frames'][self._frame]
frameDataNext = self._motion_data._motion_data['Frames'][self._frameNext]
pose = HumanoidPose()
pose.Slerp(self._frameFraction, frameData, frameDataNext, self._pybullet_client)
return pose
-
-
-
def ApplyAction(self, action):
#turn action into pose
pose = HumanoidPose()
pose.Reset()
- index=0
+ index = 0
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._chestRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._chestRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
#print("pose._chestRot=",pose._chestRot)
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._neckRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._neckRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._rightHipRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._rightHipRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
pose._rightKneeRot = [angle]
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._rightAnkleRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._rightAnkleRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._rightShoulderRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._rightShoulderRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
pose._rightElbowRot = [angle]
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._leftHipRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._leftHipRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
pose._leftKneeRot = [angle]
-
-
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._leftAnkleRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._leftAnkleRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- axis = [action[index+1],action[index+2],action[index+3]]
- index+=4
- pose._leftShoulderRot = self._pybullet_client.getQuaternionFromAxisAngle(axis,angle)
-
+ axis = [action[index + 1], action[index + 2], action[index + 3]]
+ index += 4
+ pose._leftShoulderRot = self._pybullet_client.getQuaternionFromAxisAngle(axis, angle)
+
angle = action[index]
- index+=1
+ index += 1
pose._leftElbowRot = [angle]
-
-
+
#print("index=",index)
-
+
initializeBase = False
initializeVelocities = False
- self.ApplyPose(pose, initializeBase, initializeVelocities, self._humanoid, self._pybullet_client)
-
-
- def ApplyPose(self, pose, initializeBase, initializeVelocities, humanoid,bc):
+ self.ApplyPose(pose, initializeBase, initializeVelocities, self._humanoid,
+ self._pybullet_client)
+
+ def ApplyPose(self, pose, initializeBase, initializeVelocities, humanoid, bc):
#todo: get tunable parametes from a json file or from URDF (kd, maxForce)
if (initializeBase):
- bc.changeVisualShape(humanoid, 2 , rgbaColor=[1,0,0,1])
- basePos=[pose._basePos[0]+self._baseShift[0],pose._basePos[1]+self._baseShift[1],pose._basePos[2]+self._baseShift[2]]
-
- bc.resetBasePositionAndOrientation(humanoid,
- basePos, pose._baseOrn)
+ bc.changeVisualShape(humanoid, 2, rgbaColor=[1, 0, 0, 1])
+ basePos = [
+ pose._basePos[0] + self._baseShift[0], pose._basePos[1] + self._baseShift[1],
+ pose._basePos[2] + self._baseShift[2]
+ ]
+
+ bc.resetBasePositionAndOrientation(humanoid, basePos, pose._baseOrn)
if initializeVelocities:
bc.resetBaseVelocity(humanoid, pose._baseLinVel, pose._baseAngVel)
#print("resetBaseVelocity=",pose._baseLinVel)
else:
- bc.changeVisualShape(humanoid, 2 , rgbaColor=[1,1,1,1])
-
-
-
- kp=0.03
- chest=1
- neck=2
- rightShoulder=3
- rightElbow=4
- leftShoulder=6
+ bc.changeVisualShape(humanoid, 2, rgbaColor=[1, 1, 1, 1])
+
+ kp = 0.03
+ chest = 1
+ neck = 2
+ rightShoulder = 3
+ rightElbow = 4
+ leftShoulder = 6
leftElbow = 7
rightHip = 9
- rightKnee=10
- rightAnkle=11
+ rightKnee = 10
+ rightAnkle = 11
leftHip = 12
- leftKnee=13
- leftAnkle=14
+ leftKnee = 13
+ leftAnkle = 14
controlMode = bc.POSITION_CONTROL
-
+
if (initializeBase):
if initializeVelocities:
- bc.resetJointStateMultiDof(humanoid,chest,pose._chestRot, pose._chestVel)
- bc.resetJointStateMultiDof(humanoid,neck,pose._neckRot, pose._neckVel)
- bc.resetJointStateMultiDof(humanoid,rightHip,pose._rightHipRot, pose._rightHipVel)
- bc.resetJointStateMultiDof(humanoid,rightKnee,pose._rightKneeRot, pose._rightKneeVel)
- bc.resetJointStateMultiDof(humanoid,rightAnkle,pose._rightAnkleRot, pose._rightAnkleVel)
- bc.resetJointStateMultiDof(humanoid,rightShoulder,pose._rightShoulderRot, pose._rightShoulderVel)
- bc.resetJointStateMultiDof(humanoid,rightElbow, pose._rightElbowRot, pose._rightElbowVel)
- bc.resetJointStateMultiDof(humanoid,leftHip, pose._leftHipRot, pose._leftHipVel)
- bc.resetJointStateMultiDof(humanoid,leftKnee, pose._leftKneeRot, pose._leftKneeVel)
- bc.resetJointStateMultiDof(humanoid,leftAnkle, pose._leftAnkleRot, pose._leftAnkleVel)
- bc.resetJointStateMultiDof(humanoid,leftShoulder, pose._leftShoulderRot, pose._leftShoulderVel)
- bc.resetJointStateMultiDof(humanoid,leftElbow, pose._leftElbowRot, pose._leftElbowVel)
+ bc.resetJointStateMultiDof(humanoid, chest, pose._chestRot, pose._chestVel)
+ bc.resetJointStateMultiDof(humanoid, neck, pose._neckRot, pose._neckVel)
+ bc.resetJointStateMultiDof(humanoid, rightHip, pose._rightHipRot, pose._rightHipVel)
+ bc.resetJointStateMultiDof(humanoid, rightKnee, pose._rightKneeRot, pose._rightKneeVel)
+ bc.resetJointStateMultiDof(humanoid, rightAnkle, pose._rightAnkleRot, pose._rightAnkleVel)
+ bc.resetJointStateMultiDof(humanoid, rightShoulder, pose._rightShoulderRot,
+ pose._rightShoulderVel)
+ bc.resetJointStateMultiDof(humanoid, rightElbow, pose._rightElbowRot, pose._rightElbowVel)
+ bc.resetJointStateMultiDof(humanoid, leftHip, pose._leftHipRot, pose._leftHipVel)
+ bc.resetJointStateMultiDof(humanoid, leftKnee, pose._leftKneeRot, pose._leftKneeVel)
+ bc.resetJointStateMultiDof(humanoid, leftAnkle, pose._leftAnkleRot, pose._leftAnkleVel)
+ bc.resetJointStateMultiDof(humanoid, leftShoulder, pose._leftShoulderRot,
+ pose._leftShoulderVel)
+ bc.resetJointStateMultiDof(humanoid, leftElbow, pose._leftElbowRot, pose._leftElbowVel)
else:
- bc.resetJointStateMultiDof(humanoid,chest,pose._chestRot)
- bc.resetJointStateMultiDof(humanoid,neck,pose._neckRot)
- bc.resetJointStateMultiDof(humanoid,rightHip,pose._rightHipRot)
- bc.resetJointStateMultiDof(humanoid,rightKnee,pose._rightKneeRot)
- bc.resetJointStateMultiDof(humanoid,rightAnkle,pose._rightAnkleRot)
- bc.resetJointStateMultiDof(humanoid,rightShoulder,pose._rightShoulderRot)
- bc.resetJointStateMultiDof(humanoid,rightElbow, pose._rightElbowRot)
- bc.resetJointStateMultiDof(humanoid,leftHip, pose._leftHipRot)
- bc.resetJointStateMultiDof(humanoid,leftKnee, pose._leftKneeRot)
- bc.resetJointStateMultiDof(humanoid,leftAnkle, pose._leftAnkleRot)
- bc.resetJointStateMultiDof(humanoid,leftShoulder, pose._leftShoulderRot)
- bc.resetJointStateMultiDof(humanoid,leftElbow, pose._leftElbowRot)
-
- bc.setJointMotorControlMultiDof(humanoid,chest,controlMode, targetPosition=pose._chestRot,positionGain=kp, force=[200])
- bc.setJointMotorControlMultiDof(humanoid,neck,controlMode,targetPosition=pose._neckRot,positionGain=kp, force=[50])
- bc.setJointMotorControlMultiDof(humanoid,rightHip,controlMode,targetPosition=pose._rightHipRot,positionGain=kp, force=[200])
- bc.setJointMotorControlMultiDof(humanoid,rightKnee,controlMode,targetPosition=pose._rightKneeRot,positionGain=kp, force=[150])
- bc.setJointMotorControlMultiDof(humanoid,rightAnkle,controlMode,targetPosition=pose._rightAnkleRot,positionGain=kp, force=[90])
- bc.setJointMotorControlMultiDof(humanoid,rightShoulder,controlMode,targetPosition=pose._rightShoulderRot,positionGain=kp, force=[100])
- bc.setJointMotorControlMultiDof(humanoid,rightElbow, controlMode,targetPosition=pose._rightElbowRot,positionGain=kp, force=[60])
- bc.setJointMotorControlMultiDof(humanoid,leftHip, controlMode,targetPosition=pose._leftHipRot,positionGain=kp, force=[200])
- bc.setJointMotorControlMultiDof(humanoid,leftKnee, controlMode,targetPosition=pose._leftKneeRot,positionGain=kp, force=[150])
- bc.setJointMotorControlMultiDof(humanoid,leftAnkle, controlMode,targetPosition=pose._leftAnkleRot,positionGain=kp, force=[90])
- bc.setJointMotorControlMultiDof(humanoid,leftShoulder, controlMode,targetPosition=pose._leftShoulderRot,positionGain=kp, force=[100])
- bc.setJointMotorControlMultiDof(humanoid,leftElbow, controlMode,targetPosition=pose._leftElbowRot,positionGain=kp, force=[60])
+ bc.resetJointStateMultiDof(humanoid, chest, pose._chestRot)
+ bc.resetJointStateMultiDof(humanoid, neck, pose._neckRot)
+ bc.resetJointStateMultiDof(humanoid, rightHip, pose._rightHipRot)
+ bc.resetJointStateMultiDof(humanoid, rightKnee, pose._rightKneeRot)
+ bc.resetJointStateMultiDof(humanoid, rightAnkle, pose._rightAnkleRot)
+ bc.resetJointStateMultiDof(humanoid, rightShoulder, pose._rightShoulderRot)
+ bc.resetJointStateMultiDof(humanoid, rightElbow, pose._rightElbowRot)
+ bc.resetJointStateMultiDof(humanoid, leftHip, pose._leftHipRot)
+ bc.resetJointStateMultiDof(humanoid, leftKnee, pose._leftKneeRot)
+ bc.resetJointStateMultiDof(humanoid, leftAnkle, pose._leftAnkleRot)
+ bc.resetJointStateMultiDof(humanoid, leftShoulder, pose._leftShoulderRot)
+ bc.resetJointStateMultiDof(humanoid, leftElbow, pose._leftElbowRot)
+
+ bc.setJointMotorControlMultiDof(humanoid,
+ chest,
+ controlMode,
+ targetPosition=pose._chestRot,
+ positionGain=kp,
+ force=[200])
+ bc.setJointMotorControlMultiDof(humanoid,
+ neck,
+ controlMode,
+ targetPosition=pose._neckRot,
+ positionGain=kp,
+ force=[50])
+ bc.setJointMotorControlMultiDof(humanoid,
+ rightHip,
+ controlMode,
+ targetPosition=pose._rightHipRot,
+ positionGain=kp,
+ force=[200])
+ bc.setJointMotorControlMultiDof(humanoid,
+ rightKnee,
+ controlMode,
+ targetPosition=pose._rightKneeRot,
+ positionGain=kp,
+ force=[150])
+ bc.setJointMotorControlMultiDof(humanoid,
+ rightAnkle,
+ controlMode,
+ targetPosition=pose._rightAnkleRot,
+ positionGain=kp,
+ force=[90])
+ bc.setJointMotorControlMultiDof(humanoid,
+ rightShoulder,
+ controlMode,
+ targetPosition=pose._rightShoulderRot,
+ positionGain=kp,
+ force=[100])
+ bc.setJointMotorControlMultiDof(humanoid,
+ rightElbow,
+ controlMode,
+ targetPosition=pose._rightElbowRot,
+ positionGain=kp,
+ force=[60])
+ bc.setJointMotorControlMultiDof(humanoid,
+ leftHip,
+ controlMode,
+ targetPosition=pose._leftHipRot,
+ positionGain=kp,
+ force=[200])
+ bc.setJointMotorControlMultiDof(humanoid,
+ leftKnee,
+ controlMode,
+ targetPosition=pose._leftKneeRot,
+ positionGain=kp,
+ force=[150])
+ bc.setJointMotorControlMultiDof(humanoid,
+ leftAnkle,
+ controlMode,
+ targetPosition=pose._leftAnkleRot,
+ positionGain=kp,
+ force=[90])
+ bc.setJointMotorControlMultiDof(humanoid,
+ leftShoulder,
+ controlMode,
+ targetPosition=pose._leftShoulderRot,
+ positionGain=kp,
+ force=[100])
+ bc.setJointMotorControlMultiDof(humanoid,
+ leftElbow,
+ controlMode,
+ targetPosition=pose._leftElbowRot,
+ positionGain=kp,
+ force=[60])
#debug space
#if (False):
@@ -467,51 +563,58 @@ class Humanoid(object):
# jsm = bc.getJointStateMultiDof(self._humanoid, j)
# if (len(jsm[0])>0):
# bc.resetJointStateMultiDof(self._humanoidDebug,j,jsm[0])
-
+
def GetState(self):
stateVector = []
phase = self.GetPhase()
#print("phase=",phase)
stateVector.append(phase)
-
- rootTransPos, rootTransOrn=self.BuildOriginTrans()
- basePos,baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
-
- rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, basePos,[0,0,0,1])
+
+ rootTransPos, rootTransOrn = self.BuildOriginTrans()
+ basePos, baseOrn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
+
+ rootPosRel, dummy = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, [0, 0, 0, 1])
#print("!!!rootPosRel =",rootPosRel )
#print("rootTransPos=",rootTransPos)
#print("basePos=",basePos)
- localPos,localOrn = self._pybullet_client.multiplyTransforms( rootTransPos, rootTransOrn , basePos,baseOrn )
-
- localPos=[localPos[0]-rootPosRel[0],localPos[1]-rootPosRel[1],localPos[2]-rootPosRel[2]]
+ localPos, localOrn = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn,
+ basePos, baseOrn)
+
+ localPos = [
+ localPos[0] - rootPosRel[0], localPos[1] - rootPosRel[1], localPos[2] - rootPosRel[2]
+ ]
#print("localPos=",localPos)
-
+
stateVector.append(rootPosRel[1])
-
- self.pb2dmJoints=[0,1,2,9,10,11,3,4,5,12,13,14,6,7,8]
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._humanoid)):
+
+ self.pb2dmJoints = [0, 1, 2, 9, 10, 11, 3, 4, 5, 12, 13, 14, 6, 7, 8]
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._humanoid)):
j = self.pb2dmJoints[pbJoint]
#print("joint order:",j)
ls = self._pybullet_client.getLinkState(self._humanoid, j, computeForwardKinematics=True)
linkPos = ls[0]
linkOrn = ls[1]
- linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(rootTransPos, rootTransOrn, linkPos,linkOrn)
- if (linkOrnLocal[3]<0):
- linkOrnLocal=[-linkOrnLocal[0],-linkOrnLocal[1],-linkOrnLocal[2],-linkOrnLocal[3]]
- linkPosLocal=[linkPosLocal[0]-rootPosRel[0],linkPosLocal[1]-rootPosRel[1],linkPosLocal[2]-rootPosRel[2]]
+ linkPosLocal, linkOrnLocal = self._pybullet_client.multiplyTransforms(
+ rootTransPos, rootTransOrn, linkPos, linkOrn)
+ if (linkOrnLocal[3] < 0):
+ linkOrnLocal = [-linkOrnLocal[0], -linkOrnLocal[1], -linkOrnLocal[2], -linkOrnLocal[3]]
+ linkPosLocal = [
+ linkPosLocal[0] - rootPosRel[0], linkPosLocal[1] - rootPosRel[1],
+ linkPosLocal[2] - rootPosRel[2]
+ ]
for l in linkPosLocal:
stateVector.append(l)
-
+
#re-order the quaternion, DeepMimic uses w,x,y,z
stateVector.append(linkOrnLocal[3])
stateVector.append(linkOrnLocal[0])
stateVector.append(linkOrnLocal[1])
stateVector.append(linkOrnLocal[2])
-
-
- for pbJoint in range (self._pybullet_client.getNumJoints(self._humanoid)):
+
+ for pbJoint in range(self._pybullet_client.getNumJoints(self._humanoid)):
j = self.pb2dmJoints[pbJoint]
ls = self._pybullet_client.getLinkState(self._humanoid, j, computeLinkVelocity=True)
linkLinVel = ls[6]
@@ -520,19 +623,18 @@ class Humanoid(object):
stateVector.append(l)
for l in linkAngVel:
stateVector.append(l)
-
- #print("stateVector len=",len(stateVector))
+
+ #print("stateVector len=",len(stateVector))
#for st in range (len(stateVector)):
# print("state[",st,"]=",stateVector[st])
return stateVector
-
-
+
def GetReward(self):
#from DeepMimic double cSceneImitate::CalcRewardImitate
pose_w = 0.5
vel_w = 0.05
- end_eff_w = 0 #0.15
- root_w = 0 #0.2
+ end_eff_w = 0 #0.15
+ root_w = 0 #0.2
com_w = 0.1
total_w = pose_w + vel_w + end_eff_w + root_w + com_w
@@ -557,9 +659,9 @@ class Humanoid(object):
root_err = 0
com_err = 0
heading_err = 0
-
+
#create a mimic reward, comparing the dynamics humanoid with a kinematic one
-
+
pose = self.InitializePoseFromMotionData()
#print("self._kinematicHumanoid=",self._kinematicHumanoid)
#print("kinematicHumanoid #joints=",self.kin_client.getNumJoints(self._kinematicHumanoid))
@@ -588,46 +690,49 @@ class Humanoid(object):
#tVector root_ang_vel0 = cKinTree::GetRootAngVel(joint_mat, vel0);
#tVector root_ang_vel1 = cKinTree::GetRootAngVel(joint_mat, vel1);
- mJointWeights = [0.20833,0.10416, 0.0625, 0.10416,
- 0.0625, 0.041666666666666671, 0.0625, 0.0416,
- 0.00, 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000]
-
+ mJointWeights = [
+ 0.20833, 0.10416, 0.0625, 0.10416, 0.0625, 0.041666666666666671, 0.0625, 0.0416, 0.00,
+ 0.10416, 0.0625, 0.0416, 0.0625, 0.0416, 0.0000
+ ]
+
num_end_effs = 0
num_joints = 15
-
+
root_rot_w = mJointWeights[root_id]
#pose_err += root_rot_w * cKinTree::CalcRootRotErr(joint_mat, pose0, pose1)
#vel_err += root_rot_w * cKinTree::CalcRootAngVelErr(joint_mat, vel0, vel1)
- for j in range (num_joints):
+ for j in range(num_joints):
curr_pose_err = 0
curr_vel_err = 0
- w = mJointWeights[j];
-
+ w = mJointWeights[j]
+
simJointInfo = self._pybullet_client.getJointStateMultiDof(self._humanoid, j)
-
+
#print("simJointInfo.pos=",simJointInfo[0])
#print("simJointInfo.vel=",simJointInfo[1])
- kinJointInfo = self.kin_client.getJointStateMultiDof(self._kinematicHumanoid,j)
+ kinJointInfo = self.kin_client.getJointStateMultiDof(self._kinematicHumanoid, j)
#print("kinJointInfo.pos=",kinJointInfo[0])
#print("kinJointInfo.vel=",kinJointInfo[1])
- if (len(simJointInfo[0])==1):
- angle = simJointInfo[0][0]-kinJointInfo[0][0]
- curr_pose_err = angle*angle
- velDiff = simJointInfo[1][0]-kinJointInfo[1][0]
- curr_vel_err = velDiff*velDiff
- if (len(simJointInfo[0])==4):
+ if (len(simJointInfo[0]) == 1):
+ angle = simJointInfo[0][0] - kinJointInfo[0][0]
+ curr_pose_err = angle * angle
+ velDiff = simJointInfo[1][0] - kinJointInfo[1][0]
+ curr_vel_err = velDiff * velDiff
+ if (len(simJointInfo[0]) == 4):
#print("quaternion diff")
- diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0],kinJointInfo[0])
- axis,angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
- curr_pose_err = angle*angle
- diffVel = [simJointInfo[1][0]-kinJointInfo[1][0],simJointInfo[1][1]-kinJointInfo[1][1],simJointInfo[1][2]-kinJointInfo[1][2]]
- curr_vel_err = diffVel[0]*diffVel[0]+diffVel[1]*diffVel[1]+diffVel[2]*diffVel[2]
-
-
+ diffQuat = self._pybullet_client.getDifferenceQuaternion(simJointInfo[0], kinJointInfo[0])
+ axis, angle = self._pybullet_client.getAxisAngleFromQuaternion(diffQuat)
+ curr_pose_err = angle * angle
+ diffVel = [
+ simJointInfo[1][0] - kinJointInfo[1][0], simJointInfo[1][1] - kinJointInfo[1][1],
+ simJointInfo[1][2] - kinJointInfo[1][2]
+ ]
+ curr_vel_err = diffVel[0] * diffVel[0] + diffVel[1] * diffVel[1] + diffVel[2] * diffVel[2]
+
pose_err += w * curr_pose_err
vel_err += w * curr_vel_err
-
+
# bool is_end_eff = sim_char.IsEndEffector(j)
# if (is_end_eff)
# {
@@ -657,7 +762,7 @@ class Humanoid(object):
#root_pos0[1] -= root_ground_h0
#root_pos1[1] -= root_ground_h1
#root_pos_err = (root_pos0 - root_pos1).squaredNorm()
- #
+ #
#root_rot_err = cMathUtil::QuatDiffTheta(root_rot0, root_rot1)
#root_rot_err *= root_rot_err
@@ -669,7 +774,7 @@ class Humanoid(object):
# + 0.01 * root_vel_err
# + 0.001 * root_ang_vel_err
#com_err = 0.1 * (com_vel1_world - com_vel0_world).squaredNorm()
-
+
#print("pose_err=",pose_err)
#print("vel_err=",vel_err)
pose_reward = math.exp(-err_scale * pose_scale * pose_err)
@@ -682,10 +787,9 @@ class Humanoid(object):
#print("reward = %f (pose_reward=%f, vel_reward=%f, end_eff_reward=%f, root_reward=%f, com_reward=%f)\n", reward,
# pose_reward,vel_reward,end_eff_reward, root_reward, com_reward);
-
+
return reward
def GetBasePosition(self):
- pos,orn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
+ pos, orn = self._pybullet_client.getBasePositionAndOrientation(self._humanoid)
return pos
-
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/inverse_kinematics.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/inverse_kinematics.py
index 74f7686b7..5d00c5a4d 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/inverse_kinematics.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/inverse_kinematics.py
@@ -9,142 +9,138 @@ from transformation import *
from pyquaternion import Quaternion
+
def get_angle(vec1, vec2):
- cos_theta = np.dot(vec1, vec2)/(np.linalg.norm(vec1) * np.linalg.norm(vec2))
- return acos(cos_theta)
+ cos_theta = np.dot(vec1, vec2) / (np.linalg.norm(vec1) * np.linalg.norm(vec2))
+ return acos(cos_theta)
def get_quaternion(ox, oy, oz, x, y, z):
- # given transformed axis in x-y-z order return a quaternion
- ox /= np.linalg.norm(ox)
- oy /= np.linalg.norm(oy)
- oz /= np.linalg.norm(oz)
+ # given transformed axis in x-y-z order return a quaternion
+ ox /= np.linalg.norm(ox)
+ oy /= np.linalg.norm(oy)
+ oz /= np.linalg.norm(oz)
- set1 = np.vstack((ox,oy,oz))
+ set1 = np.vstack((ox, oy, oz))
- x /= np.linalg.norm(x)
- y /= np.linalg.norm(y)
- z /= np.linalg.norm(z)
+ x /= np.linalg.norm(x)
+ y /= np.linalg.norm(y)
+ z /= np.linalg.norm(z)
- set2 = np.vstack((x,y,z))
- rot_mat = superimposition_matrix(set1, set2, scale=False, usesvd=True)
- rot_qua = quaternion_from_matrix(rot_mat)
+ set2 = np.vstack((x, y, z))
+ rot_mat = superimposition_matrix(set1, set2, scale=False, usesvd=True)
+ rot_qua = quaternion_from_matrix(rot_mat)
- return rot_qua
+ return rot_qua
# 3D coord to deepmimic rotations
def coord_to_rot(frameNum, frame, frame_duration):
- eps = 0.001
- axis_rotate_rate = 0.3
-
- frame = np.array(frame)
- tmp = [[] for i in range(15)]
- # duration of frame in seconds (1D),
- tmp[0] = [frame_duration]
- # root position (3D),
- tmp[1] = frame[0]
- # root rotation (4D),
- root_y = (frame[7] - frame[0])
- root_z = (frame[1] - frame[0])
- root_x = np.cross(root_y, root_z)
-
- x = np.array([1.0,0,0])
- y = np.array([0,1.0,0])
- z = np.array([0,0,1.0])
-
- rot_qua = get_quaternion(root_x, root_y, root_z, x, y, z)
- tmp[2] = list(rot_qua)
-
- # chest rotation (4D),
- chest_y = (frame[8] - frame[7])
- chest_z = (frame[14] - frame[8])
- chest_x = np.cross(chest_y, chest_z)
- rot_qua = get_quaternion(chest_x, chest_y, chest_z, root_x, root_y, root_z)
- tmp[3] = list(rot_qua)
-
- # neck rotation (4D),
- neck_y = (frame[10] - frame[8])
- neck_z = np.cross(frame[10]-frame[9], frame[8]-frame[9])
- neck_x = np.cross(neck_y, neck_z)
- rot_qua = get_quaternion(neck_x, neck_y, neck_z, chest_x, chest_y, chest_z)
- tmp[4] = list(rot_qua)
-
- # right hip rotation (4D),
- r_hip_y = (frame[1] - frame[2])
- r_hip_z = np.cross(frame[1]-frame[2], frame[3]-frame[2])
- r_hip_x = np.cross(r_hip_y, r_hip_z)
- rot_qua = get_quaternion(r_hip_x, r_hip_y, r_hip_z, root_x, root_y, root_z)
- tmp[5] = list(rot_qua)
-
- # right knee rotation (1D),
- vec1 = frame[1] - frame[2]
- vec2 = frame[3] - frame[2]
- angle1 = get_angle(vec1, vec2)
- tmp[6] = [angle1-pi]
-
- # right ankle rotation (4D),
- tmp[7] = [1,0,0,0]
-
- # right shoulder rotation (4D),
- r_shou_y = (frame[14] - frame[15])
- r_shou_z = np.cross(frame[16]-frame[15], frame[14]-frame[15])
- r_shou_x = np.cross(r_shou_y, r_shou_z)
- rot_qua = get_quaternion(r_shou_x, r_shou_y, r_shou_z, chest_x, chest_y, chest_z)
- tmp[8] = list(rot_qua)
-
- # right elbow rotation (1D),
- vec1 = frame[14] - frame[15]
- vec2 = frame[16] - frame[15]
- angle1 = get_angle(vec1, vec2)
- tmp[9] = [pi-angle1]
-
- # left hip rotation (4D),
- l_hip_y = (frame[4] - frame[5])
- l_hip_z = np.cross(frame[4]-frame[5], frame[6]-frame[5])
- l_hip_x = np.cross(l_hip_y, l_hip_z)
- rot_qua = get_quaternion(l_hip_x, l_hip_y, l_hip_z, root_x, root_y, root_z)
- tmp[10] = list(rot_qua)
-
- # left knee rotation (1D),
- vec1 = frame[4] - frame[5]
- vec2 = frame[6] - frame[5]
- angle1 = get_angle(vec1, vec2)
- tmp[11] = [angle1-pi]
-
- # left ankle rotation (4D),
- tmp[12] = [1,0,0,0]
-
- # left shoulder rotation (4D),
- l_shou_y = (frame[11] - frame[12])
- l_shou_z = np.cross(frame[13]-frame[12], frame[11]-frame[12])
- l_shou_x = np.cross(l_shou_y, l_shou_z)
- rot_qua = get_quaternion(l_shou_x, l_shou_y, l_shou_z, chest_x, chest_y, chest_z)
- tmp[13] = list(rot_qua)
-
- # left elbow rotation (1D)
- vec1 = frame[11] - frame[12]
- vec2 = frame[13] - frame[12]
- angle1 = get_angle(vec1, vec2)
- tmp[14] = [pi-angle1]
-
- ret = []
- for i in tmp:
- ret += list(i)
- return np.array(ret)
+ eps = 0.001
+ axis_rotate_rate = 0.3
+
+ frame = np.array(frame)
+ tmp = [[] for i in range(15)]
+ # duration of frame in seconds (1D),
+ tmp[0] = [frame_duration]
+ # root position (3D),
+ tmp[1] = frame[0]
+ # root rotation (4D),
+ root_y = (frame[7] - frame[0])
+ root_z = (frame[1] - frame[0])
+ root_x = np.cross(root_y, root_z)
+
+ x = np.array([1.0, 0, 0])
+ y = np.array([0, 1.0, 0])
+ z = np.array([0, 0, 1.0])
+
+ rot_qua = get_quaternion(root_x, root_y, root_z, x, y, z)
+ tmp[2] = list(rot_qua)
+
+ # chest rotation (4D),
+ chest_y = (frame[8] - frame[7])
+ chest_z = (frame[14] - frame[8])
+ chest_x = np.cross(chest_y, chest_z)
+ rot_qua = get_quaternion(chest_x, chest_y, chest_z, root_x, root_y, root_z)
+ tmp[3] = list(rot_qua)
+
+ # neck rotation (4D),
+ neck_y = (frame[10] - frame[8])
+ neck_z = np.cross(frame[10] - frame[9], frame[8] - frame[9])
+ neck_x = np.cross(neck_y, neck_z)
+ rot_qua = get_quaternion(neck_x, neck_y, neck_z, chest_x, chest_y, chest_z)
+ tmp[4] = list(rot_qua)
+
+ # right hip rotation (4D),
+ r_hip_y = (frame[1] - frame[2])
+ r_hip_z = np.cross(frame[1] - frame[2], frame[3] - frame[2])
+ r_hip_x = np.cross(r_hip_y, r_hip_z)
+ rot_qua = get_quaternion(r_hip_x, r_hip_y, r_hip_z, root_x, root_y, root_z)
+ tmp[5] = list(rot_qua)
+
+ # right knee rotation (1D),
+ vec1 = frame[1] - frame[2]
+ vec2 = frame[3] - frame[2]
+ angle1 = get_angle(vec1, vec2)
+ tmp[6] = [angle1 - pi]
+
+ # right ankle rotation (4D),
+ tmp[7] = [1, 0, 0, 0]
+
+ # right shoulder rotation (4D),
+ r_shou_y = (frame[14] - frame[15])
+ r_shou_z = np.cross(frame[16] - frame[15], frame[14] - frame[15])
+ r_shou_x = np.cross(r_shou_y, r_shou_z)
+ rot_qua = get_quaternion(r_shou_x, r_shou_y, r_shou_z, chest_x, chest_y, chest_z)
+ tmp[8] = list(rot_qua)
+
+ # right elbow rotation (1D),
+ vec1 = frame[14] - frame[15]
+ vec2 = frame[16] - frame[15]
+ angle1 = get_angle(vec1, vec2)
+ tmp[9] = [pi - angle1]
+
+ # left hip rotation (4D),
+ l_hip_y = (frame[4] - frame[5])
+ l_hip_z = np.cross(frame[4] - frame[5], frame[6] - frame[5])
+ l_hip_x = np.cross(l_hip_y, l_hip_z)
+ rot_qua = get_quaternion(l_hip_x, l_hip_y, l_hip_z, root_x, root_y, root_z)
+ tmp[10] = list(rot_qua)
+
+ # left knee rotation (1D),
+ vec1 = frame[4] - frame[5]
+ vec2 = frame[6] - frame[5]
+ angle1 = get_angle(vec1, vec2)
+ tmp[11] = [angle1 - pi]
+
+ # left ankle rotation (4D),
+ tmp[12] = [1, 0, 0, 0]
+
+ # left shoulder rotation (4D),
+ l_shou_y = (frame[11] - frame[12])
+ l_shou_z = np.cross(frame[13] - frame[12], frame[11] - frame[12])
+ l_shou_x = np.cross(l_shou_y, l_shou_z)
+ rot_qua = get_quaternion(l_shou_x, l_shou_y, l_shou_z, chest_x, chest_y, chest_z)
+ tmp[13] = list(rot_qua)
+
+ # left elbow rotation (1D)
+ vec1 = frame[11] - frame[12]
+ vec2 = frame[13] - frame[12]
+ angle1 = get_angle(vec1, vec2)
+ tmp[14] = [pi - angle1]
+
+ ret = []
+ for i in tmp:
+ ret += list(i)
+ return np.array(ret)
+
# In[6]:
def coord_seq_to_rot_seq(coord_seq, frame_duration):
- ret = []
- for i in range(len(coord_seq)):
- tmp = coord_to_rot( i, coord_seq[i], frame_duration)
- ret.append(list(tmp))
- return ret
-
-
-
-
-
-
+ ret = []
+ for i in range(len(coord_seq)):
+ tmp = coord_to_rot(i, coord_seq[i], frame_duration)
+ ret.append(list(tmp))
+ return ret
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/mocap_dataset.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/mocap_dataset.py
index 18bc27ae4..c297220db 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/mocap_dataset.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/mocap_dataset.py
@@ -1,36 +1,37 @@
import numpy as np
from skeleton import Skeleton
+
class MocapDataset:
- def __init__(self, fps, skeleton):
- self._skeleton = skeleton
- self._fps = fps
- self._data = None # Must be filled by subclass
- self._cameras = None # Must be filled by subclass
-
- def remove_joints(self, joints_to_remove):
- kept_joints = self._skeleton.remove_joints(joints_to_remove)
- for subject in self._data.keys():
- for action in self._data[subject].keys():
- s = self._data[subject][action]
- s['positions'] = s['positions'][:, kept_joints]
-
-
- def __getitem__(self, key):
- return self._data[key]
-
- def subjects(self):
- return self._data.keys()
-
- def fps(self):
- return self._fps
-
- def skeleton(self):
- return self._skeleton
-
- def cameras(self):
- return self._cameras
-
- def supports_semi_supervised(self):
- # This method can be overridden
- return False
+
+ def __init__(self, fps, skeleton):
+ self._skeleton = skeleton
+ self._fps = fps
+ self._data = None # Must be filled by subclass
+ self._cameras = None # Must be filled by subclass
+
+ def remove_joints(self, joints_to_remove):
+ kept_joints = self._skeleton.remove_joints(joints_to_remove)
+ for subject in self._data.keys():
+ for action in self._data[subject].keys():
+ s = self._data[subject][action]
+ s['positions'] = s['positions'][:, kept_joints]
+
+ def __getitem__(self, key):
+ return self._data[key]
+
+ def subjects(self):
+ return self._data.keys()
+
+ def fps(self):
+ return self._fps
+
+ def skeleton(self):
+ return self._skeleton
+
+ def cameras(self):
+ return self._cameras
+
+ def supports_semi_supervised(self):
+ # This method can be overridden
+ return False
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/quaternion.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/quaternion.py
index e4e9a7753..c972846ce 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/quaternion.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/quaternion.py
@@ -1,30 +1,31 @@
import numpy as np
+
def qrot(q, v):
- """
+ """
Rotate vector(s) v about the rotation described by quaternion(s) q.
Expects a tensor of shape (*, 4) for q and a tensor of shape (*, 3) for v,
where * denotes any number of dimensions.
Returns a tensor of shape (*, 3).
"""
- assert q.shape[-1] == 4
- assert v.shape[-1] == 3
- assert q.shape[:-1] == v.shape[:-1]
+ assert q.shape[-1] == 4
+ assert v.shape[-1] == 3
+ assert q.shape[:-1] == v.shape[:-1]
+
+ qvec = q[..., 1:]
+
+ uv = np.cross(qvec, v)
+ uuv = np.cross(qvec, uv)
+
+ return (v + 2 * (q[..., :1] * uv + uuv))
- qvec = q[..., 1:]
- uv = np.cross(qvec, v)
- uuv = np.cross(qvec, uv)
-
- return (v + 2 * (q[..., :1] * uv + uuv))
-
def qinverse(q, inplace=False):
- # We assume the quaternion to be normalized
- if inplace:
- q[..., 1:] *= -1
- return q
- else:
- w = q[..., :1]
- xyz = q[..., 1:]
- return np.hstack((w, -xyz))
- \ No newline at end of file
+ # We assume the quaternion to be normalized
+ if inplace:
+ q[..., 1:] *= -1
+ return q
+ else:
+ w = q[..., :1]
+ xyz = q[..., 1:]
+ return np.hstack((w, -xyz))
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/render_reference.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/render_reference.py
index c3882bf07..61fe8878d 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/render_reference.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/render_reference.py
@@ -1,7 +1,7 @@
-import os, inspect
+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)
print('parent:', parentdir)
@@ -10,7 +10,6 @@ import pybullet
import time
import random
-
from pybullet_utils.bullet_client import BulletClient
from deep_mimic.env.motion_capture_data import MotionCaptureData
@@ -26,21 +25,28 @@ import pybullet as p
import numpy as np
import argparse
-
-
parser = argparse.ArgumentParser(description='Arguments for loading reference for learning.')
# General arguments
-parser.add_argument('--dataset_path', default='data/data_3d_h36m.npz', type=str, help='target dataset') # h36m or humaneva
-parser.add_argument('--json_path', default='data/Walking.json', type=str, help='json file path for storing the deepmimic-format json created by inverse-kinect.')
+parser.add_argument('--dataset_path',
+ default='data/data_3d_h36m.npz',
+ type=str,
+ help='target dataset') # h36m or humaneva
+parser.add_argument(
+ '--json_path',
+ default='data/Walking.json',
+ type=str,
+ help='json file path for storing the deepmimic-format json created by inverse-kinect.')
parser.add_argument('--fps', default=24, type=int, help='frame per second')
parser.add_argument('--subject', default='S11', type=str, help='camera subject.')
-parser.add_argument('--action', default='Walking', type=str, help='name of the action.')
-parser.add_argument('--loop', default='wrap', type=str, help='loop information in deepmimic, wrap or none.')
+parser.add_argument('--action', default='Walking', type=str, help='name of the action.')
+parser.add_argument('--loop',
+ default='wrap',
+ type=str,
+ help='loop information in deepmimic, wrap or none.')
parser.add_argument('--draw_gt', action='store_true', help='draw ground truth or not.')
-args = parser.parse_args()
-
+args = parser.parse_args()
dataset_path = args.dataset_path
json_path = args.json_path
@@ -52,93 +58,75 @@ draw_gt = args.draw_gt
def draw_ground_truth(coord_seq, frame, duration, shift):
- global joint_info
- joint = coord_seq[frame]
- shift = np.array(shift)
- for i in range(1, 17):
- # print(x[11], x[14])
- joint_fa = joint_info['father'][i]
- if joint_info['side'][i] == 'right':
- p.addUserDebugLine(lineFromXYZ=joint[i]+shift,
- lineToXYZ=joint[joint_fa]+shift,
- lineColorRGB=(255,0,0),
- lineWidth=1,
- lifeTime=duration)
- else:
- p.addUserDebugLine(lineFromXYZ=joint[i]+shift,
- lineToXYZ=joint[joint_fa]+shift,
- lineColorRGB=(0,0,0),
- lineWidth=1,
- lifeTime=duration)
+ global joint_info
+ joint = coord_seq[frame]
+ shift = np.array(shift)
+ for i in range(1, 17):
+ # print(x[11], x[14])
+ joint_fa = joint_info['father'][i]
+ if joint_info['side'][i] == 'right':
+ p.addUserDebugLine(lineFromXYZ=joint[i] + shift,
+ lineToXYZ=joint[joint_fa] + shift,
+ lineColorRGB=(255, 0, 0),
+ lineWidth=1,
+ lifeTime=duration)
+ else:
+ p.addUserDebugLine(lineFromXYZ=joint[i] + shift,
+ lineToXYZ=joint[joint_fa] + shift,
+ lineColorRGB=(0, 0, 0),
+ lineWidth=1,
+ lifeTime=duration)
dataset = init_fb_h36m_dataset(dataset_path)
-ground_truth = pose3D_from_fb_h36m(dataset,
- subject = subject,
- action = action,
- shift = [1.0,0.0,0.0])
-
-rot_seq = coord_seq_to_rot_seq(coord_seq = ground_truth,
- frame_duration = 1/fps)
-
-
-rot_seq_to_deepmimic_json( rot_seq = rot_seq,
- loop = loop,
- json_path = json_path)
+ground_truth = pose3D_from_fb_h36m(dataset, subject=subject, action=action, shift=[1.0, 0.0, 0.0])
+rot_seq = coord_seq_to_rot_seq(coord_seq=ground_truth, frame_duration=1 / fps)
+rot_seq_to_deepmimic_json(rot_seq=rot_seq, loop=loop, json_path=json_path)
bc = BulletClient(connection_mode=pybullet.GUI)
bc.setAdditionalSearchPath(pybullet_data.getDataPath())
-bc.configureDebugVisualizer(bc.COV_ENABLE_Y_AXIS_UP,1)
-bc.setGravity(0,-9.8,0)
-motion=MotionCaptureData()
+bc.configureDebugVisualizer(bc.COV_ENABLE_Y_AXIS_UP, 1)
+bc.setGravity(0, -9.8, 0)
+motion = MotionCaptureData()
motionPath = json_path
motion.Load(motionPath)
print("numFrames = ", motion.NumFrames())
+simTimeId = bc.addUserDebugParameter("simTime", 0, motion.NumFrames() - 1.1, 0)
+y2zOrn = bc.getQuaternionFromEuler([-1.57, 0, 0])
+bc.loadURDF("plane.urdf", [0, -0.04, 0], y2zOrn)
-simTimeId= bc.addUserDebugParameter("simTime",0,motion.NumFrames()-1.1,0)
-
-y2zOrn = bc.getQuaternionFromEuler([-1.57,0,0])
-bc.loadURDF("plane.urdf",[0,-0.04,0], y2zOrn)
-
-humanoid = Humanoid(bc, motion, [0,0,0]) #这是初始位置的坐标
-
-
+humanoid = Humanoid(bc, motion, [0, 0, 0]) #这是初始位置的坐标
print(p.getBasePositionAndOrientation(humanoid._humanoid))
-
-
simTime = 0
keyFrameDuration = motion.KeyFrameDuraction()
-print("keyFrameDuration=",keyFrameDuration)
+print("keyFrameDuration=", keyFrameDuration)
for utNum in range(motion.NumFrames()):
- bc.stepSimulation()
- humanoid.RenderReference(utNum * keyFrameDuration)
- if draw_gt:
- draw_ground_truth(coord_seq = ground_truth,
- frame = utNum,
- duration = keyFrameDuration,
- shift = [-1.0, 0.0, 1.0])
- time.sleep(0.001)
+ bc.stepSimulation()
+ humanoid.RenderReference(utNum * keyFrameDuration)
+ if draw_gt:
+ draw_ground_truth(coord_seq=ground_truth,
+ frame=utNum,
+ duration=keyFrameDuration,
+ shift=[-1.0, 0.0, 1.0])
+ time.sleep(0.001)
stage = 0
-
def Reset(humanoid):
- global simTime
- humanoid.Reset()
- simTime = 0
- humanoid.SetSimTime(simTime)
- pose = humanoid.InitializePoseFromMotionData()
- humanoid.ApplyPose(pose, True, True, humanoid._humanoid,bc)
+ global simTime
+ humanoid.Reset()
+ simTime = 0
+ humanoid.SetSimTime(simTime)
+ pose = humanoid.InitializePoseFromMotionData()
+ humanoid.ApplyPose(pose, True, True, humanoid._humanoid, bc)
Reset(humanoid)
p.disconnect()
-
-
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/skeleton.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/skeleton.py
index fa6d1e622..6e8fe8ba6 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/skeleton.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/skeleton.py
@@ -1,81 +1,82 @@
import numpy as np
+
class Skeleton:
- def __init__(self, parents, joints_left, joints_right):
- assert len(joints_left) == len(joints_right)
-
- self._parents = np.array(parents)
- self._joints_left = joints_left
- self._joints_right = joints_right
- self._compute_metadata()
-
- def num_joints(self):
- return len(self._parents)
-
- def parents(self):
- return self._parents
-
- def has_children(self):
- return self._has_children
-
- def children(self):
- return self._children
-
- def remove_joints(self, joints_to_remove):
- """
+
+ def __init__(self, parents, joints_left, joints_right):
+ assert len(joints_left) == len(joints_right)
+
+ self._parents = np.array(parents)
+ self._joints_left = joints_left
+ self._joints_right = joints_right
+ self._compute_metadata()
+
+ def num_joints(self):
+ return len(self._parents)
+
+ def parents(self):
+ return self._parents
+
+ def has_children(self):
+ return self._has_children
+
+ def children(self):
+ return self._children
+
+ def remove_joints(self, joints_to_remove):
+ """
Remove the joints specified in 'joints_to_remove'.
"""
- valid_joints = []
- for joint in range(len(self._parents)):
- if joint not in joints_to_remove:
- valid_joints.append(joint)
-
- for i in range(len(self._parents)):
- while self._parents[i] in joints_to_remove:
- self._parents[i] = self._parents[self._parents[i]]
-
- index_offsets = np.zeros(len(self._parents), dtype=int)
- new_parents = []
- for i, parent in enumerate(self._parents):
- if i not in joints_to_remove:
- new_parents.append(parent - index_offsets[parent])
- else:
- index_offsets[i:] += 1
- self._parents = np.array(new_parents)
-
-
- if self._joints_left is not None:
- new_joints_left = []
- for joint in self._joints_left:
- if joint in valid_joints:
- new_joints_left.append(joint - index_offsets[joint])
- self._joints_left = new_joints_left
- if self._joints_right is not None:
- new_joints_right = []
- for joint in self._joints_right:
- if joint in valid_joints:
- new_joints_right.append(joint - index_offsets[joint])
- self._joints_right = new_joints_right
-
- self._compute_metadata()
-
- return valid_joints
-
- def joints_left(self):
- return self._joints_left
-
- def joints_right(self):
- return self._joints_right
-
- def _compute_metadata(self):
- self._has_children = np.zeros(len(self._parents)).astype(bool)
- for i, parent in enumerate(self._parents):
- if parent != -1:
- self._has_children[parent] = True
-
- self._children = []
- for i, parent in enumerate(self._parents):
- self._children.append([])
- for i, parent in enumerate(self._parents):
- if parent != -1:
- self._children[parent].append(i)
+ valid_joints = []
+ for joint in range(len(self._parents)):
+ if joint not in joints_to_remove:
+ valid_joints.append(joint)
+
+ for i in range(len(self._parents)):
+ while self._parents[i] in joints_to_remove:
+ self._parents[i] = self._parents[self._parents[i]]
+
+ index_offsets = np.zeros(len(self._parents), dtype=int)
+ new_parents = []
+ for i, parent in enumerate(self._parents):
+ if i not in joints_to_remove:
+ new_parents.append(parent - index_offsets[parent])
+ else:
+ index_offsets[i:] += 1
+ self._parents = np.array(new_parents)
+
+ if self._joints_left is not None:
+ new_joints_left = []
+ for joint in self._joints_left:
+ if joint in valid_joints:
+ new_joints_left.append(joint - index_offsets[joint])
+ self._joints_left = new_joints_left
+ if self._joints_right is not None:
+ new_joints_right = []
+ for joint in self._joints_right:
+ if joint in valid_joints:
+ new_joints_right.append(joint - index_offsets[joint])
+ self._joints_right = new_joints_right
+
+ self._compute_metadata()
+
+ return valid_joints
+
+ def joints_left(self):
+ return self._joints_left
+
+ def joints_right(self):
+ return self._joints_right
+
+ def _compute_metadata(self):
+ self._has_children = np.zeros(len(self._parents)).astype(bool)
+ for i, parent in enumerate(self._parents):
+ if parent != -1:
+ self._has_children[parent] = True
+
+ self._children = []
+ for i, parent in enumerate(self._parents):
+ self._children.append([])
+ for i, parent in enumerate(self._parents):
+ if parent != -1:
+ self._children[parent].append(i)
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/transformation.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/transformation.py
index f9745fe6e..e4807b538 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/transformation.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mocap/transformation.py
@@ -1,13 +1,12 @@
from __future__ import division, print_function
-
import math
import numpy
def identity_matrix():
- """Return 4x4 identity/unit matrix.
+ """Return 4x4 identity/unit matrix.
>>> I = identity_matrix()
>>> numpy.allclose(I, numpy.dot(I, I))
@@ -18,24 +17,24 @@ def identity_matrix():
True
"""
- return numpy.identity(4)
+ return numpy.identity(4)
def translation_matrix(direction):
- """Return matrix to translate by direction vector.
+ """Return matrix to translate by direction vector.
>>> v = numpy.random.random(3) - 0.5
>>> numpy.allclose(v, translation_matrix(v)[:3, 3])
True
"""
- M = numpy.identity(4)
- M[:3, 3] = direction[:3]
- return M
+ M = numpy.identity(4)
+ M[:3, 3] = direction[:3]
+ return M
def translation_from_matrix(matrix):
- """Return translation vector from translation matrix.
+ """Return translation vector from translation matrix.
>>> v0 = numpy.random.random(3) - 0.5
>>> v1 = translation_from_matrix(translation_matrix(v0))
@@ -43,11 +42,11 @@ def translation_from_matrix(matrix):
True
"""
- return numpy.array(matrix, copy=False)[:3, 3].copy()
+ return numpy.array(matrix, copy=False)[:3, 3].copy()
def reflection_matrix(point, normal):
- """Return matrix to mirror at plane defined by point and normal vector.
+ """Return matrix to mirror at plane defined by point and normal vector.
>>> v0 = numpy.random.random(4) - 0.5
>>> v0[3] = 1.
@@ -65,15 +64,15 @@ def reflection_matrix(point, normal):
True
"""
- normal = unit_vector(normal[:3])
- M = numpy.identity(4)
- M[:3, :3] -= 2.0 * numpy.outer(normal, normal)
- M[:3, 3] = (2.0 * numpy.dot(point[:3], normal)) * normal
- return M
+ normal = unit_vector(normal[:3])
+ M = numpy.identity(4)
+ M[:3, :3] -= 2.0 * numpy.outer(normal, normal)
+ M[:3, 3] = (2.0 * numpy.dot(point[:3], normal)) * normal
+ return M
def reflection_from_matrix(matrix):
- """Return mirror plane point and normal vector from reflection matrix.
+ """Return mirror plane point and normal vector from reflection matrix.
>>> v0 = numpy.random.random(3) - 0.5
>>> v1 = numpy.random.random(3) - 0.5
@@ -84,25 +83,25 @@ def reflection_from_matrix(matrix):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)
- # normal: unit eigenvector corresponding to eigenvalue -1
- w, V = numpy.linalg.eig(M[:3, :3])
- i = numpy.where(abs(numpy.real(w) + 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no unit eigenvector corresponding to eigenvalue -1')
- normal = numpy.real(V[:, i[0]]).squeeze()
- # point: any unit eigenvector corresponding to eigenvalue 1
- w, V = numpy.linalg.eig(M)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
- point = numpy.real(V[:, i[-1]]).squeeze()
- point /= point[3]
- return point, normal
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)
+ # normal: unit eigenvector corresponding to eigenvalue -1
+ w, V = numpy.linalg.eig(M[:3, :3])
+ i = numpy.where(abs(numpy.real(w) + 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no unit eigenvector corresponding to eigenvalue -1')
+ normal = numpy.real(V[:, i[0]]).squeeze()
+ # point: any unit eigenvector corresponding to eigenvalue 1
+ w, V = numpy.linalg.eig(M)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
+ point = numpy.real(V[:, i[-1]]).squeeze()
+ point /= point[3]
+ return point, normal
def rotation_matrix(angle, direction, point=None):
- """Return matrix to rotate about axis defined by point and direction.
+ """Return matrix to rotate about axis defined by point and direction.
>>> R = rotation_matrix(math.pi/2, [0, 0, 1], [1, 0, 0])
>>> numpy.allclose(numpy.dot(R, [0, 0, 0, 1]), [1, -1, 0, 1])
@@ -126,27 +125,26 @@ def rotation_matrix(angle, direction, point=None):
True
"""
- sina = math.sin(angle)
- cosa = math.cos(angle)
- direction = unit_vector(direction[:3])
- # rotation matrix around unit vector
- R = numpy.diag([cosa, cosa, cosa])
- R += numpy.outer(direction, direction) * (1.0 - cosa)
- direction *= sina
- R += numpy.array([[ 0.0, -direction[2], direction[1]],
- [ direction[2], 0.0, -direction[0]],
- [-direction[1], direction[0], 0.0]])
- M = numpy.identity(4)
- M[:3, :3] = R
- if point is not None:
- # rotation not around origin
- point = numpy.array(point[:3], dtype=numpy.float64, copy=False)
- M[:3, 3] = point - numpy.dot(R, point)
- return M
+ sina = math.sin(angle)
+ cosa = math.cos(angle)
+ direction = unit_vector(direction[:3])
+ # rotation matrix around unit vector
+ R = numpy.diag([cosa, cosa, cosa])
+ R += numpy.outer(direction, direction) * (1.0 - cosa)
+ direction *= sina
+ R += numpy.array([[0.0, -direction[2], direction[1]], [direction[2], 0.0, -direction[0]],
+ [-direction[1], direction[0], 0.0]])
+ M = numpy.identity(4)
+ M[:3, :3] = R
+ if point is not None:
+ # rotation not around origin
+ point = numpy.array(point[:3], dtype=numpy.float64, copy=False)
+ M[:3, 3] = point - numpy.dot(R, point)
+ return M
def rotation_from_matrix(matrix):
- """Return rotation angle and axis from rotation matrix.
+ """Return rotation angle and axis from rotation matrix.
>>> angle = (random.random() - 0.5) * (2*math.pi)
>>> direc = numpy.random.random(3) - 0.5
@@ -158,35 +156,35 @@ def rotation_from_matrix(matrix):
True
"""
- R = numpy.array(matrix, dtype=numpy.float64, copy=False)
- R33 = R[:3, :3]
- # direction: unit eigenvector of R33 corresponding to eigenvalue of 1
- w, W = numpy.linalg.eig(R33.T)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
- direction = numpy.real(W[:, i[-1]]).squeeze()
- # point: unit eigenvector of R33 corresponding to eigenvalue of 1
- w, Q = numpy.linalg.eig(R)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
- point = numpy.real(Q[:, i[-1]]).squeeze()
- point /= point[3]
- # rotation angle depending on direction
- cosa = (numpy.trace(R33) - 1.0) / 2.0
- if abs(direction[2]) > 1e-8:
- sina = (R[1, 0] + (cosa-1.0)*direction[0]*direction[1]) / direction[2]
- elif abs(direction[1]) > 1e-8:
- sina = (R[0, 2] + (cosa-1.0)*direction[0]*direction[2]) / direction[1]
- else:
- sina = (R[2, 1] + (cosa-1.0)*direction[1]*direction[2]) / direction[0]
- angle = math.atan2(sina, cosa)
- return angle, direction, point
+ R = numpy.array(matrix, dtype=numpy.float64, copy=False)
+ R33 = R[:3, :3]
+ # direction: unit eigenvector of R33 corresponding to eigenvalue of 1
+ w, W = numpy.linalg.eig(R33.T)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
+ direction = numpy.real(W[:, i[-1]]).squeeze()
+ # point: unit eigenvector of R33 corresponding to eigenvalue of 1
+ w, Q = numpy.linalg.eig(R)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no unit eigenvector corresponding to eigenvalue 1')
+ point = numpy.real(Q[:, i[-1]]).squeeze()
+ point /= point[3]
+ # rotation angle depending on direction
+ cosa = (numpy.trace(R33) - 1.0) / 2.0
+ if abs(direction[2]) > 1e-8:
+ sina = (R[1, 0] + (cosa - 1.0) * direction[0] * direction[1]) / direction[2]
+ elif abs(direction[1]) > 1e-8:
+ sina = (R[0, 2] + (cosa - 1.0) * direction[0] * direction[2]) / direction[1]
+ else:
+ sina = (R[2, 1] + (cosa - 1.0) * direction[1] * direction[2]) / direction[0]
+ angle = math.atan2(sina, cosa)
+ return angle, direction, point
def scale_matrix(factor, origin=None, direction=None):
- """Return matrix to scale by factor around origin in direction.
+ """Return matrix to scale by factor around origin in direction.
Use factor -1 for point symmetry.
@@ -202,25 +200,25 @@ def scale_matrix(factor, origin=None, direction=None):
>>> S = scale_matrix(factor, origin, direct)
"""
- if direction is None:
- # uniform scaling
- M = numpy.diag([factor, factor, factor, 1.0])
- if origin is not None:
- M[:3, 3] = origin[:3]
- M[:3, 3] *= 1.0 - factor
- else:
- # nonuniform scaling
- direction = unit_vector(direction[:3])
- factor = 1.0 - factor
- M = numpy.identity(4)
- M[:3, :3] -= factor * numpy.outer(direction, direction)
- if origin is not None:
- M[:3, 3] = (factor * numpy.dot(origin[:3], direction)) * direction
- return M
+ if direction is None:
+ # uniform scaling
+ M = numpy.diag([factor, factor, factor, 1.0])
+ if origin is not None:
+ M[:3, 3] = origin[:3]
+ M[:3, 3] *= 1.0 - factor
+ else:
+ # nonuniform scaling
+ direction = unit_vector(direction[:3])
+ factor = 1.0 - factor
+ M = numpy.identity(4)
+ M[:3, :3] -= factor * numpy.outer(direction, direction)
+ if origin is not None:
+ M[:3, 3] = (factor * numpy.dot(origin[:3], direction)) * direction
+ return M
def scale_from_matrix(matrix):
- """Return scaling factor, origin and direction from scaling matrix.
+ """Return scaling factor, origin and direction from scaling matrix.
>>> factor = random.random() * 10 - 5
>>> origin = numpy.random.random(3) - 0.5
@@ -237,32 +235,31 @@ def scale_from_matrix(matrix):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)
- M33 = M[:3, :3]
- factor = numpy.trace(M33) - 2.0
- try:
- # direction: unit eigenvector corresponding to eigenvalue factor
- w, V = numpy.linalg.eig(M33)
- i = numpy.where(abs(numpy.real(w) - factor) < 1e-8)[0][0]
- direction = numpy.real(V[:, i]).squeeze()
- direction /= vector_norm(direction)
- except IndexError:
- # uniform scaling
- factor = (factor + 2.0) / 3.0
- direction = None
- # origin: any eigenvector corresponding to eigenvalue 1
- w, V = numpy.linalg.eig(M)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no eigenvector corresponding to eigenvalue 1')
- origin = numpy.real(V[:, i[-1]]).squeeze()
- origin /= origin[3]
- return factor, origin, direction
-
-
-def projection_matrix(point, normal, direction=None,
- perspective=None, pseudo=False):
- """Return matrix to project onto plane defined by point and normal.
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)
+ M33 = M[:3, :3]
+ factor = numpy.trace(M33) - 2.0
+ try:
+ # direction: unit eigenvector corresponding to eigenvalue factor
+ w, V = numpy.linalg.eig(M33)
+ i = numpy.where(abs(numpy.real(w) - factor) < 1e-8)[0][0]
+ direction = numpy.real(V[:, i]).squeeze()
+ direction /= vector_norm(direction)
+ except IndexError:
+ # uniform scaling
+ factor = (factor + 2.0) / 3.0
+ direction = None
+ # origin: any eigenvector corresponding to eigenvalue 1
+ w, V = numpy.linalg.eig(M)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no eigenvector corresponding to eigenvalue 1')
+ origin = numpy.real(V[:, i[-1]]).squeeze()
+ origin /= origin[3]
+ return factor, origin, direction
+
+
+def projection_matrix(point, normal, direction=None, perspective=None, pseudo=False):
+ """Return matrix to project onto plane defined by point and normal.
Using either perspective point, projection direction, or none of both.
@@ -292,38 +289,37 @@ def projection_matrix(point, normal, direction=None,
True
"""
- M = numpy.identity(4)
- point = numpy.array(point[:3], dtype=numpy.float64, copy=False)
- normal = unit_vector(normal[:3])
- if perspective is not None:
- # perspective projection
- perspective = numpy.array(perspective[:3], dtype=numpy.float64,
- copy=False)
- M[0, 0] = M[1, 1] = M[2, 2] = numpy.dot(perspective-point, normal)
- M[:3, :3] -= numpy.outer(perspective, normal)
- if pseudo:
- # preserve relative depth
- M[:3, :3] -= numpy.outer(normal, normal)
- M[:3, 3] = numpy.dot(point, normal) * (perspective+normal)
- else:
- M[:3, 3] = numpy.dot(point, normal) * perspective
- M[3, :3] = -normal
- M[3, 3] = numpy.dot(perspective, normal)
- elif direction is not None:
- # parallel projection
- direction = numpy.array(direction[:3], dtype=numpy.float64, copy=False)
- scale = numpy.dot(direction, normal)
- M[:3, :3] -= numpy.outer(direction, normal) / scale
- M[:3, 3] = direction * (numpy.dot(point, normal) / scale)
+ M = numpy.identity(4)
+ point = numpy.array(point[:3], dtype=numpy.float64, copy=False)
+ normal = unit_vector(normal[:3])
+ if perspective is not None:
+ # perspective projection
+ perspective = numpy.array(perspective[:3], dtype=numpy.float64, copy=False)
+ M[0, 0] = M[1, 1] = M[2, 2] = numpy.dot(perspective - point, normal)
+ M[:3, :3] -= numpy.outer(perspective, normal)
+ if pseudo:
+ # preserve relative depth
+ M[:3, :3] -= numpy.outer(normal, normal)
+ M[:3, 3] = numpy.dot(point, normal) * (perspective + normal)
else:
- # orthogonal projection
- M[:3, :3] -= numpy.outer(normal, normal)
- M[:3, 3] = numpy.dot(point, normal) * normal
- return M
+ M[:3, 3] = numpy.dot(point, normal) * perspective
+ M[3, :3] = -normal
+ M[3, 3] = numpy.dot(perspective, normal)
+ elif direction is not None:
+ # parallel projection
+ direction = numpy.array(direction[:3], dtype=numpy.float64, copy=False)
+ scale = numpy.dot(direction, normal)
+ M[:3, :3] -= numpy.outer(direction, normal) / scale
+ M[:3, 3] = direction * (numpy.dot(point, normal) / scale)
+ else:
+ # orthogonal projection
+ M[:3, :3] -= numpy.outer(normal, normal)
+ M[:3, 3] = numpy.dot(point, normal) * normal
+ return M
def projection_from_matrix(matrix, pseudo=False):
- """Return projection plane and perspective point from projection matrix.
+ """Return projection plane and perspective point from projection matrix.
Return values are same as arguments for projection_matrix function:
point, normal, direction, perspective, and pseudo.
@@ -354,49 +350,48 @@ def projection_from_matrix(matrix, pseudo=False):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)
- M33 = M[:3, :3]
- w, V = numpy.linalg.eig(M)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not pseudo and len(i):
- # point: any eigenvector corresponding to eigenvalue 1
- point = numpy.real(V[:, i[-1]]).squeeze()
- point /= point[3]
- # direction: unit eigenvector corresponding to eigenvalue 0
- w, V = numpy.linalg.eig(M33)
- i = numpy.where(abs(numpy.real(w)) < 1e-8)[0]
- if not len(i):
- raise ValueError('no eigenvector corresponding to eigenvalue 0')
- direction = numpy.real(V[:, i[0]]).squeeze()
- direction /= vector_norm(direction)
- # normal: unit eigenvector of M33.T corresponding to eigenvalue 0
- w, V = numpy.linalg.eig(M33.T)
- i = numpy.where(abs(numpy.real(w)) < 1e-8)[0]
- if len(i):
- # parallel projection
- normal = numpy.real(V[:, i[0]]).squeeze()
- normal /= vector_norm(normal)
- return point, normal, direction, None, False
- else:
- # orthogonal projection, where normal equals direction vector
- return point, direction, None, None, False
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)
+ M33 = M[:3, :3]
+ w, V = numpy.linalg.eig(M)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not pseudo and len(i):
+ # point: any eigenvector corresponding to eigenvalue 1
+ point = numpy.real(V[:, i[-1]]).squeeze()
+ point /= point[3]
+ # direction: unit eigenvector corresponding to eigenvalue 0
+ w, V = numpy.linalg.eig(M33)
+ i = numpy.where(abs(numpy.real(w)) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no eigenvector corresponding to eigenvalue 0')
+ direction = numpy.real(V[:, i[0]]).squeeze()
+ direction /= vector_norm(direction)
+ # normal: unit eigenvector of M33.T corresponding to eigenvalue 0
+ w, V = numpy.linalg.eig(M33.T)
+ i = numpy.where(abs(numpy.real(w)) < 1e-8)[0]
+ if len(i):
+ # parallel projection
+ normal = numpy.real(V[:, i[0]]).squeeze()
+ normal /= vector_norm(normal)
+ return point, normal, direction, None, False
else:
- # perspective projection
- i = numpy.where(abs(numpy.real(w)) > 1e-8)[0]
- if not len(i):
- raise ValueError(
- 'no eigenvector not corresponding to eigenvalue 0')
- point = numpy.real(V[:, i[-1]]).squeeze()
- point /= point[3]
- normal = - M[3, :3]
- perspective = M[:3, 3] / numpy.dot(point[:3], normal)
- if pseudo:
- perspective -= normal
- return point, normal, None, perspective, pseudo
+ # orthogonal projection, where normal equals direction vector
+ return point, direction, None, None, False
+ else:
+ # perspective projection
+ i = numpy.where(abs(numpy.real(w)) > 1e-8)[0]
+ if not len(i):
+ raise ValueError('no eigenvector not corresponding to eigenvalue 0')
+ point = numpy.real(V[:, i[-1]]).squeeze()
+ point /= point[3]
+ normal = -M[3, :3]
+ perspective = M[:3, 3] / numpy.dot(point[:3], normal)
+ if pseudo:
+ perspective -= normal
+ return point, normal, None, perspective, pseudo
def clip_matrix(left, right, bottom, top, near, far, perspective=False):
- """Return matrix to obtain normalized device coordinates from frustum.
+ """Return matrix to obtain normalized device coordinates from frustum.
The frustum bounds are axis-aligned along x (left, right),
y (bottom, top) and z (near, far).
@@ -429,26 +424,24 @@ def clip_matrix(left, right, bottom, top, near, far, perspective=False):
array([ 1., 1., -1., 1.])
"""
- if left >= right or bottom >= top or near >= far:
- raise ValueError('invalid frustum')
- if perspective:
- if near <= _EPS:
- raise ValueError('invalid frustum: near <= 0')
- t = 2.0 * near
- M = [[t/(left-right), 0.0, (right+left)/(right-left), 0.0],
- [0.0, t/(bottom-top), (top+bottom)/(top-bottom), 0.0],
- [0.0, 0.0, (far+near)/(near-far), t*far/(far-near)],
- [0.0, 0.0, -1.0, 0.0]]
- else:
- M = [[2.0/(right-left), 0.0, 0.0, (right+left)/(left-right)],
- [0.0, 2.0/(top-bottom), 0.0, (top+bottom)/(bottom-top)],
- [0.0, 0.0, 2.0/(far-near), (far+near)/(near-far)],
- [0.0, 0.0, 0.0, 1.0]]
- return numpy.array(M)
+ if left >= right or bottom >= top or near >= far:
+ raise ValueError('invalid frustum')
+ if perspective:
+ if near <= _EPS:
+ raise ValueError('invalid frustum: near <= 0')
+ t = 2.0 * near
+ M = [[t / (left - right), 0.0, (right + left) / (right - left), 0.0],
+ [0.0, t / (bottom - top), (top + bottom) / (top - bottom), 0.0],
+ [0.0, 0.0, (far + near) / (near - far), t * far / (far - near)], [0.0, 0.0, -1.0, 0.0]]
+ else:
+ M = [[2.0 / (right - left), 0.0, 0.0, (right + left) / (left - right)],
+ [0.0, 2.0 / (top - bottom), 0.0, (top + bottom) / (bottom - top)],
+ [0.0, 0.0, 2.0 / (far - near), (far + near) / (near - far)], [0.0, 0.0, 0.0, 1.0]]
+ return numpy.array(M)
def shear_matrix(angle, direction, point, normal):
- """Return matrix to shear by angle along direction vector on shear plane.
+ """Return matrix to shear by angle along direction vector on shear plane.
The shear plane is defined by a point and normal vector. The direction
vector must be orthogonal to the plane's normal vector.
@@ -467,19 +460,19 @@ def shear_matrix(angle, direction, point, normal):
True
"""
- normal = unit_vector(normal[:3])
- direction = unit_vector(direction[:3])
- if abs(numpy.dot(normal, direction)) > 1e-6:
- raise ValueError('direction and normal vectors are not orthogonal')
- angle = math.tan(angle)
- M = numpy.identity(4)
- M[:3, :3] += angle * numpy.outer(direction, normal)
- M[:3, 3] = -angle * numpy.dot(point[:3], normal) * direction
- return M
+ normal = unit_vector(normal[:3])
+ direction = unit_vector(direction[:3])
+ if abs(numpy.dot(normal, direction)) > 1e-6:
+ raise ValueError('direction and normal vectors are not orthogonal')
+ angle = math.tan(angle)
+ M = numpy.identity(4)
+ M[:3, :3] += angle * numpy.outer(direction, normal)
+ M[:3, 3] = -angle * numpy.dot(point[:3], normal) * direction
+ return M
def shear_from_matrix(matrix):
- """Return shear angle, direction and plane from shear matrix.
+ """Return shear angle, direction and plane from shear matrix.
>>> angle = (random.random() - 0.5) * 4*math.pi
>>> direct = numpy.random.random(3) - 0.5
@@ -492,39 +485,39 @@ def shear_from_matrix(matrix):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)
- M33 = M[:3, :3]
- # normal: cross independent eigenvectors corresponding to the eigenvalue 1
- w, V = numpy.linalg.eig(M33)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-4)[0]
- if len(i) < 2:
- raise ValueError('no two linear independent eigenvectors found %s' % w)
- V = numpy.real(V[:, i]).squeeze().T
- lenorm = -1.0
- for i0, i1 in ((0, 1), (0, 2), (1, 2)):
- n = numpy.cross(V[i0], V[i1])
- w = vector_norm(n)
- if w > lenorm:
- lenorm = w
- normal = n
- normal /= lenorm
- # direction and angle
- direction = numpy.dot(M33 - numpy.identity(3), normal)
- angle = vector_norm(direction)
- direction /= angle
- angle = math.atan(angle)
- # point: eigenvector corresponding to eigenvalue 1
- w, V = numpy.linalg.eig(M)
- i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
- if not len(i):
- raise ValueError('no eigenvector corresponding to eigenvalue 1')
- point = numpy.real(V[:, i[-1]]).squeeze()
- point /= point[3]
- return angle, direction, point, normal
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)
+ M33 = M[:3, :3]
+ # normal: cross independent eigenvectors corresponding to the eigenvalue 1
+ w, V = numpy.linalg.eig(M33)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-4)[0]
+ if len(i) < 2:
+ raise ValueError('no two linear independent eigenvectors found %s' % w)
+ V = numpy.real(V[:, i]).squeeze().T
+ lenorm = -1.0
+ for i0, i1 in ((0, 1), (0, 2), (1, 2)):
+ n = numpy.cross(V[i0], V[i1])
+ w = vector_norm(n)
+ if w > lenorm:
+ lenorm = w
+ normal = n
+ normal /= lenorm
+ # direction and angle
+ direction = numpy.dot(M33 - numpy.identity(3), normal)
+ angle = vector_norm(direction)
+ direction /= angle
+ angle = math.atan(angle)
+ # point: eigenvector corresponding to eigenvalue 1
+ w, V = numpy.linalg.eig(M)
+ i = numpy.where(abs(numpy.real(w) - 1.0) < 1e-8)[0]
+ if not len(i):
+ raise ValueError('no eigenvector corresponding to eigenvalue 1')
+ point = numpy.real(V[:, i[-1]]).squeeze()
+ point /= point[3]
+ return angle, direction, point, normal
def decompose_matrix(matrix):
- """Return sequence of transformations from transformation matrix.
+ """Return sequence of transformations from transformation matrix.
matrix : array_like
Non-degenerative homogeneous transformation matrix
@@ -554,63 +547,62 @@ def decompose_matrix(matrix):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=True).T
- if abs(M[3, 3]) < _EPS:
- raise ValueError('M[3, 3] is zero')
- M /= M[3, 3]
- P = M.copy()
- P[:, 3] = 0.0, 0.0, 0.0, 1.0
- if not numpy.linalg.det(P):
- raise ValueError('matrix is singular')
-
- scale = numpy.zeros((3, ))
- shear = [0.0, 0.0, 0.0]
- angles = [0.0, 0.0, 0.0]
-
- if any(abs(M[:3, 3]) > _EPS):
- perspective = numpy.dot(M[:, 3], numpy.linalg.inv(P.T))
- M[:, 3] = 0.0, 0.0, 0.0, 1.0
- else:
- perspective = numpy.array([0.0, 0.0, 0.0, 1.0])
-
- translate = M[3, :3].copy()
- M[3, :3] = 0.0
-
- row = M[:3, :3].copy()
- scale[0] = vector_norm(row[0])
- row[0] /= scale[0]
- shear[0] = numpy.dot(row[0], row[1])
- row[1] -= row[0] * shear[0]
- scale[1] = vector_norm(row[1])
- row[1] /= scale[1]
- shear[0] /= scale[1]
- shear[1] = numpy.dot(row[0], row[2])
- row[2] -= row[0] * shear[1]
- shear[2] = numpy.dot(row[1], row[2])
- row[2] -= row[1] * shear[2]
- scale[2] = vector_norm(row[2])
- row[2] /= scale[2]
- shear[1:] /= scale[2]
-
- if numpy.dot(row[0], numpy.cross(row[1], row[2])) < 0:
- numpy.negative(scale, scale)
- numpy.negative(row, row)
-
- angles[1] = math.asin(-row[0, 2])
- if math.cos(angles[1]):
- angles[0] = math.atan2(row[1, 2], row[2, 2])
- angles[2] = math.atan2(row[0, 1], row[0, 0])
- else:
- # angles[0] = math.atan2(row[1, 0], row[1, 1])
- angles[0] = math.atan2(-row[2, 1], row[1, 1])
- angles[2] = 0.0
-
- return scale, shear, angles, translate, perspective
-
-
-def compose_matrix(scale=None, shear=None, angles=None, translate=None,
- perspective=None):
- """Return transformation matrix from sequence of transformations.
+ M = numpy.array(matrix, dtype=numpy.float64, copy=True).T
+ if abs(M[3, 3]) < _EPS:
+ raise ValueError('M[3, 3] is zero')
+ M /= M[3, 3]
+ P = M.copy()
+ P[:, 3] = 0.0, 0.0, 0.0, 1.0
+ if not numpy.linalg.det(P):
+ raise ValueError('matrix is singular')
+
+ scale = numpy.zeros((3,))
+ shear = [0.0, 0.0, 0.0]
+ angles = [0.0, 0.0, 0.0]
+
+ if any(abs(M[:3, 3]) > _EPS):
+ perspective = numpy.dot(M[:, 3], numpy.linalg.inv(P.T))
+ M[:, 3] = 0.0, 0.0, 0.0, 1.0
+ else:
+ perspective = numpy.array([0.0, 0.0, 0.0, 1.0])
+
+ translate = M[3, :3].copy()
+ M[3, :3] = 0.0
+
+ row = M[:3, :3].copy()
+ scale[0] = vector_norm(row[0])
+ row[0] /= scale[0]
+ shear[0] = numpy.dot(row[0], row[1])
+ row[1] -= row[0] * shear[0]
+ scale[1] = vector_norm(row[1])
+ row[1] /= scale[1]
+ shear[0] /= scale[1]
+ shear[1] = numpy.dot(row[0], row[2])
+ row[2] -= row[0] * shear[1]
+ shear[2] = numpy.dot(row[1], row[2])
+ row[2] -= row[1] * shear[2]
+ scale[2] = vector_norm(row[2])
+ row[2] /= scale[2]
+ shear[1:] /= scale[2]
+
+ if numpy.dot(row[0], numpy.cross(row[1], row[2])) < 0:
+ numpy.negative(scale, scale)
+ numpy.negative(row, row)
+
+ angles[1] = math.asin(-row[0, 2])
+ if math.cos(angles[1]):
+ angles[0] = math.atan2(row[1, 2], row[2, 2])
+ angles[2] = math.atan2(row[0, 1], row[0, 0])
+ else:
+ # angles[0] = math.atan2(row[1, 0], row[1, 1])
+ angles[0] = math.atan2(-row[2, 1], row[1, 1])
+ angles[2] = 0.0
+
+ return scale, shear, angles, translate, perspective
+
+
+def compose_matrix(scale=None, shear=None, angles=None, translate=None, perspective=None):
+ """Return transformation matrix from sequence of transformations.
This is the inverse of the decompose_matrix function.
@@ -633,36 +625,36 @@ def compose_matrix(scale=None, shear=None, angles=None, translate=None,
True
"""
- M = numpy.identity(4)
- if perspective is not None:
- P = numpy.identity(4)
- P[3, :] = perspective[:4]
- M = numpy.dot(M, P)
- if translate is not None:
- T = numpy.identity(4)
- T[:3, 3] = translate[:3]
- M = numpy.dot(M, T)
- if angles is not None:
- R = euler_matrix(angles[0], angles[1], angles[2], 'sxyz')
- M = numpy.dot(M, R)
- if shear is not None:
- Z = numpy.identity(4)
- Z[1, 2] = shear[2]
- Z[0, 2] = shear[1]
- Z[0, 1] = shear[0]
- M = numpy.dot(M, Z)
- if scale is not None:
- S = numpy.identity(4)
- S[0, 0] = scale[0]
- S[1, 1] = scale[1]
- S[2, 2] = scale[2]
- M = numpy.dot(M, S)
- M /= M[3, 3]
- return M
+ M = numpy.identity(4)
+ if perspective is not None:
+ P = numpy.identity(4)
+ P[3, :] = perspective[:4]
+ M = numpy.dot(M, P)
+ if translate is not None:
+ T = numpy.identity(4)
+ T[:3, 3] = translate[:3]
+ M = numpy.dot(M, T)
+ if angles is not None:
+ R = euler_matrix(angles[0], angles[1], angles[2], 'sxyz')
+ M = numpy.dot(M, R)
+ if shear is not None:
+ Z = numpy.identity(4)
+ Z[1, 2] = shear[2]
+ Z[0, 2] = shear[1]
+ Z[0, 1] = shear[0]
+ M = numpy.dot(M, Z)
+ if scale is not None:
+ S = numpy.identity(4)
+ S[0, 0] = scale[0]
+ S[1, 1] = scale[1]
+ S[2, 2] = scale[2]
+ M = numpy.dot(M, S)
+ M /= M[3, 3]
+ return M
def orthogonalization_matrix(lengths, angles):
- """Return orthogonalization matrix for crystallographic cell coordinates.
+ """Return orthogonalization matrix for crystallographic cell coordinates.
Angles are expected in degrees.
@@ -676,20 +668,18 @@ def orthogonalization_matrix(lengths, angles):
True
"""
- a, b, c = lengths
- angles = numpy.radians(angles)
- sina, sinb, _ = numpy.sin(angles)
- cosa, cosb, cosg = numpy.cos(angles)
- co = (cosa * cosb - cosg) / (sina * sinb)
- return numpy.array([
- [ a*sinb*math.sqrt(1.0-co*co), 0.0, 0.0, 0.0],
- [-a*sinb*co, b*sina, 0.0, 0.0],
- [ a*cosb, b*cosa, c, 0.0],
- [ 0.0, 0.0, 0.0, 1.0]])
+ a, b, c = lengths
+ angles = numpy.radians(angles)
+ sina, sinb, _ = numpy.sin(angles)
+ cosa, cosb, cosg = numpy.cos(angles)
+ co = (cosa * cosb - cosg) / (sina * sinb)
+ return numpy.array([[a * sinb * math.sqrt(1.0 - co * co), 0.0, 0.0, 0.0],
+ [-a * sinb * co, b * sina, 0.0, 0.0], [a * cosb, b * cosa, c, 0.0],
+ [0.0, 0.0, 0.0, 1.0]])
def affine_matrix_from_points(v0, v1, shear=True, scale=True, usesvd=True):
- """Return affine transform matrix to register two point sets.
+ """Return affine transform matrix to register two point sets.
v0 and v1 are shape (ndims, \*) arrays of at least ndims non-homogeneous
coordinates, where ndims is the dimensionality of the coordinate space.
@@ -729,76 +719,74 @@ def affine_matrix_from_points(v0, v1, shear=True, scale=True, usesvd=True):
More examples in superimposition_matrix()
"""
- v0 = numpy.array(v0, dtype=numpy.float64, copy=True)
- v1 = numpy.array(v1, dtype=numpy.float64, copy=True)
-
- ndims = v0.shape[0]
- if ndims < 2 or v0.shape[1] < ndims or v0.shape != v1.shape:
- raise ValueError('input arrays are of wrong shape or type')
-
- # move centroids to origin
- t0 = -numpy.mean(v0, axis=1)
- M0 = numpy.identity(ndims+1)
- M0[:ndims, ndims] = t0
- v0 += t0.reshape(ndims, 1)
- t1 = -numpy.mean(v1, axis=1)
- M1 = numpy.identity(ndims+1)
- M1[:ndims, ndims] = t1
- v1 += t1.reshape(ndims, 1)
-
- if shear:
- # Affine transformation
- A = numpy.concatenate((v0, v1), axis=0)
- u, s, vh = numpy.linalg.svd(A.T)
- vh = vh[:ndims].T
- B = vh[:ndims]
- C = vh[ndims:2*ndims]
- t = numpy.dot(C, numpy.linalg.pinv(B))
- t = numpy.concatenate((t, numpy.zeros((ndims, 1))), axis=1)
- M = numpy.vstack((t, ((0.0,)*ndims) + (1.0,)))
- elif usesvd or ndims != 3:
- # Rigid transformation via SVD of covariance matrix
- u, s, vh = numpy.linalg.svd(numpy.dot(v1, v0.T))
- # rotation matrix from SVD orthonormal bases
- R = numpy.dot(u, vh)
- if numpy.linalg.det(R) < 0.0:
- # R does not constitute right handed system
- R -= numpy.outer(u[:, ndims-1], vh[ndims-1, :]*2.0)
- s[-1] *= -1.0
- # homogeneous transformation matrix
- M = numpy.identity(ndims+1)
- M[:ndims, :ndims] = R
- else:
- # Rigid transformation matrix via quaternion
- # compute symmetric matrix N
- xx, yy, zz = numpy.sum(v0 * v1, axis=1)
- xy, yz, zx = numpy.sum(v0 * numpy.roll(v1, -1, axis=0), axis=1)
- xz, yx, zy = numpy.sum(v0 * numpy.roll(v1, -2, axis=0), axis=1)
- N = [[xx+yy+zz, 0.0, 0.0, 0.0],
- [yz-zy, xx-yy-zz, 0.0, 0.0],
- [zx-xz, xy+yx, yy-xx-zz, 0.0],
- [xy-yx, zx+xz, yz+zy, zz-xx-yy]]
- # quaternion: eigenvector corresponding to most positive eigenvalue
- w, V = numpy.linalg.eigh(N)
- q = V[:, numpy.argmax(w)]
- q /= vector_norm(q) # unit quaternion
- # homogeneous transformation matrix
- M = quaternion_matrix(q)
-
- if scale and not shear:
- # Affine transformation; scale is ratio of RMS deviations from centroid
- v0 *= v0
- v1 *= v1
- M[:ndims, :ndims] *= math.sqrt(numpy.sum(v1) / numpy.sum(v0))
-
- # move centroids back
- M = numpy.dot(numpy.linalg.inv(M1), numpy.dot(M, M0))
- M /= M[ndims, ndims]
- return M
+ v0 = numpy.array(v0, dtype=numpy.float64, copy=True)
+ v1 = numpy.array(v1, dtype=numpy.float64, copy=True)
+
+ ndims = v0.shape[0]
+ if ndims < 2 or v0.shape[1] < ndims or v0.shape != v1.shape:
+ raise ValueError('input arrays are of wrong shape or type')
+
+ # move centroids to origin
+ t0 = -numpy.mean(v0, axis=1)
+ M0 = numpy.identity(ndims + 1)
+ M0[:ndims, ndims] = t0
+ v0 += t0.reshape(ndims, 1)
+ t1 = -numpy.mean(v1, axis=1)
+ M1 = numpy.identity(ndims + 1)
+ M1[:ndims, ndims] = t1
+ v1 += t1.reshape(ndims, 1)
+
+ if shear:
+ # Affine transformation
+ A = numpy.concatenate((v0, v1), axis=0)
+ u, s, vh = numpy.linalg.svd(A.T)
+ vh = vh[:ndims].T
+ B = vh[:ndims]
+ C = vh[ndims:2 * ndims]
+ t = numpy.dot(C, numpy.linalg.pinv(B))
+ t = numpy.concatenate((t, numpy.zeros((ndims, 1))), axis=1)
+ M = numpy.vstack((t, ((0.0,) * ndims) + (1.0,)))
+ elif usesvd or ndims != 3:
+ # Rigid transformation via SVD of covariance matrix
+ u, s, vh = numpy.linalg.svd(numpy.dot(v1, v0.T))
+ # rotation matrix from SVD orthonormal bases
+ R = numpy.dot(u, vh)
+ if numpy.linalg.det(R) < 0.0:
+ # R does not constitute right handed system
+ R -= numpy.outer(u[:, ndims - 1], vh[ndims - 1, :] * 2.0)
+ s[-1] *= -1.0
+ # homogeneous transformation matrix
+ M = numpy.identity(ndims + 1)
+ M[:ndims, :ndims] = R
+ else:
+ # Rigid transformation matrix via quaternion
+ # compute symmetric matrix N
+ xx, yy, zz = numpy.sum(v0 * v1, axis=1)
+ xy, yz, zx = numpy.sum(v0 * numpy.roll(v1, -1, axis=0), axis=1)
+ xz, yx, zy = numpy.sum(v0 * numpy.roll(v1, -2, axis=0), axis=1)
+ N = [[xx + yy + zz, 0.0, 0.0, 0.0], [yz - zy, xx - yy - zz, 0.0, 0.0],
+ [zx - xz, xy + yx, yy - xx - zz, 0.0], [xy - yx, zx + xz, yz + zy, zz - xx - yy]]
+ # quaternion: eigenvector corresponding to most positive eigenvalue
+ w, V = numpy.linalg.eigh(N)
+ q = V[:, numpy.argmax(w)]
+ q /= vector_norm(q) # unit quaternion
+ # homogeneous transformation matrix
+ M = quaternion_matrix(q)
+
+ if scale and not shear:
+ # Affine transformation; scale is ratio of RMS deviations from centroid
+ v0 *= v0
+ v1 *= v1
+ M[:ndims, :ndims] *= math.sqrt(numpy.sum(v1) / numpy.sum(v0))
+
+ # move centroids back
+ M = numpy.dot(numpy.linalg.inv(M1), numpy.dot(M, M0))
+ M /= M[ndims, ndims]
+ return M
def superimposition_matrix(v0, v1, scale=False, usesvd=True):
- """Return matrix to transform given 3D point set into second point set.
+ """Return matrix to transform given 3D point set into second point set.
v0 and v1 are shape (3, \*) or (4, \*) arrays of at least 3 points.
@@ -842,14 +830,13 @@ def superimposition_matrix(v0, v1, scale=False, usesvd=True):
True
"""
- v0 = numpy.array(v0, dtype=numpy.float64, copy=False)[:3]
- v1 = numpy.array(v1, dtype=numpy.float64, copy=False)[:3]
- return affine_matrix_from_points(v0, v1, shear=False,
- scale=scale, usesvd=usesvd)
+ v0 = numpy.array(v0, dtype=numpy.float64, copy=False)[:3]
+ v1 = numpy.array(v1, dtype=numpy.float64, copy=False)[:3]
+ return affine_matrix_from_points(v0, v1, shear=False, scale=scale, usesvd=usesvd)
def euler_matrix(ai, aj, ak, axes='sxyz'):
- """Return homogeneous rotation matrix from Euler angles and axis sequence.
+ """Return homogeneous rotation matrix from Euler angles and axis sequence.
ai, aj, ak : Euler's roll, pitch and yaw angles
axes : One of 24 axis sequences as string or encoded tuple
@@ -867,52 +854,52 @@ def euler_matrix(ai, aj, ak, axes='sxyz'):
... R = euler_matrix(ai, aj, ak, axes)
"""
- try:
- firstaxis, parity, repetition, frame = _AXES2TUPLE[axes]
- except (AttributeError, KeyError):
- _TUPLE2AXES[axes] # noqa: validation
- firstaxis, parity, repetition, frame = axes
-
- i = firstaxis
- j = _NEXT_AXIS[i+parity]
- k = _NEXT_AXIS[i-parity+1]
-
- if frame:
- ai, ak = ak, ai
- if parity:
- ai, aj, ak = -ai, -aj, -ak
-
- si, sj, sk = math.sin(ai), math.sin(aj), math.sin(ak)
- ci, cj, ck = math.cos(ai), math.cos(aj), math.cos(ak)
- cc, cs = ci*ck, ci*sk
- sc, ss = si*ck, si*sk
-
- M = numpy.identity(4)
- if repetition:
- M[i, i] = cj
- M[i, j] = sj*si
- M[i, k] = sj*ci
- M[j, i] = sj*sk
- M[j, j] = -cj*ss+cc
- M[j, k] = -cj*cs-sc
- M[k, i] = -sj*ck
- M[k, j] = cj*sc+cs
- M[k, k] = cj*cc-ss
- else:
- M[i, i] = cj*ck
- M[i, j] = sj*sc-cs
- M[i, k] = sj*cc+ss
- M[j, i] = cj*sk
- M[j, j] = sj*ss+cc
- M[j, k] = sj*cs-sc
- M[k, i] = -sj
- M[k, j] = cj*si
- M[k, k] = cj*ci
- return M
+ try:
+ firstaxis, parity, repetition, frame = _AXES2TUPLE[axes]
+ except (AttributeError, KeyError):
+ _TUPLE2AXES[axes] # noqa: validation
+ firstaxis, parity, repetition, frame = axes
+
+ i = firstaxis
+ j = _NEXT_AXIS[i + parity]
+ k = _NEXT_AXIS[i - parity + 1]
+
+ if frame:
+ ai, ak = ak, ai
+ if parity:
+ ai, aj, ak = -ai, -aj, -ak
+
+ si, sj, sk = math.sin(ai), math.sin(aj), math.sin(ak)
+ ci, cj, ck = math.cos(ai), math.cos(aj), math.cos(ak)
+ cc, cs = ci * ck, ci * sk
+ sc, ss = si * ck, si * sk
+
+ M = numpy.identity(4)
+ if repetition:
+ M[i, i] = cj
+ M[i, j] = sj * si
+ M[i, k] = sj * ci
+ M[j, i] = sj * sk
+ M[j, j] = -cj * ss + cc
+ M[j, k] = -cj * cs - sc
+ M[k, i] = -sj * ck
+ M[k, j] = cj * sc + cs
+ M[k, k] = cj * cc - ss
+ else:
+ M[i, i] = cj * ck
+ M[i, j] = sj * sc - cs
+ M[i, k] = sj * cc + ss
+ M[j, i] = cj * sk
+ M[j, j] = sj * ss + cc
+ M[j, k] = sj * cs - sc
+ M[k, i] = -sj
+ M[k, j] = cj * si
+ M[k, k] = cj * ci
+ return M
def euler_from_matrix(matrix, axes='sxyz'):
- """Return Euler angles from rotation matrix for specified axis sequence.
+ """Return Euler angles from rotation matrix for specified axis sequence.
axes : One of 24 axis sequences as string or encoded tuple
@@ -930,58 +917,58 @@ def euler_from_matrix(matrix, axes='sxyz'):
... if not numpy.allclose(R0, R1): print(axes, "failed")
"""
- try:
- firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()]
- except (AttributeError, KeyError):
- _TUPLE2AXES[axes] # noqa: validation
- firstaxis, parity, repetition, frame = axes
-
- i = firstaxis
- j = _NEXT_AXIS[i+parity]
- k = _NEXT_AXIS[i-parity+1]
-
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:3, :3]
- if repetition:
- sy = math.sqrt(M[i, j]*M[i, j] + M[i, k]*M[i, k])
- if sy > _EPS:
- ax = math.atan2( M[i, j], M[i, k])
- ay = math.atan2( sy, M[i, i])
- az = math.atan2( M[j, i], -M[k, i])
- else:
- ax = math.atan2(-M[j, k], M[j, j])
- ay = math.atan2( sy, M[i, i])
- az = 0.0
+ try:
+ firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()]
+ except (AttributeError, KeyError):
+ _TUPLE2AXES[axes] # noqa: validation
+ firstaxis, parity, repetition, frame = axes
+
+ i = firstaxis
+ j = _NEXT_AXIS[i + parity]
+ k = _NEXT_AXIS[i - parity + 1]
+
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:3, :3]
+ if repetition:
+ sy = math.sqrt(M[i, j] * M[i, j] + M[i, k] * M[i, k])
+ if sy > _EPS:
+ ax = math.atan2(M[i, j], M[i, k])
+ ay = math.atan2(sy, M[i, i])
+ az = math.atan2(M[j, i], -M[k, i])
+ else:
+ ax = math.atan2(-M[j, k], M[j, j])
+ ay = math.atan2(sy, M[i, i])
+ az = 0.0
+ else:
+ cy = math.sqrt(M[i, i] * M[i, i] + M[j, i] * M[j, i])
+ if cy > _EPS:
+ ax = math.atan2(M[k, j], M[k, k])
+ ay = math.atan2(-M[k, i], cy)
+ az = math.atan2(M[j, i], M[i, i])
else:
- cy = math.sqrt(M[i, i]*M[i, i] + M[j, i]*M[j, i])
- if cy > _EPS:
- ax = math.atan2( M[k, j], M[k, k])
- ay = math.atan2(-M[k, i], cy)
- az = math.atan2( M[j, i], M[i, i])
- else:
- ax = math.atan2(-M[j, k], M[j, j])
- ay = math.atan2(-M[k, i], cy)
- az = 0.0
-
- if parity:
- ax, ay, az = -ax, -ay, -az
- if frame:
- ax, az = az, ax
- return ax, ay, az
+ ax = math.atan2(-M[j, k], M[j, j])
+ ay = math.atan2(-M[k, i], cy)
+ az = 0.0
+
+ if parity:
+ ax, ay, az = -ax, -ay, -az
+ if frame:
+ ax, az = az, ax
+ return ax, ay, az
def euler_from_quaternion(quaternion, axes='sxyz'):
- """Return Euler angles from quaternion for specified axis sequence.
+ """Return Euler angles from quaternion for specified axis sequence.
>>> angles = euler_from_quaternion([0.99810947, 0.06146124, 0, 0])
>>> numpy.allclose(angles, [0.123, 0, 0])
True
"""
- return euler_from_matrix(quaternion_matrix(quaternion), axes)
+ return euler_from_matrix(quaternion_matrix(quaternion), axes)
def quaternion_from_euler(ai, aj, ak, axes='sxyz'):
- """Return quaternion from Euler angles and axis sequence.
+ """Return quaternion from Euler angles and axis sequence.
ai, aj, ak : Euler's roll, pitch and yaw angles
axes : One of 24 axis sequences as string or encoded tuple
@@ -991,70 +978,70 @@ def quaternion_from_euler(ai, aj, ak, axes='sxyz'):
True
"""
- try:
- firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()]
- except (AttributeError, KeyError):
- _TUPLE2AXES[axes] # noqa: validation
- firstaxis, parity, repetition, frame = axes
-
- i = firstaxis + 1
- j = _NEXT_AXIS[i+parity-1] + 1
- k = _NEXT_AXIS[i-parity] + 1
-
- if frame:
- ai, ak = ak, ai
- if parity:
- aj = -aj
-
- ai /= 2.0
- aj /= 2.0
- ak /= 2.0
- ci = math.cos(ai)
- si = math.sin(ai)
- cj = math.cos(aj)
- sj = math.sin(aj)
- ck = math.cos(ak)
- sk = math.sin(ak)
- cc = ci*ck
- cs = ci*sk
- sc = si*ck
- ss = si*sk
-
- q = numpy.empty((4, ))
- if repetition:
- q[0] = cj*(cc - ss)
- q[i] = cj*(cs + sc)
- q[j] = sj*(cc + ss)
- q[k] = sj*(cs - sc)
- else:
- q[0] = cj*cc + sj*ss
- q[i] = cj*sc - sj*cs
- q[j] = cj*ss + sj*cc
- q[k] = cj*cs - sj*sc
- if parity:
- q[j] *= -1.0
-
- return q
+ try:
+ firstaxis, parity, repetition, frame = _AXES2TUPLE[axes.lower()]
+ except (AttributeError, KeyError):
+ _TUPLE2AXES[axes] # noqa: validation
+ firstaxis, parity, repetition, frame = axes
+
+ i = firstaxis + 1
+ j = _NEXT_AXIS[i + parity - 1] + 1
+ k = _NEXT_AXIS[i - parity] + 1
+
+ if frame:
+ ai, ak = ak, ai
+ if parity:
+ aj = -aj
+
+ ai /= 2.0
+ aj /= 2.0
+ ak /= 2.0
+ ci = math.cos(ai)
+ si = math.sin(ai)
+ cj = math.cos(aj)
+ sj = math.sin(aj)
+ ck = math.cos(ak)
+ sk = math.sin(ak)
+ cc = ci * ck
+ cs = ci * sk
+ sc = si * ck
+ ss = si * sk
+
+ q = numpy.empty((4,))
+ if repetition:
+ q[0] = cj * (cc - ss)
+ q[i] = cj * (cs + sc)
+ q[j] = sj * (cc + ss)
+ q[k] = sj * (cs - sc)
+ else:
+ q[0] = cj * cc + sj * ss
+ q[i] = cj * sc - sj * cs
+ q[j] = cj * ss + sj * cc
+ q[k] = cj * cs - sj * sc
+ if parity:
+ q[j] *= -1.0
+
+ return q
def quaternion_about_axis(angle, axis):
- """Return quaternion for rotation about axis.
+ """Return quaternion for rotation about axis.
>>> q = quaternion_about_axis(0.123, [1, 0, 0])
>>> numpy.allclose(q, [0.99810947, 0.06146124, 0, 0])
True
"""
- q = numpy.array([0.0, axis[0], axis[1], axis[2]])
- qlen = vector_norm(q)
- if qlen > _EPS:
- q *= math.sin(angle/2.0) / qlen
- q[0] = math.cos(angle/2.0)
- return q
+ q = numpy.array([0.0, axis[0], axis[1], axis[2]])
+ qlen = vector_norm(q)
+ if qlen > _EPS:
+ q *= math.sin(angle / 2.0) / qlen
+ q[0] = math.cos(angle / 2.0)
+ return q
def quaternion_matrix(quaternion):
- """Return homogeneous rotation matrix from quaternion.
+ """Return homogeneous rotation matrix from quaternion.
>>> M = quaternion_matrix([0.99810947, 0.06146124, 0, 0])
>>> numpy.allclose(M, rotation_matrix(0.123, [1, 0, 0]))
@@ -1067,21 +1054,20 @@ def quaternion_matrix(quaternion):
True
"""
- q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
- n = numpy.dot(q, q)
- if n < _EPS:
- return numpy.identity(4)
- q *= math.sqrt(2.0 / n)
- q = numpy.outer(q, q)
- return numpy.array([
- [1.0-q[2, 2]-q[3, 3], q[1, 2]-q[3, 0], q[1, 3]+q[2, 0], 0.0],
- [ q[1, 2]+q[3, 0], 1.0-q[1, 1]-q[3, 3], q[2, 3]-q[1, 0], 0.0],
- [ q[1, 3]-q[2, 0], q[2, 3]+q[1, 0], 1.0-q[1, 1]-q[2, 2], 0.0],
- [ 0.0, 0.0, 0.0, 1.0]])
+ q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
+ n = numpy.dot(q, q)
+ if n < _EPS:
+ return numpy.identity(4)
+ q *= math.sqrt(2.0 / n)
+ q = numpy.outer(q, q)
+ return numpy.array([[1.0 - q[2, 2] - q[3, 3], q[1, 2] - q[3, 0], q[1, 3] + q[2, 0], 0.0],
+ [q[1, 2] + q[3, 0], 1.0 - q[1, 1] - q[3, 3], q[2, 3] - q[1, 0], 0.0],
+ [q[1, 3] - q[2, 0], q[2, 3] + q[1, 0], 1.0 - q[1, 1] - q[2, 2], 0.0],
+ [0.0, 0.0, 0.0, 1.0]])
def quaternion_from_matrix(matrix, isprecise=False):
- """Return quaternion from rotation matrix.
+ """Return quaternion from rotation matrix.
If isprecise is True, the input matrix is assumed to be a precise rotation
matrix and a faster algorithm is used.
@@ -1119,71 +1105,70 @@ def quaternion_from_matrix(matrix, isprecise=False):
True
"""
- M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:4, :4]
- if isprecise:
- q = numpy.empty((4, ))
- t = numpy.trace(M)
- if t > M[3, 3]:
- q[0] = t
- q[3] = M[1, 0] - M[0, 1]
- q[2] = M[0, 2] - M[2, 0]
- q[1] = M[2, 1] - M[1, 2]
- else:
- i, j, k = 0, 1, 2
- if M[1, 1] > M[0, 0]:
- i, j, k = 1, 2, 0
- if M[2, 2] > M[i, i]:
- i, j, k = 2, 0, 1
- t = M[i, i] - (M[j, j] + M[k, k]) + M[3, 3]
- q[i] = t
- q[j] = M[i, j] + M[j, i]
- q[k] = M[k, i] + M[i, k]
- q[3] = M[k, j] - M[j, k]
- q = q[[3, 0, 1, 2]]
- q *= 0.5 / math.sqrt(t * M[3, 3])
+ M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:4, :4]
+ if isprecise:
+ q = numpy.empty((4,))
+ t = numpy.trace(M)
+ if t > M[3, 3]:
+ q[0] = t
+ q[3] = M[1, 0] - M[0, 1]
+ q[2] = M[0, 2] - M[2, 0]
+ q[1] = M[2, 1] - M[1, 2]
else:
- m00 = M[0, 0]
- m01 = M[0, 1]
- m02 = M[0, 2]
- m10 = M[1, 0]
- m11 = M[1, 1]
- m12 = M[1, 2]
- m20 = M[2, 0]
- m21 = M[2, 1]
- m22 = M[2, 2]
- # symmetric matrix K
- K = numpy.array([[m00-m11-m22, 0.0, 0.0, 0.0],
- [m01+m10, m11-m00-m22, 0.0, 0.0],
- [m02+m20, m12+m21, m22-m00-m11, 0.0],
- [m21-m12, m02-m20, m10-m01, m00+m11+m22]])
- K /= 3.0
- # quaternion is eigenvector of K that corresponds to largest eigenvalue
- w, V = numpy.linalg.eigh(K)
- q = V[[3, 0, 1, 2], numpy.argmax(w)]
- if q[0] < 0.0:
- numpy.negative(q, q)
- return q
+ i, j, k = 0, 1, 2
+ if M[1, 1] > M[0, 0]:
+ i, j, k = 1, 2, 0
+ if M[2, 2] > M[i, i]:
+ i, j, k = 2, 0, 1
+ t = M[i, i] - (M[j, j] + M[k, k]) + M[3, 3]
+ q[i] = t
+ q[j] = M[i, j] + M[j, i]
+ q[k] = M[k, i] + M[i, k]
+ q[3] = M[k, j] - M[j, k]
+ q = q[[3, 0, 1, 2]]
+ q *= 0.5 / math.sqrt(t * M[3, 3])
+ else:
+ m00 = M[0, 0]
+ m01 = M[0, 1]
+ m02 = M[0, 2]
+ m10 = M[1, 0]
+ m11 = M[1, 1]
+ m12 = M[1, 2]
+ m20 = M[2, 0]
+ m21 = M[2, 1]
+ m22 = M[2, 2]
+ # symmetric matrix K
+ K = numpy.array([[m00 - m11 - m22, 0.0, 0.0, 0.0], [m01 + m10, m11 - m00 - m22, 0.0, 0.0],
+ [m02 + m20, m12 + m21, m22 - m00 - m11, 0.0],
+ [m21 - m12, m02 - m20, m10 - m01, m00 + m11 + m22]])
+ K /= 3.0
+ # quaternion is eigenvector of K that corresponds to largest eigenvalue
+ w, V = numpy.linalg.eigh(K)
+ q = V[[3, 0, 1, 2], numpy.argmax(w)]
+ if q[0] < 0.0:
+ numpy.negative(q, q)
+ return q
def quaternion_multiply(quaternion1, quaternion0):
- """Return multiplication of two quaternions.
+ """Return multiplication of two quaternions.
>>> q = quaternion_multiply([4, 1, -2, 3], [8, -5, 6, 7])
>>> numpy.allclose(q, [28, -44, -14, 48])
True
"""
- w0, x0, y0, z0 = quaternion0
- w1, x1, y1, z1 = quaternion1
- return numpy.array([
- -x1*x0 - y1*y0 - z1*z0 + w1*w0,
- x1*w0 + y1*z0 - z1*y0 + w1*x0,
- -x1*z0 + y1*w0 + z1*x0 + w1*y0,
- x1*y0 - y1*x0 + z1*w0 + w1*z0], dtype=numpy.float64)
+ w0, x0, y0, z0 = quaternion0
+ w1, x1, y1, z1 = quaternion1
+ return numpy.array([
+ -x1 * x0 - y1 * y0 - z1 * z0 + w1 * w0, x1 * w0 + y1 * z0 - z1 * y0 + w1 * x0,
+ -x1 * z0 + y1 * w0 + z1 * x0 + w1 * y0, x1 * y0 - y1 * x0 + z1 * w0 + w1 * z0
+ ],
+ dtype=numpy.float64)
def quaternion_conjugate(quaternion):
- """Return conjugate of quaternion.
+ """Return conjugate of quaternion.
>>> q0 = random_quaternion()
>>> q1 = quaternion_conjugate(q0)
@@ -1191,13 +1176,13 @@ def quaternion_conjugate(quaternion):
True
"""
- q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
- numpy.negative(q[1:], q[1:])
- return q
+ q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
+ numpy.negative(q[1:], q[1:])
+ return q
def quaternion_inverse(quaternion):
- """Return inverse of quaternion.
+ """Return inverse of quaternion.
>>> q0 = random_quaternion()
>>> q1 = quaternion_inverse(q0)
@@ -1205,33 +1190,33 @@ def quaternion_inverse(quaternion):
True
"""
- q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
- numpy.negative(q[1:], q[1:])
- return q / numpy.dot(q, q)
+ q = numpy.array(quaternion, dtype=numpy.float64, copy=True)
+ numpy.negative(q[1:], q[1:])
+ return q / numpy.dot(q, q)
def quaternion_real(quaternion):
- """Return real part of quaternion.
+ """Return real part of quaternion.
>>> quaternion_real([3, 0, 1, 2])
3.0
"""
- return float(quaternion[0])
+ return float(quaternion[0])
def quaternion_imag(quaternion):
- """Return imaginary part of quaternion.
+ """Return imaginary part of quaternion.
>>> quaternion_imag([3, 0, 1, 2])
array([ 0., 1., 2.])
"""
- return numpy.array(quaternion[1:4], dtype=numpy.float64, copy=True)
+ return numpy.array(quaternion[1:4], dtype=numpy.float64, copy=True)
def quaternion_slerp(quat0, quat1, fraction, spin=0, shortestpath=True):
- """Return spherical linear interpolation between two quaternions.
+ """Return spherical linear interpolation between two quaternions.
>>> q0 = random_quaternion()
>>> q1 = random_quaternion()
@@ -1248,31 +1233,31 @@ def quaternion_slerp(quat0, quat1, fraction, spin=0, shortestpath=True):
True
"""
- q0 = unit_vector(quat0[:4])
- q1 = unit_vector(quat1[:4])
- if fraction == 0.0:
- return q0
- elif fraction == 1.0:
- return q1
- d = numpy.dot(q0, q1)
- if abs(abs(d) - 1.0) < _EPS:
- return q0
- if shortestpath and d < 0.0:
- # invert rotation
- d = -d
- numpy.negative(q1, q1)
- angle = math.acos(d) + spin * math.pi
- if abs(angle) < _EPS:
- return q0
- isin = 1.0 / math.sin(angle)
- q0 *= math.sin((1.0 - fraction) * angle) * isin
- q1 *= math.sin(fraction * angle) * isin
- q0 += q1
+ q0 = unit_vector(quat0[:4])
+ q1 = unit_vector(quat1[:4])
+ if fraction == 0.0:
+ return q0
+ elif fraction == 1.0:
+ return q1
+ d = numpy.dot(q0, q1)
+ if abs(abs(d) - 1.0) < _EPS:
+ return q0
+ if shortestpath and d < 0.0:
+ # invert rotation
+ d = -d
+ numpy.negative(q1, q1)
+ angle = math.acos(d) + spin * math.pi
+ if abs(angle) < _EPS:
return q0
+ isin = 1.0 / math.sin(angle)
+ q0 *= math.sin((1.0 - fraction) * angle) * isin
+ q1 *= math.sin(fraction * angle) * isin
+ q0 += q1
+ return q0
def random_quaternion(rand=None):
- """Return uniform random unit quaternion.
+ """Return uniform random unit quaternion.
rand: array like or None
Three independent random variables that are uniformly distributed
@@ -1286,21 +1271,24 @@ def random_quaternion(rand=None):
(1, True)
"""
- if rand is None:
- rand = numpy.random.rand(3)
- else:
- assert len(rand) == 3
- r1 = numpy.sqrt(1.0 - rand[0])
- r2 = numpy.sqrt(rand[0])
- pi2 = math.pi * 2.0
- t1 = pi2 * rand[1]
- t2 = pi2 * rand[2]
- return numpy.array([numpy.cos(t2)*r2, numpy.sin(t1)*r1,
- numpy.cos(t1)*r1, numpy.sin(t2)*r2])
+ if rand is None:
+ rand = numpy.random.rand(3)
+ else:
+ assert len(rand) == 3
+ r1 = numpy.sqrt(1.0 - rand[0])
+ r2 = numpy.sqrt(rand[0])
+ pi2 = math.pi * 2.0
+ t1 = pi2 * rand[1]
+ t2 = pi2 * rand[2]
+ return numpy.array(
+ [numpy.cos(t2) * r2,
+ numpy.sin(t1) * r1,
+ numpy.cos(t1) * r1,
+ numpy.sin(t2) * r2])
def random_rotation_matrix(rand=None):
- """Return uniform random rotation matrix.
+ """Return uniform random rotation matrix.
rand: array like
Three independent random variables that are uniformly distributed
@@ -1311,7 +1299,7 @@ def random_rotation_matrix(rand=None):
True
"""
- return quaternion_matrix(random_quaternion(rand))
+ return quaternion_matrix(random_quaternion(rand))
# epsilon for testing whether a number is close to zero
@@ -1322,20 +1310,37 @@ _NEXT_AXIS = [1, 2, 0, 1]
# map axes strings to/from tuples of inner axis, parity, repetition, frame
_AXES2TUPLE = {
- 'sxyz': (0, 0, 0, 0), 'sxyx': (0, 0, 1, 0), 'sxzy': (0, 1, 0, 0),
- 'sxzx': (0, 1, 1, 0), 'syzx': (1, 0, 0, 0), 'syzy': (1, 0, 1, 0),
- 'syxz': (1, 1, 0, 0), 'syxy': (1, 1, 1, 0), 'szxy': (2, 0, 0, 0),
- 'szxz': (2, 0, 1, 0), 'szyx': (2, 1, 0, 0), 'szyz': (2, 1, 1, 0),
- 'rzyx': (0, 0, 0, 1), 'rxyx': (0, 0, 1, 1), 'ryzx': (0, 1, 0, 1),
- 'rxzx': (0, 1, 1, 1), 'rxzy': (1, 0, 0, 1), 'ryzy': (1, 0, 1, 1),
- 'rzxy': (1, 1, 0, 1), 'ryxy': (1, 1, 1, 1), 'ryxz': (2, 0, 0, 1),
- 'rzxz': (2, 0, 1, 1), 'rxyz': (2, 1, 0, 1), 'rzyz': (2, 1, 1, 1)}
+ 'sxyz': (0, 0, 0, 0),
+ 'sxyx': (0, 0, 1, 0),
+ 'sxzy': (0, 1, 0, 0),
+ 'sxzx': (0, 1, 1, 0),
+ 'syzx': (1, 0, 0, 0),
+ 'syzy': (1, 0, 1, 0),
+ 'syxz': (1, 1, 0, 0),
+ 'syxy': (1, 1, 1, 0),
+ 'szxy': (2, 0, 0, 0),
+ 'szxz': (2, 0, 1, 0),
+ 'szyx': (2, 1, 0, 0),
+ 'szyz': (2, 1, 1, 0),
+ 'rzyx': (0, 0, 0, 1),
+ 'rxyx': (0, 0, 1, 1),
+ 'ryzx': (0, 1, 0, 1),
+ 'rxzx': (0, 1, 1, 1),
+ 'rxzy': (1, 0, 0, 1),
+ 'ryzy': (1, 0, 1, 1),
+ 'rzxy': (1, 1, 0, 1),
+ 'ryxy': (1, 1, 1, 1),
+ 'ryxz': (2, 0, 0, 1),
+ 'rzxz': (2, 0, 1, 1),
+ 'rxyz': (2, 1, 0, 1),
+ 'rzyz': (2, 1, 1, 1)
+}
_TUPLE2AXES = dict((v, k) for k, v in _AXES2TUPLE.items())
def vector_norm(data, axis=None, out=None):
- """Return length, i.e. Euclidean norm, of ndarray along axis.
+ """Return length, i.e. Euclidean norm, of ndarray along axis.
>>> v = numpy.random.random(3)
>>> n = vector_norm(v)
@@ -1359,22 +1364,22 @@ def vector_norm(data, axis=None, out=None):
1.0
"""
- data = numpy.array(data, dtype=numpy.float64, copy=True)
- if out is None:
- if data.ndim == 1:
- return math.sqrt(numpy.dot(data, data))
- data *= data
- out = numpy.atleast_1d(numpy.sum(data, axis=axis))
- numpy.sqrt(out, out)
- return out
- else:
- data *= data
- numpy.sum(data, axis=axis, out=out)
- numpy.sqrt(out, out)
+ data = numpy.array(data, dtype=numpy.float64, copy=True)
+ if out is None:
+ if data.ndim == 1:
+ return math.sqrt(numpy.dot(data, data))
+ data *= data
+ out = numpy.atleast_1d(numpy.sum(data, axis=axis))
+ numpy.sqrt(out, out)
+ return out
+ else:
+ data *= data
+ numpy.sum(data, axis=axis, out=out)
+ numpy.sqrt(out, out)
def unit_vector(data, axis=None, out=None):
- """Return ndarray normalized by length, i.e. Euclidean norm, along axis.
+ """Return ndarray normalized by length, i.e. Euclidean norm, along axis.
>>> v0 = numpy.random.random(3)
>>> v1 = unit_vector(v0)
@@ -1399,26 +1404,26 @@ def unit_vector(data, axis=None, out=None):
[1.0]
"""
- if out is None:
- data = numpy.array(data, dtype=numpy.float64, copy=True)
- if data.ndim == 1:
- data /= math.sqrt(numpy.dot(data, data))
- return data
- else:
- if out is not data:
- out[:] = numpy.array(data, copy=False)
- data = out
- length = numpy.atleast_1d(numpy.sum(data*data, axis))
- numpy.sqrt(length, length)
- if axis is not None:
- length = numpy.expand_dims(length, axis)
- data /= length
- if out is None:
- return data
+ if out is None:
+ data = numpy.array(data, dtype=numpy.float64, copy=True)
+ if data.ndim == 1:
+ data /= math.sqrt(numpy.dot(data, data))
+ return data
+ else:
+ if out is not data:
+ out[:] = numpy.array(data, copy=False)
+ data = out
+ length = numpy.atleast_1d(numpy.sum(data * data, axis))
+ numpy.sqrt(length, length)
+ if axis is not None:
+ length = numpy.expand_dims(length, axis)
+ data /= length
+ if out is None:
+ return data
def random_vector(size):
- """Return array of random doubles in the half-open interval [0.0, 1.0).
+ """Return array of random doubles in the half-open interval [0.0, 1.0).
>>> v = random_vector(10000)
>>> numpy.all(v >= 0) and numpy.all(v < 1)
@@ -1429,11 +1434,11 @@ def random_vector(size):
False
"""
- return numpy.random.random(size)
+ return numpy.random.random(size)
def vector_product(v0, v1, axis=0):
- """Return vector perpendicular to vectors.
+ """Return vector perpendicular to vectors.
>>> v = vector_product([2, 0, 0], [0, 3, 0])
>>> numpy.allclose(v, [0, 0, 6])
@@ -1450,11 +1455,11 @@ def vector_product(v0, v1, axis=0):
True
"""
- return numpy.cross(v0, v1, axis=axis)
+ return numpy.cross(v0, v1, axis=axis)
def angle_between_vectors(v0, v1, directed=True, axis=0):
- """Return angle between vectors.
+ """Return angle between vectors.
If directed is False, the input vectors are interpreted as undirected axes,
i.e. the maximum angle is pi/2.
@@ -1477,16 +1482,16 @@ def angle_between_vectors(v0, v1, directed=True, axis=0):
True
"""
- v0 = numpy.array(v0, dtype=numpy.float64, copy=False)
- v1 = numpy.array(v1, dtype=numpy.float64, copy=False)
- dot = numpy.sum(v0 * v1, axis=axis)
- dot /= vector_norm(v0, axis=axis) * vector_norm(v1, axis=axis)
- dot = numpy.clip(dot, -1.0, 1.0)
- return numpy.arccos(dot if directed else numpy.fabs(dot))
+ v0 = numpy.array(v0, dtype=numpy.float64, copy=False)
+ v1 = numpy.array(v1, dtype=numpy.float64, copy=False)
+ dot = numpy.sum(v0 * v1, axis=axis)
+ dot /= vector_norm(v0, axis=axis) * vector_norm(v1, axis=axis)
+ dot = numpy.clip(dot, -1.0, 1.0)
+ return numpy.arccos(dot if directed else numpy.fabs(dot))
def inverse_matrix(matrix):
- """Return inverse of square transformation matrix.
+ """Return inverse of square transformation matrix.
>>> M0 = random_rotation_matrix()
>>> M1 = inverse_matrix(M0.T)
@@ -1498,11 +1503,11 @@ def inverse_matrix(matrix):
... if not numpy.allclose(M1, numpy.linalg.inv(M0)): print(size)
"""
- return numpy.linalg.inv(matrix)
+ return numpy.linalg.inv(matrix)
def concatenate_matrices(*matrices):
- """Return concatenation of series of transformation matrices.
+ """Return concatenation of series of transformation matrices.
>>> M = numpy.random.rand(16).reshape((4, 4)) - 0.5
>>> numpy.allclose(M, concatenate_matrices(M))
@@ -1511,14 +1516,14 @@ def concatenate_matrices(*matrices):
True
"""
- M = numpy.identity(4)
- for i in matrices:
- M = numpy.dot(M, i)
- return M
+ M = numpy.identity(4)
+ for i in matrices:
+ M = numpy.dot(M, i)
+ return M
def is_same_transform(matrix0, matrix1):
- """Return True if two matrices perform same transformation.
+ """Return True if two matrices perform same transformation.
>>> is_same_transform(numpy.identity(4), numpy.identity(4))
True
@@ -1526,22 +1531,22 @@ def is_same_transform(matrix0, matrix1):
False
"""
- matrix0 = numpy.array(matrix0, dtype=numpy.float64, copy=True)
- matrix0 /= matrix0[3, 3]
- matrix1 = numpy.array(matrix1, dtype=numpy.float64, copy=True)
- matrix1 /= matrix1[3, 3]
- return numpy.allclose(matrix0, matrix1)
+ matrix0 = numpy.array(matrix0, dtype=numpy.float64, copy=True)
+ matrix0 /= matrix0[3, 3]
+ matrix1 = numpy.array(matrix1, dtype=numpy.float64, copy=True)
+ matrix1 /= matrix1[3, 3]
+ return numpy.allclose(matrix0, matrix1)
def is_same_quaternion(q0, q1):
- """Return True if two quaternions are equal."""
- q0 = numpy.array(q0)
- q1 = numpy.array(q1)
- return numpy.allclose(q0, q1) or numpy.allclose(q0, -q1)
+ """Return True if two quaternions are equal."""
+ q0 = numpy.array(q0)
+ q1 = numpy.array(q1)
+ return numpy.allclose(q0, q1) or numpy.allclose(q0, -q1)
def _import_module(name, package=None, warn=True, postfix='_py', ignore='_'):
- """Try import all public attributes from module into global namespace.
+ """Try import all public attributes from module into global namespace.
Existing attributes with name clashes are renamed with prefix.
Attributes starting with underscore are ignored by default.
@@ -1549,32 +1554,31 @@ def _import_module(name, package=None, warn=True, postfix='_py', ignore='_'):
Return True on successful import.
"""
- import warnings
- from importlib import import_module
- try:
- if not package:
- module = import_module(name)
- else:
- module = import_module('.' + name, package=package)
- except ImportError as err:
- if warn:
- warnings.warn(str(err))
+ import warnings
+ from importlib import import_module
+ try:
+ if not package:
+ module = import_module(name)
else:
- for attr in dir(module):
- if ignore and attr.startswith(ignore):
- continue
- if postfix:
- if attr in globals():
- globals()[attr + postfix] = globals()[attr]
- elif warn:
- warnings.warn('no Python implementation of ' + attr)
- globals()[attr] = getattr(module, attr)
- return True
+ module = import_module('.' + name, package=package)
+ except ImportError as err:
+ if warn:
+ warnings.warn(str(err))
+ else:
+ for attr in dir(module):
+ if ignore and attr.startswith(ignore):
+ continue
+ if postfix:
+ if attr in globals():
+ globals()[attr + postfix] = globals()[attr]
+ elif warn:
+ warnings.warn('no Python implementation of ' + attr)
+ globals()[attr] = getattr(module, attr)
+ return True
# _import_module('_transformations', __package__)
-
# if __name__ == '__main__':
# import doctest
# import random # noqa: used in doctests
@@ -1582,4 +1586,4 @@ def _import_module(name, package=None, warn=True, postfix='_py', ignore='_'):
# numpy.set_printoptions(suppress=True, precision=5, legacy='1.13')
# except TypeError:
# numpy.set_printoptions(suppress=True, precision=5)
-# doctest.testmod() \ No newline at end of file
+# doctest.testmod()
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/mpi_run.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/mpi_run.py
index 85d70abb1..0d30f5d5e 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/mpi_run.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/mpi_run.py
@@ -3,21 +3,23 @@ import subprocess
from pybullet_utils.arg_parser import ArgParser
from pybullet_utils.logger import Logger
+
def main():
- # Command line arguments
- args = sys.argv[1:]
- arg_parser = ArgParser()
- arg_parser.load_args(args)
+ # Command line arguments
+ args = sys.argv[1:]
+ arg_parser = ArgParser()
+ arg_parser.load_args(args)
+
+ num_workers = arg_parser.parse_int('num_workers', 1)
+ assert (num_workers > 0)
- num_workers = arg_parser.parse_int('num_workers', 1)
- assert(num_workers > 0)
+ Logger.print2('Running with {:d} workers'.format(num_workers))
+ cmd = 'mpiexec -n {:d} python3 DeepMimic_Optimizer.py '.format(num_workers)
+ cmd += ' '.join(args)
+ Logger.print2('cmd: ' + cmd)
+ subprocess.call(cmd, shell=True)
+ return
- Logger.print2('Running with {:d} workers'.format(num_workers))
- cmd = 'mpiexec -n {:d} python3 DeepMimic_Optimizer.py '.format(num_workers)
- cmd += ' '.join(args)
- Logger.print2('cmd: ' + cmd)
- subprocess.call(cmd, shell=True)
- return
if __name__ == '__main__':
- main()
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/testrl.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/testrl.py
index 38a9469e9..1693fe7d4 100644
--- a/examples/pybullet/gym/pybullet_envs/deep_mimic/testrl.py
+++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/testrl.py
@@ -2,8 +2,8 @@ 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)
-print("parentdir=",parentdir)
+os.sys.path.insert(0, parentdir)
+print("parentdir=", parentdir)
import json
from pybullet_envs.deep_mimic.learning.rl_world import RLWorld
from pybullet_envs.deep_mimic.learning.ppo_agent import PPOAgent
@@ -15,81 +15,78 @@ from pybullet_envs.deep_mimic.env.pybullet_deep_mimic_env import PyBulletDeepMim
import sys
import random
-update_timestep = 1./240.
+update_timestep = 1. / 240.
animating = True
+
def update_world(world, time_elapsed):
- timeStep = update_timestep
- world.update(timeStep)
- reward = world.env.calc_reward(agent_id=0)
- #print("reward=",reward)
- end_episode = world.env.is_episode_end()
- if (end_episode):
- world.end_episode()
- world.reset()
- return
+ timeStep = update_timestep
+ world.update(timeStep)
+ reward = world.env.calc_reward(agent_id=0)
+ #print("reward=",reward)
+ end_episode = world.env.is_episode_end()
+ if (end_episode):
+ world.end_episode()
+ world.reset()
+ return
+
def build_arg_parser(args):
- arg_parser = ArgParser()
- arg_parser.load_args(args)
+ arg_parser = ArgParser()
+ arg_parser.load_args(args)
- arg_file = arg_parser.parse_string('arg_file', '')
- if (arg_file != ''):
- path = pybullet_data.getDataPath()+"/args/"+arg_file
- succ = arg_parser.load_file(path)
- Logger.print2(arg_file)
- assert succ, Logger.print2('Failed to load args from: ' + arg_file)
- return arg_parser
+ arg_file = arg_parser.parse_string('arg_file', '')
+ if (arg_file != ''):
+ path = pybullet_data.getDataPath() + "/args/" + arg_file
+ succ = arg_parser.load_file(path)
+ Logger.print2(arg_file)
+ assert succ, Logger.print2('Failed to load args from: ' + arg_file)
+ return arg_parser
-args = sys.argv[1:]
+args = sys.argv[1:]
def build_world(args, enable_draw):
- arg_parser = build_arg_parser(args)
- print("enable_draw=",enable_draw)
- env = PyBulletDeepMimicEnv(arg_parser, enable_draw)
- world = RLWorld(env, arg_parser)
- #world.env.set_playback_speed(playback_speed)
-
- motion_file = arg_parser.parse_string("motion_file")
- print("motion_file=",motion_file)
- bodies = arg_parser.parse_ints("fall_contact_bodies")
- print("bodies=",bodies)
- int_output_path = arg_parser.parse_string("int_output_path")
- print("int_output_path=",int_output_path)
- agent_files = pybullet_data.getDataPath()+"/"+arg_parser.parse_string("agent_files")
-
- AGENT_TYPE_KEY = "AgentType"
-
- print("agent_file=",agent_files)
- with open(agent_files) as data_file:
- json_data = json.load(data_file)
- print("json_data=",json_data)
- assert AGENT_TYPE_KEY in json_data
- agent_type = json_data[AGENT_TYPE_KEY]
- print("agent_type=",agent_type)
- agent = PPOAgent(world, id, json_data)
-
- agent.set_enable_training(False)
- world.reset()
- return world
-
-
-
-
-
+ arg_parser = build_arg_parser(args)
+ print("enable_draw=", enable_draw)
+ env = PyBulletDeepMimicEnv(arg_parser, enable_draw)
+ world = RLWorld(env, arg_parser)
+ #world.env.set_playback_speed(playback_speed)
+
+ motion_file = arg_parser.parse_string("motion_file")
+ print("motion_file=", motion_file)
+ bodies = arg_parser.parse_ints("fall_contact_bodies")
+ print("bodies=", bodies)
+ int_output_path = arg_parser.parse_string("int_output_path")
+ print("int_output_path=", int_output_path)
+ agent_files = pybullet_data.getDataPath() + "/" + arg_parser.parse_string("agent_files")
+
+ AGENT_TYPE_KEY = "AgentType"
+
+ print("agent_file=", agent_files)
+ with open(agent_files) as data_file:
+ json_data = json.load(data_file)
+ print("json_data=", json_data)
+ assert AGENT_TYPE_KEY in json_data
+ agent_type = json_data[AGENT_TYPE_KEY]
+ print("agent_type=", agent_type)
+ agent = PPOAgent(world, id, json_data)
+
+ agent.set_enable_training(False)
+ world.reset()
+ return world
+
+
if __name__ == '__main__':
-
- world = build_world(args, True)
- while (world.env._pybullet_client.isConnected()):
- timeStep = update_timestep
- keys = world.env.getKeyboardEvents()
-
-
- if world.env.isKeyTriggered(keys, ' '):
- animating = not animating
- if (animating):
- update_world(world, timeStep)
- #animating=False
+ world = build_world(args, True)
+ while (world.env._pybullet_client.isConnected()):
+ timeStep = update_timestep
+ keys = world.env.getKeyboardEvents()
+
+ if world.env.isKeyTriggered(keys, ' '):
+ animating = not animating
+ if (animating):
+ update_world(world, timeStep)
+ #animating=False
diff --git a/examples/pybullet/gym/pybullet_envs/env_bases.py b/examples/pybullet/gym/pybullet_envs/env_bases.py
index aeef7fda5..a352ebe4c 100644
--- a/examples/pybullet/gym/pybullet_envs/env_bases.py
+++ b/examples/pybullet/gym/pybullet_envs/env_bases.py
@@ -5,134 +5,134 @@ from pybullet_utils import bullet_client
from pkg_resources import parse_version
+
class MJCFBaseBulletEnv(gym.Env):
- """
+ """
Base class for Bullet physics simulation loading MJCF (MuJoCo .xml) environments in a Scene.
These environments create single-player scenes and behave like normal Gym environments, if
you don't use multiplayer.
"""
- metadata = {
- 'render.modes': ['human', 'rgb_array'],
- 'video.frames_per_second': 60
- }
-
- def __init__(self, robot, render=False):
- self.scene = None
- self.physicsClientId = -1
- self.ownsPhysicsClient = 0
- self.camera = Camera()
- self.isRender = render
- self.robot = robot
- self.seed()
- self._cam_dist = 3
- self._cam_yaw = 0
- self._cam_pitch = -30
- self._render_width =320
- self._render_height = 240
-
- self.action_space = robot.action_space
- self.observation_space = robot.observation_space
-
- def configure(self, args):
- self.robot.args = args
-
- def seed(self, seed=None):
- self.np_random, seed = gym.utils.seeding.np_random(seed)
- self.robot.np_random = self.np_random # use the same np_randomizer for robot as for env
- return [seed]
-
- def reset(self):
- if (self.physicsClientId<0):
- self.ownsPhysicsClient = True
-
- if self.isRender:
- self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
- else:
- self._p = bullet_client.BulletClient()
-
- self.physicsClientId = self._p._client
- self._p.configureDebugVisualizer(pybullet.COV_ENABLE_GUI,0)
-
- if self.scene is None:
- self.scene = self.create_single_player_scene(self._p)
- if not self.scene.multiplayer and self.ownsPhysicsClient:
- self.scene.episode_restart(self._p)
-
- self.robot.scene = self.scene
-
- self.frame = 0
- self.done = 0
- self.reward = 0
- dump = 0
- s = self.robot.reset(self._p)
- self.potential = self.robot.calc_potential()
- return s
-
- def render(self, mode='human', close=False):
- if mode == "human":
- self.isRender = True
- if mode != "rgb_array":
- return np.array([])
-
- base_pos=[0,0,0]
- if (hasattr(self,'robot')):
- if (hasattr(self.robot,'body_xyz')):
- base_pos = self.robot.body_xyz
-
- view_matrix = self._p.computeViewMatrixFromYawPitchRoll(
- cameraTargetPosition=base_pos,
- distance=self._cam_dist,
- yaw=self._cam_yaw,
- pitch=self._cam_pitch,
- roll=0,
- upAxisIndex=2)
- proj_matrix = self._p.computeProjectionMatrixFOV(
- fov=60, aspect=float(self._render_width)/self._render_height,
- nearVal=0.1, farVal=100.0)
- (_, _, px, _, _) = self._p.getCameraImage(
- width=self._render_width, height=self._render_height, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix,
- renderer=pybullet.ER_BULLET_HARDWARE_OPENGL
- )
- rgb_array = np.array(px)
- rgb_array = np.reshape(np.array(px), (self._render_height, self._render_width, -1))
- rgb_array = rgb_array[:, :, :3]
- return rgb_array
-
-
- def close(self):
- if (self.ownsPhysicsClient):
- if (self.physicsClientId>=0):
- self._p.disconnect()
- self.physicsClientId = -1
-
- def HUD(self, state, a, done):
- pass
-
- # def step(self, *args, **kwargs):
- # if self.isRender:
- # base_pos=[0,0,0]
- # if (hasattr(self,'robot')):
- # if (hasattr(self.robot,'body_xyz')):
- # base_pos = self.robot.body_xyz
- # # Keep the previous orientation of the camera set by the user.
- # #[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
- # self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
- #
- #
- # return self.step(*args, **kwargs)
- if parse_version(gym.__version__) < parse_version('0.9.6'):
- _render = render
- _reset = reset
- _seed = seed
+ metadata = {'render.modes': ['human', 'rgb_array'], 'video.frames_per_second': 60}
+
+ def __init__(self, robot, render=False):
+ self.scene = None
+ self.physicsClientId = -1
+ self.ownsPhysicsClient = 0
+ self.camera = Camera()
+ self.isRender = render
+ self.robot = robot
+ self.seed()
+ self._cam_dist = 3
+ self._cam_yaw = 0
+ self._cam_pitch = -30
+ self._render_width = 320
+ self._render_height = 240
+
+ self.action_space = robot.action_space
+ self.observation_space = robot.observation_space
+
+ def configure(self, args):
+ self.robot.args = args
+
+ def seed(self, seed=None):
+ self.np_random, seed = gym.utils.seeding.np_random(seed)
+ self.robot.np_random = self.np_random # use the same np_randomizer for robot as for env
+ return [seed]
+
+ def reset(self):
+ if (self.physicsClientId < 0):
+ self.ownsPhysicsClient = True
+
+ if self.isRender:
+ self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
+ else:
+ self._p = bullet_client.BulletClient()
+
+ self.physicsClientId = self._p._client
+ self._p.configureDebugVisualizer(pybullet.COV_ENABLE_GUI, 0)
+
+ if self.scene is None:
+ self.scene = self.create_single_player_scene(self._p)
+ if not self.scene.multiplayer and self.ownsPhysicsClient:
+ self.scene.episode_restart(self._p)
+
+ self.robot.scene = self.scene
+
+ self.frame = 0
+ self.done = 0
+ self.reward = 0
+ dump = 0
+ s = self.robot.reset(self._p)
+ self.potential = self.robot.calc_potential()
+ return s
+
+ def render(self, mode='human', close=False):
+ if mode == "human":
+ self.isRender = True
+ if mode != "rgb_array":
+ return np.array([])
+
+ base_pos = [0, 0, 0]
+ if (hasattr(self, 'robot')):
+ if (hasattr(self.robot, 'body_xyz')):
+ base_pos = self.robot.body_xyz
+
+ view_matrix = self._p.computeViewMatrixFromYawPitchRoll(cameraTargetPosition=base_pos,
+ distance=self._cam_dist,
+ yaw=self._cam_yaw,
+ pitch=self._cam_pitch,
+ roll=0,
+ upAxisIndex=2)
+ proj_matrix = self._p.computeProjectionMatrixFOV(fov=60,
+ aspect=float(self._render_width) /
+ self._render_height,
+ nearVal=0.1,
+ farVal=100.0)
+ (_, _, px, _, _) = self._p.getCameraImage(width=self._render_width,
+ height=self._render_height,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
+ rgb_array = np.array(px)
+ rgb_array = np.reshape(np.array(px), (self._render_height, self._render_width, -1))
+ rgb_array = rgb_array[:, :, :3]
+ return rgb_array
+
+ def close(self):
+ if (self.ownsPhysicsClient):
+ if (self.physicsClientId >= 0):
+ self._p.disconnect()
+ self.physicsClientId = -1
+
+ def HUD(self, state, a, done):
+ pass
+
+ # def step(self, *args, **kwargs):
+ # if self.isRender:
+ # base_pos=[0,0,0]
+ # if (hasattr(self,'robot')):
+ # if (hasattr(self.robot,'body_xyz')):
+ # base_pos = self.robot.body_xyz
+ # # Keep the previous orientation of the camera set by the user.
+ # #[yaw, pitch, dist] = self._p.getDebugVisualizerCamera()[8:11]
+ # self._p.resetDebugVisualizerCamera(3,0,0, base_pos)
+ #
+ #
+ # return self.step(*args, **kwargs)
+ if parse_version(gym.__version__) < parse_version('0.9.6'):
+ _render = render
+ _reset = reset
+ _seed = seed
+
class Camera:
- def __init__(self):
- pass
-
- def move_and_look_at(self,i,j,k,x,y,z):
- lookat = [x,y,z]
- distance = 10
- yaw = 10
- self._p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)
+
+ def __init__(self):
+ pass
+
+ def move_and_look_at(self, i, j, k, x, y, z):
+ lookat = [x, y, z]
+ distance = 10
+ yaw = 10
+ self._p.resetDebugVisualizerCamera(distance, yaw, -20, lookat)
diff --git a/examples/pybullet/gym/pybullet_envs/examples/dominoes.py b/examples/pybullet/gym/pybullet_envs/examples/dominoes.py
index c96c07ebd..e27f6aec9 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/dominoes.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/dominoes.py
@@ -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.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)
-
-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):
+p #.setPhysicsEngineParameter(numSolverIterations=10, fixedTimeStep=0.01)
+
+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)
+
+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):
#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.configureDebugVisualizer(p.COV_ENABLE_RENDERING, 1)
-p.setGravity(0,0,-9.8)
+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.) \ No newline at end of file
+ time.sleep(1. / 240.)
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py
index 6b1379c16..9fc5d7962 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_AntBulletEnv_v0_2017may.py
@@ -3,300 +3,2167 @@ 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
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], 128)
- assert weights_dense2_w.shape == (128, 64)
- assert weights_final_w.shape == (64, 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], 128)
+ assert weights_dense2_w.shape == (128, 64)
+ assert weights_final_w.shape == (64, 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():
- pybullet.connect(pybullet.DIRECT)
- env = gym.make("AntBulletEnv-v0")
- env.render(mode="human")
-
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
- env.reset()
+ pybullet.connect(pybullet.DIRECT)
+ env = gym.make("AntBulletEnv-v0")
+ env.render(mode="human")
+
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ env.reset()
+
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ obs = env.reset()
while 1:
- frame = 0
- score = 0
- restart_delay = 0
- obs = env.reset()
-
- while 1:
- time.sleep(1./60.)
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- #print("reward")
- #print(r)
- score += r
- frame += 1
- distance=5
- yaw = 0
+ time.sleep(1. / 60.)
+ a = pi.act(obs)
+ obs, r, done, _ = env.step(a)
+ #print("reward")
+ #print(r)
+ score += r
+ frame += 1
+ distance = 5
+ yaw = 0
- 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
+ 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.2856, -0.4091, +0.3380, -0.1083, +0.1049, -0.0806, -0.0827, +0.0402, +0.2415, +0.0927, +0.1812, +0.5455, +0.3157, +0.1043, +0.0527, +0.3768, -0.2083, +0.1218, -0.0633, +0.3236, +0.2198, +0.0513, +0.3505, -0.1165, -0.1732, +0.2760, +0.0006, +0.0249, +0.5887, -0.2324, +0.1503, -0.0108, +0.1220, +0.2527, +0.0984, +0.5360, -0.0579, -0.0847, +0.1649, +0.0589, -0.2046, +0.5981, -0.1063, -0.1088, +0.3424, +0.3479, -0.1751, +0.2924, -0.0610, +0.0807, +0.3291, +0.0059, +0.0339, -0.2823, +0.2533, +0.3156, +0.1679, +0.2417, +0.1265, +0.0024, +0.0802, +0.2531, -0.2576, +0.3894, +0.3206, +0.2015, +0.3482, +0.1042, -0.2418, -0.0002, +0.1277, +0.1811, +0.1551, +0.5460, +0.1714, +0.1021, -0.1252, +0.0609, -0.0372, -0.0351, +0.1216, +0.0023, -0.2448, +0.0077, +0.0584, +0.2389, -0.0848, +0.3542, +0.3065, -0.2268, +0.2387, +0.3303, +0.4184, -0.1619, +0.2230, +0.2829, +0.3884, +0.1262, +0.6383, -0.1629, +0.3087, +0.0554, +0.2294, +0.0280, +0.4139, -0.1484, +0.1358, +0.3153, -0.2652, +0.2637, -0.1563, +0.0706, +0.4192, +0.2381, -0.3540, +0.2789, +0.2647, +0.0931, +0.1439, +0.3415, -0.2445, +0.1039, -0.3692, +0.5095, +0.0010, +0.0777, +0.3382, -0.1100],
-[ +0.0820, +0.6327, +1.0135, -0.1423, -0.0275, +0.0396, -0.5933, +0.3027, -0.2220, +0.1476, -0.0591, -0.7910, -0.0776, +0.2565, +0.0241, -1.1300, +0.1324, +0.9079, +0.2318, +0.5574, +1.0162, +0.1408, +0.7525, +0.3612, +0.6088, -0.2541, +0.8134, +0.1348, -0.1265, +0.7991, -0.2304, -0.4826, -0.4123, +0.2831, -0.5457, -0.3518, -0.9733, -0.1654, +0.2409, +0.3971, +0.6624, +0.0728, +0.2200, -0.2126, -0.5299, -0.1858, -0.3467, -0.2776, -0.2004, -0.7567, +0.4417, -0.4378, -0.6799, +0.3789, +0.2937, -0.1247, +0.5540, -1.0124, -0.5759, +0.0308, +0.2971, +1.1300, -0.1185, +0.5303, +0.0527, +0.3392, +0.7436, -0.3578, -0.0559, +0.2165, -0.5860, +0.9427, -0.2522, -0.0805, +0.9314, +1.4173, +0.6216, +0.6923, +0.6592, -0.0457, +0.5152, -0.3523, -0.5135, +0.6466, -0.4804, +0.0006, +0.3223, -0.1548, +1.5508, +0.6204, +0.2618, -0.0392, -0.6208, +0.0237, +0.0577, -0.2913, -0.3893, -0.1459, -0.1103, +0.7485, -0.0045, +0.0640, +0.0726, -0.0966, +0.0452, +0.2741, -0.3389, +0.8830, +0.9819, +0.3915, -0.1127, -0.2653, -0.6842, +0.2389, -0.4349, +1.4013, -0.4442, +1.1846, -0.7550, +0.5812, -0.2940, +0.7046, +0.4730, -0.2155, +0.1432, +0.1518, +0.5336, -0.0827],
-[ -0.2503, +0.2354, -0.0468, +0.1318, -0.0161, +0.1235, -0.1649, -0.1380, -0.1816, -0.0953, -0.0303, -0.4337, +0.0159, -0.2893, -0.1178, -0.1779, +0.0557, -0.0788, -0.1745, -0.1349, +0.1942, +0.1707, -0.3289, +0.1177, -0.3084, +0.0423, +0.0006, -0.1240, -0.2685, -0.0578, +0.3282, -0.3570, +0.0039, +0.3399, -0.3599, -0.3346, -0.2273, -0.0044, -0.0425, -0.2483, -0.2284, -0.5528, -0.2406, -0.0144, -0.0306, +0.1037, +0.0497, -0.3302, +0.0505, +0.0054, -0.2037, -0.0112, +0.1068, -0.1273, +0.1019, -0.0463, -0.0527, -0.0015, -0.1546, -0.2187, +0.0633, -0.1969, -0.0954, -0.0111, -0.5329, +0.1480, -0.1007, +0.1115, -0.0692, -0.3348, +0.1361, -0.1606, -0.1103, -0.3221, -0.2678, -0.1543, -0.4900, -0.2455, -0.0798, -0.0545, +0.0848, +0.0149, -0.1908, +0.1721, +0.0687, -0.2002, -0.1194, +0.1023, -0.3005, -0.2030, -0.0681, -0.2440, -0.2892, -0.4305, -0.2357, +0.0932, -0.4055, -0.0629, -0.1043, -0.5354, -0.1120, -0.1867, -0.1219, -0.2403, -0.5562, -0.1247, -0.5158, -0.0720, -0.2935, -0.2138, +0.1382, +0.3068, -0.1444, +0.0100, -0.3312, -0.6305, +0.0030, -0.2372, -0.0005, -0.3775, +0.1123, +0.0166, -0.0000, -0.0605, -0.5071, +0.0482, -0.1440, -0.0311],
-[ -0.2697, +0.0706, +0.3032, -0.1729, +0.3361, -0.0424, -0.1621, -0.1890, +0.0724, -0.4940, +0.0174, +0.2439, -0.4449, +0.2452, -0.2110, +0.2058, -0.3416, -0.0957, +0.0431, +0.2706, +0.0075, -0.2335, -0.4697, -0.4996, -0.0722, -0.2389, -0.0721, -0.2428, +0.4497, +0.1403, +0.0491, +0.3252, -0.3800, -0.2324, +0.2014, +0.4212, +0.4495, -0.2843, +0.2277, +0.0246, -0.6231, -0.1313, -0.5353, -0.3726, -0.1220, -0.6917, -0.2465, -0.1089, -0.2945, +0.5820, -0.2255, +0.0518, +0.1999, +0.0492, +0.1157, -0.0289, -0.7021, +0.2170, +0.2487, -0.1803, -0.0788, -0.7116, +0.2452, +0.0250, +0.5466, -0.6420, -0.0797, -0.5767, -0.1020, +0.3390, -0.1549, +0.4149, +0.1835, +0.8112, -0.3514, +0.3155, -0.6475, -0.2191, +0.1377, +0.0273, -0.0859, +0.0621, -0.9109, -0.3396, +0.3122, -0.2752, -0.3375, -0.2920, +0.1554, -0.6032, -0.3321, +0.1136, -0.0712, -0.3951, +0.2268, -0.2402, +0.4850, +0.1052, +0.5524, -0.4844, +0.5053, +0.0377, -0.1097, +0.2861, -0.1864, -0.3226, -0.0154, -0.2144, -0.6764, -1.0064, -0.2201, -0.3494, -0.1009, -0.0346, +0.0222, -0.4648, -0.6888, +0.0936, -0.7490, +0.2389, -0.0461, -0.0490, -0.4350, -0.5020, -0.6949, +0.3147, +0.3905, -0.4302],
-[ -0.5894, -0.0462, -0.0671, +0.1779, -0.2985, -0.0093, +0.1025, -0.2851, -0.5022, +0.4617, -0.0050, -0.4186, -0.4120, +0.5342, -0.4466, -0.5710, -0.0778, +0.5455, +0.4230, -0.1727, +0.0248, +0.6199, -0.0249, -0.0536, -0.2538, -0.0548, -0.5637, +0.1861, -0.3756, +0.6562, -0.0309, -0.7059, -0.5196, -0.6593, -0.0786, -0.4255, -0.2951, -0.3396, +0.2999, +0.2590, +0.5004, +0.3659, -0.1944, -0.5518, -0.0093, +0.3915, -0.0654, +0.7140, -0.0118, -0.3306, +0.4059, -0.5650, -0.4346, +0.8268, -0.2418, -0.6769, -0.1529, -0.1019, -0.0935, -0.4321, +0.3257, -0.2702, -0.0989, +0.2711, -0.6210, +0.4389, +0.3887, -0.1652, -0.0982, +0.0433, -0.1120, +0.2608, +0.1155, -0.3326, -0.5094, +0.0474, +0.1239, -0.2204, -0.1056, -0.6978, +0.1862, -0.2300, -0.1165, +0.1509, +0.7566, -0.5543, +0.3839, -0.5120, +0.3099, -0.2034, +0.7276, +0.2385, -0.7288, -0.1266, -0.2343, -0.5672, -0.0057, -0.0186, -0.3665, -1.2855, +0.6746, -0.1203, -0.3309, -0.8603, +0.4811, -0.1538, +0.5446, +0.0038, +0.1556, +0.5776, -0.1994, -0.3110, -0.4141, +0.0772, +0.1195, +0.4368, +0.3796, +0.3990, -0.3452, +0.0268, -0.0037, -0.2803, +0.7420, -0.5205, +0.7103, +0.0814, +0.0917, +0.5727],
-[ +0.9108, -1.2019, -0.8828, -0.0571, +0.4640, -0.4255, -0.3412, -0.1130, +0.5679, -0.0657, +0.0851, -0.4367, -0.3447, -1.0903, -0.1277, +0.0440, +0.1664, +0.3279, -0.1176, -0.2553, -0.5594, -0.1823, +0.0093, -0.1161, +0.0341, -0.9688, -0.2799, +0.7136, +0.4686, -0.7197, -0.0798, -0.4068, -0.2519, +0.3220, +0.6010, +0.6546, -0.5138, +0.6600, -0.2747, -0.6502, +1.1478, +0.7705, -0.8645, -0.7124, +0.4578, -0.1423, -0.6454, -0.6139, -0.2964, -0.3525, +0.2287, -0.5368, -1.0776, -0.0507, -0.3517, -0.5014, -0.1767, -0.5016, +0.8044, -0.3985, +0.2099, +0.2479, -1.3310, +0.1198, +0.9254, -0.4103, +0.0248, -0.3546, +0.2374, +0.7145, -0.2494, -0.2125, -0.3934, +0.2301, -0.7252, +0.0734, +0.2172, +0.1852, -0.4918, -0.6549, +0.3549, +0.9117, -0.2437, +0.4721, +0.7126, +0.5653, +0.4648, -0.0169, -0.1650, +1.1287, +0.2412, +1.1366, +0.9122, +0.2840, -0.7930, +0.6158, -1.0912, +0.2805, +1.1295, -0.4873, +1.0141, -0.5452, +0.2255, +0.9590, +0.4029, -1.3217, +0.1508, +0.8827, -0.8346, +0.1531, -0.9785, -0.1839, +1.2149, +1.0538, +0.3230, +0.0808, -0.1425, -1.4677, +0.1845, +0.6411, -0.8535, +1.3519, -0.1753, +0.4364, -0.1985, -0.2911, +0.2662, -0.9084],
-[ +0.0887, -0.7902, -0.1326, +0.2560, +0.5971, +0.1597, +0.6151, -0.2445, -0.1579, +0.3995, +0.6582, +0.6882, +0.6858, -0.0499, +0.7302, -0.0497, -0.6517, +0.3105, -0.5837, +0.0370, -0.2824, +0.2725, +0.0053, -0.0114, +0.4586, +0.0917, -0.0565, -0.1905, +0.8068, -0.0370, +0.1055, -0.5045, +0.0999, +0.4123, +0.0117, -0.2204, -0.2399, -0.4052, -0.1977, -0.2043, -0.3355, -0.0034, +0.5239, -0.0669, -0.4476, +0.5272, +0.1968, -0.0636, -0.0077, +0.0786, +0.4349, +0.8252, -0.1576, -0.3040, +0.4199, +0.6836, +0.0844, -0.2492, +0.2916, -0.5348, +0.6261, -0.2533, +0.4726, +0.3358, -0.4089, +0.3682, -0.2293, +0.3252, +0.1088, -0.0533, +0.3884, -0.1629, +0.2775, -0.3031, -0.0119, +0.5219, -0.3374, -0.1560, +0.0500, +0.3756, +0.5114, -0.2009, +0.1710, -0.4174, +0.2280, -0.2902, +0.4603, +0.2395, -0.0964, +0.2353, -0.0310, -0.4563, -0.4219, -0.1862, -0.6264, -0.6686, +0.2240, +0.1773, +0.2184, -0.3676, +0.7615, +0.0471, +0.3136, -0.1120, -0.1764, -0.5694, +0.7293, -0.0837, +0.0061, -0.3985, -0.5278, -0.2859, +0.0929, -0.1284, -0.0300, -0.0944, -0.0390, +0.2991, -0.1451, +0.1105, -0.4419, -0.7432, -0.2460, -0.5057, +0.6673, +1.0114, +0.1792, +0.3065],
-[ -0.6564, +0.6125, -0.3640, +0.1619, -0.2321, +0.5720, +0.6131, -0.5911, +0.5526, +0.3226, -0.1944, -0.1839, +0.3572, +0.4781, +0.3407, +0.1641, +0.3172, -0.0047, -0.5162, -0.1206, -0.3861, +0.1791, -0.3154, +0.2562, -0.3293, +0.0456, +0.4672, -0.3446, -0.1234, +0.3884, +0.1968, -0.0986, +1.2169, +0.3088, +0.1092, -0.5128, -0.1868, +0.1527, -1.0628, +0.2786, +0.8325, +0.4390, +0.7205, +1.3926, +0.7260, +0.1448, +1.1186, -0.5237, +0.7353, +0.2267, -0.2913, +0.6712, -0.2731, +0.4048, +0.2022, +0.2905, -0.1395, +0.1775, +0.3433, +1.9090, -0.5115, -0.0573, +0.3704, -0.0411, -0.9364, -0.3512, -0.2041, +0.1542, +0.2627, -0.5482, +0.0865, +0.1783, -0.2311, -1.5702, -0.0176, +0.8767, -0.4654, -0.1130, -0.1795, +0.6021, +0.3102, -0.4057, +0.4632, -0.0942, +0.4566, +0.0989, -0.5076, -0.3882, +0.3039, +0.5014, -0.5293, -0.0868, -0.4451, -0.5433, -0.0461, -0.2973, +0.3207, -0.6808, -1.2056, +0.7728, +0.4685, +0.2351, +0.2659, -0.2359, -0.9062, +0.7528, -0.1476, +0.6847, +0.1755, -0.0489, +0.6044, +0.9700, -0.9183, +0.1199, +0.1771, -0.5627, -0.3509, -0.0693, +0.4640, -0.0557, +1.0644, -0.7226, +0.1818, -1.0610, -0.7919, +1.0787, -0.1449, +0.6288],
-[ -0.2821, +0.1942, +0.0717, -0.1533, +0.2884, +0.0299, -0.4759, +0.1094, +0.0928, -0.5330, -0.4834, +0.1220, +0.4441, +0.0950, -0.2181, -0.3184, -0.1734, +0.2083, -0.0679, +0.0449, +0.1293, -0.2203, -0.4006, +0.1973, +0.4127, -0.1489, +0.2313, +0.1979, -0.3278, -0.0182, +0.1668, +0.5720, +0.0830, -0.4511, -0.0183, +0.3112, -0.1480, +0.4522, -0.4363, -0.0033, +0.0456, -0.3984, -0.1388, -0.1651, -0.5918, +0.5272, -0.3076, +0.3667, -0.1151, +0.8332, +0.0800, -0.0647, -0.0477, -0.1672, -0.2390, +0.3837, -0.0609, +0.1687, +0.2350, +0.0576, +0.1809, -0.9367, +0.5738, +0.5234, +0.0063, +0.5833, -0.1264, -0.1810, +0.2093, +0.3804, +0.4890, +0.1374, -0.3955, -0.2193, -0.3411, -0.2258, +0.3689, -0.2886, +0.1800, +0.2246, -0.3125, +0.5031, -0.1732, +0.4497, -0.2867, +0.1692, +0.2127, +0.2622, -0.1449, +0.4516, +0.3948, -0.5770, -0.2663, +0.1198, -0.4118, -0.2319, +0.0458, +0.7989, -0.2666, +0.5099, +0.1698, -0.2164, -0.1695, -0.3694, +0.4706, +0.2198, +0.2426, +0.3539, +0.2527, -0.1951, -0.3628, +0.2259, +0.2184, +0.3123, +0.1581, -0.4492, -0.1066, +0.1484, +0.3531, +0.0580, +0.1617, +0.3627, -0.7292, -0.4043, -0.6717, +0.4356, -0.2808, -0.2858],
-[ -0.3475, -0.0438, +0.3943, -0.9454, -0.0676, +0.5420, +0.0486, -0.3051, -1.0394, -0.5628, +0.1000, +0.4686, +0.1047, +0.6092, -0.0295, -0.0841, -0.6189, -0.2652, +0.6656, +0.4027, -0.3481, +0.0851, +0.0883, +0.2802, -0.2617, -0.4973, +1.1301, -0.8747, -0.0359, +0.0684, -0.3017, -0.3851, +0.0739, +0.0212, -0.1619, -0.4641, -0.3448, -0.2891, -0.1347, -0.4114, +0.0257, -0.1971, -0.7760, -0.0600, -0.7219, -0.2177, -0.7149, -1.4175, +0.4650, +0.2970, +0.2164, +0.1605, +0.2960, -0.0941, -0.6133, -0.3279, +0.2995, -0.7627, -0.4375, -0.2131, +0.5522, -0.1457, +0.3077, +0.3471, +0.2723, -0.3329, +0.6586, -0.2858, -0.9763, -0.1005, +0.4768, -0.2830, +0.3709, +0.2231, -0.2970, -0.0227, +0.4660, +0.0485, -0.1268, +0.2986, -0.1887, -0.2624, +0.6477, -0.3838, +0.2028, +0.1874, -0.1547, -0.7356, -0.2964, -0.5112, +0.5242, -0.2078, -0.3975, -0.0907, +0.5330, +0.1397, -0.5146, +0.2458, +0.5131, +0.2961, -0.1090, -0.0372, +0.2060, -0.2964, +0.8767, +0.3651, +0.5461, +0.7021, -0.7075, -0.3400, -0.9134, -0.0393, +0.3066, +0.0670, -0.2127, -0.0001, -0.0257, +0.0683, +0.1032, -0.4013, +0.4372, +0.7734, -1.0677, -0.5434, +0.0179, +0.1156, +0.5057, -0.7392],
-[ +0.6845, -0.4383, +0.4872, +0.0337, -0.5214, +0.3372, -0.2544, +0.3252, +0.1244, -0.0537, +0.3436, +0.0441, -0.1664, -0.1286, +0.9051, +0.6243, +0.1279, -0.3978, -0.4463, -0.6320, -0.4879, -0.0646, -0.0833, -0.0981, -0.1637, -0.0102, -0.5135, -0.3484, -0.3294, +0.1523, +0.7086, +0.1241, +0.1427, -0.1268, -0.2152, -0.4389, -0.3871, -0.2253, +0.2274, +0.1638, +0.3830, +0.0758, +0.2766, -0.4313, -0.3447, +0.5139, +0.0702, -0.7301, +0.2489, -0.2315, +0.4823, -0.1761, +0.1126, -0.2033, +0.6136, +0.1210, +0.4397, +0.2120, -0.3228, -0.0294, +0.0316, -0.0530, -0.5844, +0.1468, +0.5722, +0.5126, -0.3906, +0.1985, +0.4183, -0.4121, +0.5311, -0.0552, +0.1256, +0.5112, -0.1565, +0.4151, -0.0674, -0.7475, -0.0087, +0.4671, -0.3835, -0.8014, -0.0984, -0.4115, +0.4680, -0.4746, +0.0263, +0.2254, -0.4636, -0.0526, +0.0329, -0.6224, +0.1628, +0.1484, +0.2757, +0.1010, -0.0662, +0.1431, +0.3350, -0.0244, -0.0363, -0.2423, +0.2825, +0.4420, +1.0574, -0.5121, -0.1705, +0.4002, +0.0021, -0.4088, -0.0184, +0.1179, +0.4331, -0.3388, -0.2149, +0.5182, +0.7147, +0.2308, -0.2920, +0.2585, -0.0006, +0.2654, -0.0136, +0.3788, -0.3258, +0.4393, +0.1283, +0.1638],
-[ -0.3958, -0.1723, +0.0041, -0.1713, +0.1163, +0.9317, +0.1024, +0.3821, -0.5272, -0.1965, -1.2950, -0.0896, -0.0509, +0.4697, -0.9789, +0.9504, +0.9781, +0.1087, +0.3547, +0.1490, -0.6933, +0.0642, -0.2842, -0.4972, -0.3845, +0.2326, -0.2337, -0.7827, -0.0600, +0.5650, +0.8874, -0.3840, -0.6595, -0.6787, -0.4388, -0.8687, -0.2893, -1.0843, +0.3562, +0.1733, +0.4882, -0.2395, +0.3340, +0.3259, +0.0118, +0.3943, -0.1122, +0.0261, +0.2895, -0.1793, -0.6270, +1.0038, -0.4197, +0.1312, +0.5332, +0.2492, +0.1200, +0.6193, +0.0708, -0.0898, -0.4113, -0.2571, -0.3703, +1.3534, +0.3064, -0.3420, +0.0751, -0.2390, +0.4730, -0.0710, -0.6082, -0.0621, -0.7128, +0.0342, -0.2973, +1.0688, +0.5756, -0.4482, -0.7317, +0.6677, -0.2893, -1.0595, +0.5063, +0.2384, -0.0241, -0.0483, +0.5890, +0.4075, +0.2774, -0.3506, -0.3246, -0.1290, -0.4692, -0.5019, -0.5848, -0.3720, +0.3620, -0.2611, +0.8221, +0.1117, +0.1067, +0.5905, -0.3737, +0.1316, +0.4962, -0.1595, +0.1623, +1.0253, +0.4063, -0.3844, +0.5407, +0.2100, -0.2984, +0.8594, -0.7372, -0.1105, +0.5597, +0.1740, -0.9340, -0.2020, -0.1063, +0.4312, +0.1656, -0.8614, +0.0234, +0.4053, +0.2024, +0.0626],
-[ +0.3669, +0.3593, -0.0679, +0.3940, -0.9204, +0.1025, -0.1689, +0.6320, +0.3582, -0.2730, -0.3401, +0.5420, +0.1045, -0.1997, -0.4225, +0.5526, +0.3061, -0.3005, +0.1425, +0.2908, +0.0791, +0.3145, -0.3164, -0.2949, -0.2283, -0.5429, +0.1733, +0.1975, +0.1159, +0.3973, -0.5349, +0.1466, -0.2287, -0.4473, -0.4484, -0.1103, +0.4081, -0.2773, +0.3694, -0.6277, -0.0604, -0.2044, +0.2405, -0.8861, -1.1240, +0.0556, +0.0223, +0.0884, -0.6452, +0.0812, +0.2555, -0.5136, -0.2579, -0.0254, +0.4603, -0.3547, +0.2863, +0.0858, -0.2448, -0.1999, -0.3094, -0.7570, -0.1114, -0.0045, +0.6206, -0.2205, -0.0834, -0.5264, +0.5787, +0.2510, +0.3055, +0.6086, +0.1200, +0.0357, -0.1737, -0.1313, +0.4764, -0.3230, -0.3782, +0.3621, -0.2281, -0.4303, +0.5640, +0.5459, -0.0745, -0.2958, +0.1598, -0.2153, +0.2673, +0.4034, +0.0226, +0.1286, -0.3545, -0.4070, -0.2406, -0.1634, -0.0783, +0.6329, +0.3980, -0.2605, +0.2381, -0.2010, -0.1000, +0.3910, +0.0025, -0.2878, +0.0189, +0.2230, +0.4205, +0.1812, +0.0964, -0.6297, +0.2513, -0.2243, +0.0616, +0.2949, -0.8054, -0.0157, -0.1560, -0.4856, +0.1065, -0.3170, -0.3207, -0.4832, -0.1724, -0.1985, +0.1615, -0.5231],
-[ +0.1502, +0.1263, +0.3691, -0.2445, -0.2294, +0.1696, +0.4260, -0.4073, -0.3526, -0.0995, +0.0118, -0.2520, -0.5770, +0.1645, -0.5140, -0.1315, -0.4054, +0.4050, +0.4091, +0.4156, +0.1958, -0.0018, +0.4402, +0.0407, -0.1550, +0.3260, -0.5984, -0.5423, -0.0081, +0.3311, -0.2417, -0.2983, -0.0229, -0.5054, +0.0148, +0.1414, -0.1635, +0.6437, +0.9040, -0.1526, +0.6908, +1.2097, -0.1414, -0.5378, -0.4508, +0.0576, -0.5288, -0.6764, +0.9012, +0.1000, -0.2793, -0.2411, -0.0810, +0.6758, +0.3308, -0.5293, -0.2459, -0.0823, +0.0820, -0.7715, +0.5418, -0.5643, -0.3646, +0.4732, -0.0883, -0.0692, +0.3908, -0.3652, -0.4002, -0.3069, +0.2307, -0.3974, -0.2452, -0.6176, +0.1380, +0.2980, +0.6655, -0.2056, +0.0333, -0.3240, -1.2843, -0.1259, +1.1622, +0.3627, -0.1679, +0.6800, -0.2267, +0.2362, -0.0507, -0.1413, +0.2503, -0.5978, -0.9194, +0.2369, +0.5321, -0.4427, +0.2876, +0.3368, +0.5545, -0.4450, +0.2571, +0.4898, +0.6034, +0.2236, +0.0011, -0.4392, +0.3809, -0.2146, -0.1374, +0.0637, -0.4852, -0.0325, +0.5547, -0.5392, +0.3382, -0.0263, +0.1119, -0.5638, +0.8715, -0.2044, -0.7598, +0.6241, +0.2881, -0.3804, +0.4588, +0.2541, +0.3476, -0.0141],
-[ +0.2340, -0.3097, +0.1328, +0.1492, +0.2735, -0.7588, -0.2059, +0.2854, -1.0919, +0.3341, -0.1496, -0.0754, -0.6094, +0.2697, -0.2989, -0.3690, +0.1993, +0.2189, +0.1199, +0.0099, -0.1689, +0.2214, -0.1943, +0.1307, -0.3045, +0.3797, +0.0547, +0.6835, -0.9322, -0.0897, -0.3947, +0.2783, -0.2957, -0.8735, -0.0857, -0.5275, +0.5872, +0.1125, +0.3264, +0.1085, -0.2542, -0.1712, -0.1670, -0.0907, -0.4145, -0.1559, -0.1683, +0.1396, -0.0608, -0.4183, +0.1501, -0.0744, +0.6009, -0.3488, +0.0600, -0.1671, -0.9331, -0.2067, +0.2982, -0.4334, -0.9677, +0.1867, -0.0084, -0.4228, -0.2115, +0.3280, +0.2394, +0.0311, -0.0103, +0.2755, +0.4475, -0.1920, +0.1652, +0.1196, -0.1093, -0.4222, +1.0664, +0.1558, +0.3881, -1.4208, -0.6818, -0.0486, -0.0218, +0.2288, -0.5064, +0.1701, +0.3040, -0.0079, -0.0437, -0.1605, -0.6087, -0.2500, +0.0799, +0.5584, +0.6784, +0.2731, -0.2145, +0.2343, +0.2560, +0.1749, -0.3732, +0.0208, -0.7439, -0.0895, +0.2646, -0.2037, -0.6270, -0.9166, +0.4650, +0.0876, +0.4140, -0.5085, +0.6740, -0.9125, +0.2592, +0.8056, +0.2206, -0.2435, +0.0648, +0.0790, +0.0676, +0.6078, +0.1500, +0.2579, +0.6270, -0.4166, +0.2167, +0.2587],
-[ -0.6869, -1.2532, +0.5147, +1.2637, -0.2554, +0.8228, +0.2481, -0.5951, -1.2476, +0.6364, +1.5374, -0.0955, +0.0997, -0.6819, +0.2029, -0.6230, +0.1415, -0.0057, -0.6143, +0.8542, -0.9662, -0.2502, -0.4263, +0.7339, -0.6119, +1.3317, -0.3264, -0.2859, +0.8607, +0.4652, +0.7761, -0.1911, +0.9349, -1.2767, -0.3979, -0.1446, +0.3565, +0.0987, +0.4651, +0.4175, -0.8598, -0.0698, +0.2101, -1.0191, +0.3386, -0.8061, +0.1306, +0.2496, +0.1610, -0.3182, -0.3485, -0.2170, -0.8648, -0.7257, -0.7880, -1.0330, -0.2050, +1.1819, +0.0586, -1.4075, -0.5363, -0.6277, +0.4401, +0.1976, -0.0799, +0.4374, +0.0549, -0.8748, +0.3757, +0.2235, +0.1204, +0.4534, +1.1956, +0.6497, -0.8471, -0.0833, -0.2274, +0.3909, +0.5884, -0.2598, -0.0392, +0.1970, +0.5909, -0.7688, +0.3490, +0.6633, +2.0425, +0.4622, -0.8812, -0.4726, +0.9418, -0.1776, -1.1585, -0.3635, +0.7697, +0.4182, +0.2191, -0.2996, -0.8620, -0.4153, -0.2173, -0.8207, +0.5243, -0.5698, +0.0565, +0.2763, -0.4199, +0.2476, +0.6535, -0.4769, -0.4259, +0.2979, -0.1168, -0.3108, +0.1613, +0.3998, +0.5336, -0.4033, +0.0084, +0.9511, -0.1251, -0.2039, -0.2658, -0.5147, +0.3438, -0.3128, -0.2120, +0.4101],
-[ +0.2121, +0.0458, +0.0966, -0.1909, -0.1630, -0.2852, +0.0075, -0.2155, -0.0629, +0.1217, +0.0489, +0.2674, -0.1357, +0.7580, +0.0394, +0.1849, +0.2186, +0.0919, -0.0582, +0.0811, -0.2470, +0.4404, +0.4534, -0.0258, +0.4894, +0.1105, +0.1572, +0.1051, -0.2135, +0.1338, -0.2483, +0.2294, +0.4080, -0.2635, -0.6115, -0.6237, -0.1793, +0.5117, -0.2792, +0.0733, +0.5426, -0.2688, -0.4095, -0.1793, -0.0157, +0.0190, +0.4212, -0.0357, +0.6304, -0.3873, +0.3924, -0.0861, +0.6672, -0.4723, -0.1297, -0.3288, -0.6972, -0.1781, -0.4545, +0.5582, -0.1303, -0.0516, +0.7788, +0.0142, -0.2343, +0.6808, -0.0081, -0.2134, -0.0809, -0.2294, -0.1111, -0.6365, -0.1107, +0.3189, -0.5341, -0.0996, +0.0316, -0.5004, +0.1849, +0.3280, +0.0008, -0.3973, +0.4816, +0.1103, +0.1240, -0.4628, +0.1310, -0.6613, -0.3732, -0.1561, -0.3627, -0.1388, +0.1114, +0.2950, +0.0092, -0.1535, -0.2932, +0.0699, -0.0546, -0.1053, +0.4289, -0.2362, -0.2584, -0.1726, -0.0949, -0.0362, +0.2322, +0.3950, +0.4641, +0.7640, +0.3092, +0.4914, +0.2736, +0.3157, +0.5094, -0.2677, -0.0304, +0.5290, -0.1541, +0.4361, +0.7528, +0.1171, -0.4145, -0.6882, +0.3426, +0.0556, -0.4773, -0.3244],
-[ +0.1956, +0.1411, -0.1178, -0.4152, -0.4311, +0.8176, +0.0779, -0.3809, -0.4114, +0.4712, -0.4344, -0.2139, -0.1640, -0.2804, -0.1627, +0.4153, +0.1441, -0.0034, +1.2698, +0.6388, +0.6887, +0.3232, +0.6699, -0.4265, -0.2310, -0.4578, -0.1124, -0.0999, +0.6439, +0.2424, -0.8201, -0.9492, +0.3796, +0.0581, -0.4657, -0.2927, +0.2837, +0.1804, -0.1202, +0.3552, +0.3751, +0.1974, +0.2472, +0.4008, +0.0195, +0.3877, -0.0637, +0.2603, -0.3156, -0.2780, -0.4614, -0.3423, +0.5843, -0.4884, -0.2875, +0.1293, -0.0482, +0.3154, -0.1461, -0.2471, +0.6120, +0.0867, +0.4732, -0.1967, -0.2645, +0.9138, -0.5977, -0.2765, -0.4727, -0.5815, +0.0225, -0.0835, -0.2688, +0.4517, -0.5937, +0.0246, +0.6287, -0.0022, -0.3399, -0.3237, -0.2632, -0.5175, +0.3992, +0.0535, +0.0226, +0.2662, +0.1523, -0.6824, -0.3497, -0.1999, +0.1842, +0.1421, -0.1967, -0.4185, -0.2236, +0.0956, -0.2740, -0.0225, +0.0631, +0.6854, -0.0791, -0.0231, -0.4041, -0.1458, -0.1564, +0.6051, +0.9266, +0.4423, -0.0485, +0.1817, +0.0502, -0.4416, +0.3662, -0.0397, +0.1136, +0.4185, -0.9586, +0.5222, +0.4192, +0.7460, -0.1631, -0.1646, -0.0479, -0.3892, -0.2540, +0.9087, -0.0765, +1.2772],
-[ +0.4488, -0.3346, +0.8797, +0.4681, +0.1887, +0.1747, +0.6390, +0.4812, -0.2087, +0.0780, +0.1529, +0.4104, -0.1816, +0.3295, +0.0669, +0.2162, -0.0938, +0.2174, -0.1737, -0.1142, -0.4596, -0.8221, +0.1460, -0.0529, +0.0091, +0.2910, -0.0069, +0.0269, +0.3302, +0.2057, -0.2453, -0.1601, -0.3126, -0.1870, +0.4375, +0.1843, -0.1943, -0.3884, -0.3279, +0.2304, -0.4774, -0.2126, -0.0953, -0.2638, -0.2560, +0.3985, -0.4843, +0.0108, -0.3235, +0.4747, +0.0984, +0.4887, -0.0731, -0.1361, -0.2360, +0.5858, +0.6585, -0.1947, +0.3593, -0.1992, +0.1642, -0.1906, +0.5165, +0.3017, +0.1850, +0.4195, -0.5015, +0.4992, +0.1888, +0.2433, -0.0199, +0.2201, +0.2489, -0.0059, +0.3244, +0.0615, -0.0830, +0.0901, +0.0987, -0.1308, -0.2390, +0.3367, +0.1630, -0.0879, -0.5759, -0.3706, +0.1402, +0.1441, -0.6210, +0.4549, +0.3207, -0.0909, -0.3474, +0.0062, -0.2868, +0.4860, +0.3282, -0.0616, +0.0435, -0.1916, -0.1337, +0.1767, -0.0441, +0.1377, -0.0714, -0.2422, +0.4145, -0.2775, +0.3438, -0.2590, +0.2416, +0.0796, +0.2678, -0.5077, -0.0722, +0.0602, +0.2200, +0.3370, -0.1364, +0.3795, +0.2717, -0.1259, +0.3194, +0.0890, +0.4020, -0.6233, +0.4707, -0.2599],
-[ +0.4315, -0.5242, +0.2993, +0.2586, -0.4536, +0.7252, +1.0447, +0.6436, +0.6565, -0.0306, -0.3917, +0.0166, -0.8798, -0.1608, -0.4328, +0.0445, +0.3390, +1.2367, +0.9440, +0.9838, -0.4572, -0.4492, +0.4107, -0.0530, -0.4856, +1.1638, -0.2589, +0.6477, -0.5231, -0.0183, -0.4494, -0.6078, +0.3157, +0.0966, +0.4945, +0.7510, +0.4720, -0.5626, -0.6421, +0.6448, -0.5423, +0.1364, -0.0387, -0.2223, -0.0231, -0.6804, +0.2425, -0.1449, -0.0750, +0.4714, -0.4510, +0.8352, +0.1629, +0.0985, -0.1184, +1.0701, +0.6010, -0.6381, -0.3502, -0.5364, -0.7213, +0.3615, +0.7297, -0.7086, +0.6527, +0.3366, -0.2960, -0.8704, +0.0380, -0.8244, -0.6834, -0.2081, -0.4857, -0.8519, -0.2393, -0.3309, -0.3599, +0.1116, -0.4067, +0.5794, -0.5252, +0.2352, +0.2287, -1.0552, -0.2218, -0.3554, -0.1419, -0.6236, -0.2989, -1.2390, -0.2218, +0.4722, -0.1092, +0.3008, -0.0389, -0.3754, +1.4747, -0.2283, +0.4314, -1.1489, -0.7093, +0.6276, +0.1810, +0.5491, -0.5756, +0.3173, +0.6483, +0.8906, -0.4209, -0.5796, +1.0200, -0.6163, -0.1214, -0.1258, +0.5805, +0.2950, +0.2307, +0.4381, +0.4400, -0.1583, +0.5816, -0.2036, -0.5437, -0.4232, +0.0940, -0.2808, +0.3216, -0.2525],
-[ +0.0742, +0.4380, -0.1123, +0.1466, -0.2904, +0.2372, -0.0534, +0.1450, +0.4487, +0.1276, +0.2094, +0.2912, -0.4848, -0.1227, -0.0124, +0.1027, -0.2706, -0.4136, +0.2279, +0.3685, +0.5077, +0.4813, -0.2295, -0.0581, -0.2173, +0.0079, -0.4921, +0.0092, +0.3458, +0.6057, -0.5006, -0.2395, +0.5917, +0.1108, +0.2833, +0.2301, +0.1825, +0.1964, -0.0255, -0.0449, -0.0345, -1.0167, +0.0476, -0.2173, +0.0279, +0.0429, +0.2997, +0.1938, -0.3537, -0.2747, +0.2032, -0.2481, -0.0964, -0.7288, -0.4086, -0.3281, -0.5330, -0.0353, +0.0908, -0.0745, -0.3914, -0.0477, +0.3210, -0.4763, +0.4682, +0.1382, -0.1023, -0.4761, -0.3149, +0.2353, -0.5013, +0.3278, +0.7215, +0.5220, +0.2365, +0.0376, +0.0850, +0.0728, -0.5511, -0.2774, +0.3453, +0.5757, -0.4881, +0.1291, +0.3019, -0.5095, -0.3132, -0.0783, +0.3169, +0.1090, -0.2678, +0.0573, +0.0323, +0.4465, +0.2120, +0.1226, -0.2121, -0.5436, -0.3721, -0.2470, +0.2039, -0.2365, -0.2653, -0.6544, +0.2113, +0.0409, -0.2423, -0.0809, -0.3150, +0.4188, +0.2396, +0.0892, -0.3252, +0.0785, -0.0765, +0.0001, -0.1093, +0.0154, +0.2728, -0.3279, -0.5862, -0.3453, +0.3352, +0.2447, +0.1718, -0.0457, +0.1011, +0.0055],
-[ +0.0624, +0.4458, +0.4019, +0.8994, -0.6486, -0.1769, +0.4868, +0.9355, -0.2429, +0.7262, +0.6965, -0.0365, -0.6536, +0.3626, -0.2547, -0.1860, +0.2543, +0.4959, -0.6441, +0.2759, +0.4728, -0.7154, +0.4143, -0.5522, +0.4175, -0.4754, -0.2388, +0.6940, +0.1767, -0.0695, -0.5299, -0.7597, +0.2607, +0.0011, -0.2511, +0.2057, -0.2618, +0.8556, -0.0538, +0.6507, -0.0294, +0.0506, +0.5690, +0.9084, +0.3703, +0.3960, +0.6274, -0.2553, -0.3905, -0.4587, +0.6875, -0.7533, +0.2636, +0.0411, +0.0147, -0.4051, -0.2924, +0.0527, -0.6806, -0.0558, +0.3568, +0.0074, +0.7132, +0.3295, -0.4066, +0.7340, +0.1515, -0.5188, -0.5649, -0.2111, +0.0307, +0.4785, +0.1403, +0.3972, +0.3874, -0.6252, -0.7443, +0.3098, -0.0559, -0.4157, +0.0956, -0.5464, +0.1054, -0.0222, -0.2876, -0.7069, -0.7060, -0.5730, -0.3187, -0.3308, +1.0375, -0.8244, -0.9502, -0.0767, +0.5329, +0.1996, -0.0616, -0.7486, -0.3553, +0.6040, -0.8704, +0.2485, +0.7603, -0.7057, -0.1106, -0.2849, -0.3432, -0.4080, -0.3912, -0.0188, -0.3057, +0.2499, -0.1263, -0.1666, -0.1307, -0.1352, +0.0337, -0.4882, -0.0702, +0.1477, -0.0856, -0.2110, +0.4851, +0.0950, -0.1593, -0.0592, +0.3819, -0.2539],
-[ -0.3277, +0.1814, -0.3611, -0.3536, +0.9558, -0.1371, -0.9228, +0.7332, -0.1135, -0.3220, +0.4618, +0.0046, -0.1908, -0.1740, -0.2697, +0.1673, -0.0277, +0.2209, -0.2079, +0.5537, +0.3612, +0.2695, +0.3291, -0.8728, +0.4467, -0.2909, -0.1597, -0.6550, -0.0407, -0.5847, +0.3041, +0.4567, -0.0534, -0.3562, -0.6015, +0.5992, +0.5897, +0.2154, -0.2170, +0.1209, +0.2172, -0.0841, +0.0595, -0.2743, +0.2453, -0.0516, +0.6076, -0.1599, -0.1639, +0.6758, -0.6129, -0.4856, -0.1665, +0.2961, +0.1685, -0.2497, +0.7368, -0.1308, -0.0867, +0.2630, -0.8968, -0.5963, -0.3214, +0.1025, +0.1405, +0.1901, +0.5998, -0.3181, -0.4843, +0.5493, -0.0508, +0.0764, -0.4598, +0.1588, +0.5656, -0.4946, +0.2046, -0.3919, +0.0494, -0.1187, -0.3681, +0.2047, +0.0572, -0.0279, +0.3694, -0.2163, +0.1243, -0.1322, +0.1684, -0.2716, -0.2936, -0.1226, +0.3318, +0.5098, +0.5054, +0.6682, -0.1864, -0.6823, -0.1102, -0.2002, -0.3101, -0.4739, +0.7084, +0.2078, -0.0477, +0.5757, +0.2804, -0.0118, -0.1011, -0.4933, +0.1299, +0.0906, +0.1697, +0.1583, +0.2360, -0.0804, +0.8859, -0.2989, +0.0533, +0.2189, -0.4457, +0.3204, -0.3140, +0.0131, -0.1737, +0.2181, -0.4677, -0.1006],
-[ -0.8126, +0.1990, +0.5124, -0.6074, +0.1914, +0.0813, -0.4273, -0.9015, -0.6596, -0.7723, +0.0850, +0.8301, +0.3937, -0.0051, -0.4537, +0.0449, +1.8714, -0.9737, -0.6382, +0.9047, +0.4053, +0.6448, -0.6425, -0.2780, -0.5496, -0.7814, +0.1890, -0.0449, +0.3741, -0.3408, -0.0122, +0.0116, -0.5959, +0.1219, -0.5759, -0.1331, -0.4107, -0.0134, -0.3225, +0.2390, -0.2296, +0.9920, -0.1071, +0.3630, +0.8198, +0.0303, +0.3771, -0.8828, +0.6714, -0.1488, +0.0408, -0.3381, +0.3740, +0.6765, +0.2284, +0.1534, +0.0127, -1.0164, +0.2159, +0.3989, -0.0969, +0.4181, -0.6163, +0.2185, +0.5617, -0.5112, +0.2564, -0.2430, +0.2221, +0.7438, +0.2085, -0.2271, -0.7645, +0.2447, +0.0580, -0.2986, -0.3843, +0.4457, +1.1948, +0.3098, +0.4203, +0.1285, +0.1100, +0.0654, +0.1632, -0.1969, +0.4257, -0.2921, -0.4148, -0.6491, +0.0640, +1.0732, +0.3787, -0.8488, +0.7749, -0.6143, -0.3522, -0.6646, -0.0218, -0.4335, +0.1399, +0.6476, -1.1843, -0.2402, -0.4294, +0.9316, -0.2125, -0.4109, +1.2925, +0.3828, +0.3296, -0.0682, -0.3338, +0.6236, +0.5535, -0.7328, +0.2679, -1.2653, +0.4066, +1.0549, +0.7709, +0.1907, -0.0912, -0.5897, +0.4094, -0.2027, -0.7482, +0.0041],
-[ +0.0151, -0.3742, +0.0016, +0.2834, +0.1383, +0.0585, -0.7797, +0.2568, -0.2497, +0.0606, +0.1941, +0.1929, +0.0807, -0.0506, +0.0821, +0.2228, +0.0671, -0.3058, +0.1571, +0.0677, -0.2029, +0.2194, -0.2530, +0.0500, -0.4600, -0.2309, -0.0687, -0.3576, +0.0130, -0.0976, -0.0143, +0.1618, -0.3840, -0.0062, +0.1015, +0.2622, +0.0436, -0.2084, -0.3667, -0.0176, +0.3798, -0.1638, +0.3623, +0.0450, +0.1132, -0.2585, +0.3003, +0.0910, -0.3317, -0.3344, -0.0952, -0.2291, +0.2999, -0.0652, +0.2557, -0.3650, +0.0745, +0.0989, +0.1088, +0.2606, -0.3433, -0.2269, +0.1071, -0.4127, +0.0438, -0.0027, -0.4558, -0.8596, -0.0528, -0.3395, +0.2788, -0.0144, -0.5132, -0.1118, +0.1520, +0.1987, -0.6925, -0.3463, -0.5606, +0.2373, -0.0452, -0.1289, +0.4662, -0.3166, +0.0866, +0.2533, +0.4591, -0.0308, -0.3316, +0.1370, -0.1116, -0.1013, -0.0797, +0.1959, -0.4299, -0.1954, +0.2309, +0.2581, -0.0489, +0.1615, +0.6893, +0.1740, +0.1636, -0.1154, +0.3753, +0.0447, +0.0770, +0.1540, -0.2353, +0.2607, -0.1375, +0.2752, +0.0977, -0.1261, +0.6568, +0.0207, +0.1612, +0.2390, -0.7583, -0.0295, -0.1044, -0.3573, -0.0536, +0.1232, -0.4262, +0.0862, -0.0726, +0.3601],
-[ -0.5548, -0.1920, -0.1439, -0.2483, -0.2082, +0.2122, +0.2975, -0.0369, +0.1039, +0.1244, -0.2222, -0.4510, -0.0367, -0.3843, +0.0420, -0.0774, -0.4945, -0.1076, +0.0751, -0.3280, +0.1379, -0.3938, -0.3873, +0.3270, +0.0236, +0.0715, +0.0896, +0.1184, -0.2641, +0.0510, -0.3702, +0.0130, +0.3300, +0.0556, +0.2294, +0.1442, -0.1642, +0.2728, -0.2139, +0.0856, +0.2201, -0.1087, +0.3973, -0.1710, -0.3188, -0.2484, -0.2577, +0.4702, -0.4588, -0.1338, -0.0958, -0.1490, -0.0467, +0.2776, -0.1214, +0.0956, -0.2453, -0.1851, -0.6091, -0.2544, -0.0672, +0.0316, -0.2612, -0.1510, +0.0608, -0.4044, -0.5566, -0.3592, -0.5053, -0.2740, -0.5723, -0.2479, -0.3828, -0.0039, +0.2360, -0.3965, +0.2531, -0.2019, -0.5607, +0.1221, -0.0773, -0.0489, -0.4456, -0.0804, +0.0646, +0.2497, -0.4190, +0.0741, -0.6103, -0.4852, +0.0652, +0.1799, +0.2872, -0.4064, +0.1900, +0.0633, +0.0661, +0.0996, -0.2651, -0.0885, -0.2680, -0.5878, -0.1839, +0.2367, +0.3337, +0.1498, -0.3725, +0.3615, -0.5109, -0.1843, -0.1727, -0.1397, +0.1574, +0.0561, +0.3344, +0.0321, +0.0132, +0.0869, -0.2513, +0.2337, -0.2482, -0.0790, +0.1544, -0.3034, -0.1849, +0.0757, -0.2174, -0.5574],
-[ +0.5490, -0.4549, -0.1807, -0.1592, -0.3788, -0.5189, -0.3193, -0.2197, +0.1731, +0.0376, -0.0203, +0.1929, +0.2335, -0.1647, -0.1995, +0.0219, +0.0582, +0.4244, -0.5565, +0.0563, -0.1738, +0.0395, +0.3419, -0.4511, +0.3530, -0.0868, +0.1509, -0.3145, +0.1942, -0.5813, -0.5611, -0.2145, +0.3324, -0.1938, -0.1914, -0.1679, +0.1673, +0.0441, -0.1303, -0.0111, -0.5023, -0.2911, +0.2364, -0.0646, -0.0100, -0.0791, +0.2281, -0.1580, +0.5276, -0.0730, +0.3710, -0.0632, -0.2827, -0.4295, -0.9110, -0.0882, -0.0346, -0.1583, -0.7173, -0.1413, -0.6280, +0.1766, -0.2437, -0.3187, -0.2748, -0.1086, -0.2328, +0.3354, -0.3041, -0.0570, +0.1021, -0.3893, +0.0137, -0.1443, +0.2737, -0.0007, -0.3881, +0.1483, +0.5163, -0.3890, -0.2129, -0.0672, +0.0883, +0.3756, -0.5196, -0.0377, +0.3687, +0.0005, -0.0266, -0.5761, -0.1695, -0.3244, +0.2822, +0.5312, -0.4635, +0.0570, +0.1477, -0.0760, -0.0655, -0.0777, -0.3997, -0.6029, +0.0564, -0.4778, -0.3137, -0.5685, -0.1534, -0.1205, -0.1739, +0.3745, +0.1266, -0.1687, -0.7521, +0.1720, -0.6872, +0.2064, -0.1344, +0.1887, -0.1305, +0.2296, -0.2478, +0.1684, -0.0571, -0.0419, -0.3555, +0.0154, -0.3511, -0.0239],
-[ -0.3780, -0.0914, -0.1854, -0.0867, +0.0707, -0.0432, +0.1008, -1.0046, +0.1248, +0.0778, -0.0427, +0.2416, +0.0008, -0.0101, -0.4476, -0.5558, +0.0581, -0.6113, -0.2540, -0.6178, -0.4318, -0.3423, +0.3608, -0.1651, -0.3607, +0.1386, -0.3745, +0.0981, -0.4823, +0.0222, +0.2264, -0.2605, +0.3376, +0.3309, -0.2458, -0.4256, -0.2320, -0.1249, +0.0601, +0.4954, +0.0609, -0.0214, -0.5550, -0.5377, -0.1116, +0.3434, +0.2198, -0.2050, -0.1425, -0.1160, -0.1088, +0.3296, -0.1532, -0.1229, -0.1750, -0.2386, +0.2166, +0.1215, +0.1890, -0.4310, -0.2282, -0.0927, -0.1166, +0.1719, -0.4427, +0.0348, -0.3925, -0.0549, -0.1108, +0.1640, +0.1764, +0.2961, +0.4874, -0.5198, -0.1629, -0.1281, +0.0984, +0.2756, -0.3100, +0.4790, -0.1045, -0.1158, -0.1894, -0.0491, +0.2014, -0.1137, -0.3516, -0.3540, -0.2153, +0.1554, -0.2093, -0.7217, -0.0483, -0.1205, -0.0052, +0.0623, -0.9125, -0.2332, -0.4875, +0.5284, +0.3595, +0.2822, +0.0158, -0.4752, -0.1192, +0.2230, -0.0346, -0.7476, +0.1063, +0.2522, -0.4063, -0.1613, -0.0444, -0.1514, -0.1480, -0.0707, -0.0311, -0.6826, +0.0449, -0.0401, -0.0937, -0.1488, -0.0981, -0.3116, +0.5926, -0.7581, +0.4659, -0.1110]
-])
-weights_dense1_b = np.array([ -0.0148, -0.0390, -0.2168, -0.0866, -0.0677, -0.1575, +0.0077, -0.1385, -0.0953, -0.2318, -0.1402, -0.0267, -0.0565, -0.1655, -0.0944, -0.1856, +0.1183, -0.0606, -0.1517, -0.1972, -0.0256, -0.1761, -0.2543, -0.1125, -0.1902, -0.1462, +0.0160, -0.2130, -0.1644, +0.0530, -0.0384, -0.1030, -0.1822, -0.0219, -0.1597, -0.1946, -0.1177, -0.1970, -0.1569, -0.2162, -0.0256, -0.2618, -0.2127, -0.0910, -0.1862, -0.0517, -0.0811, -0.2137, +0.0810, -0.2098, -0.2763, -0.0980, -0.0986, -0.0983, -0.2186, -0.1723, -0.0822, -0.1072, -0.1466, -0.3015, +0.2120, -0.0178, +0.0700, -0.1122, -0.2641, -0.1767, -0.0722, +0.0859, -0.3453, -0.2988, -0.0838, -0.1928, -0.0916, -0.1749, -0.0969, -0.2420, -0.0859, -0.1487, -0.0692, -0.0028, -0.0989, -0.1322, -0.0582, -0.2906, -0.1255, -0.0026, +0.0352, -0.2485, -0.0592, -0.0695, -0.1047, -0.1616, -0.2268, -0.1474, -0.2683, +0.1161, -0.1794, -0.1011, -0.1924, +0.0348, -0.0169, -0.3281, -0.2085, -0.2750, -0.3329, -0.1793, -0.2296, -0.2289, -0.1589, -0.3225, +0.0159, -0.2951, -0.0156, -0.0544, -0.1193, -0.1563, -0.1691, -0.1292, +0.0228, -0.2741, -0.0235, -0.0564, +0.1007, -0.0648, -0.1383, -0.0235, -0.0557, -0.0005])
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ +0.2856, -0.4091, +0.3380, -0.1083, +0.1049, -0.0806, -0.0827, +0.0402,
+ +0.2415, +0.0927, +0.1812, +0.5455, +0.3157, +0.1043, +0.0527, +0.3768,
+ -0.2083, +0.1218, -0.0633, +0.3236, +0.2198, +0.0513, +0.3505, -0.1165,
+ -0.1732, +0.2760, +0.0006, +0.0249, +0.5887, -0.2324, +0.1503, -0.0108,
+ +0.1220, +0.2527, +0.0984, +0.5360, -0.0579, -0.0847, +0.1649, +0.0589,
+ -0.2046, +0.5981, -0.1063, -0.1088, +0.3424, +0.3479, -0.1751, +0.2924,
+ -0.0610, +0.0807, +0.3291, +0.0059, +0.0339, -0.2823, +0.2533, +0.3156,
+ +0.1679, +0.2417, +0.1265, +0.0024, +0.0802, +0.2531, -0.2576, +0.3894,
+ +0.3206, +0.2015, +0.3482, +0.1042, -0.2418, -0.0002, +0.1277, +0.1811,
+ +0.1551, +0.5460, +0.1714, +0.1021, -0.1252, +0.0609, -0.0372, -0.0351,
+ +0.1216, +0.0023, -0.2448, +0.0077, +0.0584, +0.2389, -0.0848, +0.3542,
+ +0.3065, -0.2268, +0.2387, +0.3303, +0.4184, -0.1619, +0.2230, +0.2829,
+ +0.3884, +0.1262, +0.6383, -0.1629, +0.3087, +0.0554, +0.2294, +0.0280,
+ +0.4139, -0.1484, +0.1358, +0.3153, -0.2652, +0.2637, -0.1563, +0.0706,
+ +0.4192, +0.2381, -0.3540, +0.2789, +0.2647, +0.0931, +0.1439, +0.3415,
+ -0.2445, +0.1039, -0.3692, +0.5095, +0.0010, +0.0777, +0.3382, -0.1100
+ ],
+ [
+ +0.0820, +0.6327, +1.0135, -0.1423, -0.0275, +0.0396, -0.5933,
+ +0.3027, -0.2220, +0.1476, -0.0591, -0.7910, -0.0776, +0.2565,
+ +0.0241, -1.1300, +0.1324, +0.9079, +0.2318, +0.5574, +1.0162,
+ +0.1408, +0.7525, +0.3612, +0.6088, -0.2541, +0.8134, +0.1348,
+ -0.1265, +0.7991, -0.2304, -0.4826, -0.4123, +0.2831, -0.5457,
+ -0.3518, -0.9733, -0.1654, +0.2409, +0.3971, +0.6624, +0.0728,
+ +0.2200, -0.2126, -0.5299, -0.1858, -0.3467, -0.2776, -0.2004,
+ -0.7567, +0.4417, -0.4378, -0.6799, +0.3789, +0.2937, -0.1247,
+ +0.5540, -1.0124, -0.5759, +0.0308, +0.2971, +1.1300, -0.1185,
+ +0.5303, +0.0527, +0.3392, +0.7436, -0.3578, -0.0559, +0.2165,
+ -0.5860, +0.9427, -0.2522, -0.0805, +0.9314, +1.4173, +0.6216,
+ +0.6923, +0.6592, -0.0457, +0.5152, -0.3523, -0.5135, +0.6466,
+ -0.4804, +0.0006, +0.3223, -0.1548, +1.5508, +0.6204, +0.2618,
+ -0.0392, -0.6208, +0.0237, +0.0577, -0.2913, -0.3893, -0.1459,
+ -0.1103, +0.7485, -0.0045, +0.0640, +0.0726, -0.0966, +0.0452,
+ +0.2741, -0.3389, +0.8830, +0.9819, +0.3915, -0.1127, -0.2653,
+ -0.6842, +0.2389, -0.4349, +1.4013, -0.4442, +1.1846, -0.7550,
+ +0.5812, -0.2940, +0.7046, +0.4730, -0.2155, +0.1432, +0.1518,
+ +0.5336, -0.0827
+ ],
+ [
+ -0.2503, +0.2354, -0.0468, +0.1318, -0.0161, +0.1235, -0.1649,
+ -0.1380, -0.1816, -0.0953, -0.0303, -0.4337, +0.0159, -0.2893,
+ -0.1178, -0.1779, +0.0557, -0.0788, -0.1745, -0.1349, +0.1942,
+ +0.1707, -0.3289, +0.1177, -0.3084, +0.0423, +0.0006, -0.1240,
+ -0.2685, -0.0578, +0.3282, -0.3570, +0.0039, +0.3399, -0.3599,
+ -0.3346, -0.2273, -0.0044, -0.0425, -0.2483, -0.2284, -0.5528,
+ -0.2406, -0.0144, -0.0306, +0.1037, +0.0497, -0.3302, +0.0505,
+ +0.0054, -0.2037, -0.0112, +0.1068, -0.1273, +0.1019, -0.0463,
+ -0.0527, -0.0015, -0.1546, -0.2187, +0.0633, -0.1969, -0.0954,
+ -0.0111, -0.5329, +0.1480, -0.1007, +0.1115, -0.0692, -0.3348,
+ +0.1361, -0.1606, -0.1103, -0.3221, -0.2678, -0.1543, -0.4900,
+ -0.2455, -0.0798, -0.0545, +0.0848, +0.0149, -0.1908, +0.1721,
+ +0.0687, -0.2002, -0.1194, +0.1023, -0.3005, -0.2030, -0.0681,
+ -0.2440, -0.2892, -0.4305, -0.2357, +0.0932, -0.4055, -0.0629,
+ -0.1043, -0.5354, -0.1120, -0.1867, -0.1219, -0.2403, -0.5562,
+ -0.1247, -0.5158, -0.0720, -0.2935, -0.2138, +0.1382, +0.3068,
+ -0.1444, +0.0100, -0.3312, -0.6305, +0.0030, -0.2372, -0.0005,
+ -0.3775, +0.1123, +0.0166, -0.0000, -0.0605, -0.5071, +0.0482,
+ -0.1440, -0.0311
+ ],
+ [
+ -0.2697, +0.0706, +0.3032, -0.1729, +0.3361, -0.0424, -0.1621,
+ -0.1890, +0.0724, -0.4940, +0.0174, +0.2439, -0.4449, +0.2452,
+ -0.2110, +0.2058, -0.3416, -0.0957, +0.0431, +0.2706, +0.0075,
+ -0.2335, -0.4697, -0.4996, -0.0722, -0.2389, -0.0721, -0.2428,
+ +0.4497, +0.1403, +0.0491, +0.3252, -0.3800, -0.2324, +0.2014,
+ +0.4212, +0.4495, -0.2843, +0.2277, +0.0246, -0.6231, -0.1313,
+ -0.5353, -0.3726, -0.1220, -0.6917, -0.2465, -0.1089, -0.2945,
+ +0.5820, -0.2255, +0.0518, +0.1999, +0.0492, +0.1157, -0.0289,
+ -0.7021, +0.2170, +0.2487, -0.1803, -0.0788, -0.7116, +0.2452,
+ +0.0250, +0.5466, -0.6420, -0.0797, -0.5767, -0.1020, +0.3390,
+ -0.1549, +0.4149, +0.1835, +0.8112, -0.3514, +0.3155, -0.6475,
+ -0.2191, +0.1377, +0.0273, -0.0859, +0.0621, -0.9109, -0.3396,
+ +0.3122, -0.2752, -0.3375, -0.2920, +0.1554, -0.6032, -0.3321,
+ +0.1136, -0.0712, -0.3951, +0.2268, -0.2402, +0.4850, +0.1052,
+ +0.5524, -0.4844, +0.5053, +0.0377, -0.1097, +0.2861, -0.1864,
+ -0.3226, -0.0154, -0.2144, -0.6764, -1.0064, -0.2201, -0.3494,
+ -0.1009, -0.0346, +0.0222, -0.4648, -0.6888, +0.0936, -0.7490,
+ +0.2389, -0.0461, -0.0490, -0.4350, -0.5020, -0.6949, +0.3147,
+ +0.3905, -0.4302
+ ],
+ [
+ -0.5894, -0.0462, -0.0671, +0.1779, -0.2985, -0.0093, +0.1025,
+ -0.2851, -0.5022, +0.4617, -0.0050, -0.4186, -0.4120, +0.5342,
+ -0.4466, -0.5710, -0.0778, +0.5455, +0.4230, -0.1727, +0.0248,
+ +0.6199, -0.0249, -0.0536, -0.2538, -0.0548, -0.5637, +0.1861,
+ -0.3756, +0.6562, -0.0309, -0.7059, -0.5196, -0.6593, -0.0786,
+ -0.4255, -0.2951, -0.3396, +0.2999, +0.2590, +0.5004, +0.3659,
+ -0.1944, -0.5518, -0.0093, +0.3915, -0.0654, +0.7140, -0.0118,
+ -0.3306, +0.4059, -0.5650, -0.4346, +0.8268, -0.2418, -0.6769,
+ -0.1529, -0.1019, -0.0935, -0.4321, +0.3257, -0.2702, -0.0989,
+ +0.2711, -0.6210, +0.4389, +0.3887, -0.1652, -0.0982, +0.0433,
+ -0.1120, +0.2608, +0.1155, -0.3326, -0.5094, +0.0474, +0.1239,
+ -0.2204, -0.1056, -0.6978, +0.1862, -0.2300, -0.1165, +0.1509,
+ +0.7566, -0.5543, +0.3839, -0.5120, +0.3099, -0.2034, +0.7276,
+ +0.2385, -0.7288, -0.1266, -0.2343, -0.5672, -0.0057, -0.0186,
+ -0.3665, -1.2855, +0.6746, -0.1203, -0.3309, -0.8603, +0.4811,
+ -0.1538, +0.5446, +0.0038, +0.1556, +0.5776, -0.1994, -0.3110,
+ -0.4141, +0.0772, +0.1195, +0.4368, +0.3796, +0.3990, -0.3452,
+ +0.0268, -0.0037, -0.2803, +0.7420, -0.5205, +0.7103, +0.0814,
+ +0.0917, +0.5727
+ ],
+ [
+ +0.9108, -1.2019, -0.8828, -0.0571, +0.4640, -0.4255, -0.3412,
+ -0.1130, +0.5679, -0.0657, +0.0851, -0.4367, -0.3447, -1.0903,
+ -0.1277, +0.0440, +0.1664, +0.3279, -0.1176, -0.2553, -0.5594,
+ -0.1823, +0.0093, -0.1161, +0.0341, -0.9688, -0.2799, +0.7136,
+ +0.4686, -0.7197, -0.0798, -0.4068, -0.2519, +0.3220, +0.6010,
+ +0.6546, -0.5138, +0.6600, -0.2747, -0.6502, +1.1478, +0.7705,
+ -0.8645, -0.7124, +0.4578, -0.1423, -0.6454, -0.6139, -0.2964,
+ -0.3525, +0.2287, -0.5368, -1.0776, -0.0507, -0.3517, -0.5014,
+ -0.1767, -0.5016, +0.8044, -0.3985, +0.2099, +0.2479, -1.3310,
+ +0.1198, +0.9254, -0.4103, +0.0248, -0.3546, +0.2374, +0.7145,
+ -0.2494, -0.2125, -0.3934, +0.2301, -0.7252, +0.0734, +0.2172,
+ +0.1852, -0.4918, -0.6549, +0.3549, +0.9117, -0.2437, +0.4721,
+ +0.7126, +0.5653, +0.4648, -0.0169, -0.1650, +1.1287, +0.2412,
+ +1.1366, +0.9122, +0.2840, -0.7930, +0.6158, -1.0912, +0.2805,
+ +1.1295, -0.4873, +1.0141, -0.5452, +0.2255, +0.9590, +0.4029,
+ -1.3217, +0.1508, +0.8827, -0.8346, +0.1531, -0.9785, -0.1839,
+ +1.2149, +1.0538, +0.3230, +0.0808, -0.1425, -1.4677, +0.1845,
+ +0.6411, -0.8535, +1.3519, -0.1753, +0.4364, -0.1985, -0.2911,
+ +0.2662, -0.9084
+ ],
+ [
+ +0.0887, -0.7902, -0.1326, +0.2560, +0.5971, +0.1597, +0.6151,
+ -0.2445, -0.1579, +0.3995, +0.6582, +0.6882, +0.6858, -0.0499,
+ +0.7302, -0.0497, -0.6517, +0.3105, -0.5837, +0.0370, -0.2824,
+ +0.2725, +0.0053, -0.0114, +0.4586, +0.0917, -0.0565, -0.1905,
+ +0.8068, -0.0370, +0.1055, -0.5045, +0.0999, +0.4123, +0.0117,
+ -0.2204, -0.2399, -0.4052, -0.1977, -0.2043, -0.3355, -0.0034,
+ +0.5239, -0.0669, -0.4476, +0.5272, +0.1968, -0.0636, -0.0077,
+ +0.0786, +0.4349, +0.8252, -0.1576, -0.3040, +0.4199, +0.6836,
+ +0.0844, -0.2492, +0.2916, -0.5348, +0.6261, -0.2533, +0.4726,
+ +0.3358, -0.4089, +0.3682, -0.2293, +0.3252, +0.1088, -0.0533,
+ +0.3884, -0.1629, +0.2775, -0.3031, -0.0119, +0.5219, -0.3374,
+ -0.1560, +0.0500, +0.3756, +0.5114, -0.2009, +0.1710, -0.4174,
+ +0.2280, -0.2902, +0.4603, +0.2395, -0.0964, +0.2353, -0.0310,
+ -0.4563, -0.4219, -0.1862, -0.6264, -0.6686, +0.2240, +0.1773,
+ +0.2184, -0.3676, +0.7615, +0.0471, +0.3136, -0.1120, -0.1764,
+ -0.5694, +0.7293, -0.0837, +0.0061, -0.3985, -0.5278, -0.2859,
+ +0.0929, -0.1284, -0.0300, -0.0944, -0.0390, +0.2991, -0.1451,
+ +0.1105, -0.4419, -0.7432, -0.2460, -0.5057, +0.6673, +1.0114,
+ +0.1792, +0.3065
+ ],
+ [
+ -0.6564, +0.6125, -0.3640, +0.1619, -0.2321, +0.5720, +0.6131,
+ -0.5911, +0.5526, +0.3226, -0.1944, -0.1839, +0.3572, +0.4781,
+ +0.3407, +0.1641, +0.3172, -0.0047, -0.5162, -0.1206, -0.3861,
+ +0.1791, -0.3154, +0.2562, -0.3293, +0.0456, +0.4672, -0.3446,
+ -0.1234, +0.3884, +0.1968, -0.0986, +1.2169, +0.3088, +0.1092,
+ -0.5128, -0.1868, +0.1527, -1.0628, +0.2786, +0.8325, +0.4390,
+ +0.7205, +1.3926, +0.7260, +0.1448, +1.1186, -0.5237, +0.7353,
+ +0.2267, -0.2913, +0.6712, -0.2731, +0.4048, +0.2022, +0.2905,
+ -0.1395, +0.1775, +0.3433, +1.9090, -0.5115, -0.0573, +0.3704,
+ -0.0411, -0.9364, -0.3512, -0.2041, +0.1542, +0.2627, -0.5482,
+ +0.0865, +0.1783, -0.2311, -1.5702, -0.0176, +0.8767, -0.4654,
+ -0.1130, -0.1795, +0.6021, +0.3102, -0.4057, +0.4632, -0.0942,
+ +0.4566, +0.0989, -0.5076, -0.3882, +0.3039, +0.5014, -0.5293,
+ -0.0868, -0.4451, -0.5433, -0.0461, -0.2973, +0.3207, -0.6808,
+ -1.2056, +0.7728, +0.4685, +0.2351, +0.2659, -0.2359, -0.9062,
+ +0.7528, -0.1476, +0.6847, +0.1755, -0.0489, +0.6044, +0.9700,
+ -0.9183, +0.1199, +0.1771, -0.5627, -0.3509, -0.0693, +0.4640,
+ -0.0557, +1.0644, -0.7226, +0.1818, -1.0610, -0.7919, +1.0787,
+ -0.1449, +0.6288
+ ],
+ [
+ -0.2821, +0.1942, +0.0717, -0.1533, +0.2884, +0.0299, -0.4759,
+ +0.1094, +0.0928, -0.5330, -0.4834, +0.1220, +0.4441, +0.0950,
+ -0.2181, -0.3184, -0.1734, +0.2083, -0.0679, +0.0449, +0.1293,
+ -0.2203, -0.4006, +0.1973, +0.4127, -0.1489, +0.2313, +0.1979,
+ -0.3278, -0.0182, +0.1668, +0.5720, +0.0830, -0.4511, -0.0183,
+ +0.3112, -0.1480, +0.4522, -0.4363, -0.0033, +0.0456, -0.3984,
+ -0.1388, -0.1651, -0.5918, +0.5272, -0.3076, +0.3667, -0.1151,
+ +0.8332, +0.0800, -0.0647, -0.0477, -0.1672, -0.2390, +0.3837,
+ -0.0609, +0.1687, +0.2350, +0.0576, +0.1809, -0.9367, +0.5738,
+ +0.5234, +0.0063, +0.5833, -0.1264, -0.1810, +0.2093, +0.3804,
+ +0.4890, +0.1374, -0.3955, -0.2193, -0.3411, -0.2258, +0.3689,
+ -0.2886, +0.1800, +0.2246, -0.3125, +0.5031, -0.1732, +0.4497,
+ -0.2867, +0.1692, +0.2127, +0.2622, -0.1449, +0.4516, +0.3948,
+ -0.5770, -0.2663, +0.1198, -0.4118, -0.2319, +0.0458, +0.7989,
+ -0.2666, +0.5099, +0.1698, -0.2164, -0.1695, -0.3694, +0.4706,
+ +0.2198, +0.2426, +0.3539, +0.2527, -0.1951, -0.3628, +0.2259,
+ +0.2184, +0.3123, +0.1581, -0.4492, -0.1066, +0.1484, +0.3531,
+ +0.0580, +0.1617, +0.3627, -0.7292, -0.4043, -0.6717, +0.4356,
+ -0.2808, -0.2858
+ ],
+ [
+ -0.3475, -0.0438, +0.3943, -0.9454, -0.0676, +0.5420, +0.0486,
+ -0.3051, -1.0394, -0.5628, +0.1000, +0.4686, +0.1047, +0.6092,
+ -0.0295, -0.0841, -0.6189, -0.2652, +0.6656, +0.4027, -0.3481,
+ +0.0851, +0.0883, +0.2802, -0.2617, -0.4973, +1.1301, -0.8747,
+ -0.0359, +0.0684, -0.3017, -0.3851, +0.0739, +0.0212, -0.1619,
+ -0.4641, -0.3448, -0.2891, -0.1347, -0.4114, +0.0257, -0.1971,
+ -0.7760, -0.0600, -0.7219, -0.2177, -0.7149, -1.4175, +0.4650,
+ +0.2970, +0.2164, +0.1605, +0.2960, -0.0941, -0.6133, -0.3279,
+ +0.2995, -0.7627, -0.4375, -0.2131, +0.5522, -0.1457, +0.3077,
+ +0.3471, +0.2723, -0.3329, +0.6586, -0.2858, -0.9763, -0.1005,
+ +0.4768, -0.2830, +0.3709, +0.2231, -0.2970, -0.0227, +0.4660,
+ +0.0485, -0.1268, +0.2986, -0.1887, -0.2624, +0.6477, -0.3838,
+ +0.2028, +0.1874, -0.1547, -0.7356, -0.2964, -0.5112, +0.5242,
+ -0.2078, -0.3975, -0.0907, +0.5330, +0.1397, -0.5146, +0.2458,
+ +0.5131, +0.2961, -0.1090, -0.0372, +0.2060, -0.2964, +0.8767,
+ +0.3651, +0.5461, +0.7021, -0.7075, -0.3400, -0.9134, -0.0393,
+ +0.3066, +0.0670, -0.2127, -0.0001, -0.0257, +0.0683, +0.1032,
+ -0.4013, +0.4372, +0.7734, -1.0677, -0.5434, +0.0179, +0.1156,
+ +0.5057, -0.7392
+ ],
+ [
+ +0.6845, -0.4383, +0.4872, +0.0337, -0.5214, +0.3372, -0.2544,
+ +0.3252, +0.1244, -0.0537, +0.3436, +0.0441, -0.1664, -0.1286,
+ +0.9051, +0.6243, +0.1279, -0.3978, -0.4463, -0.6320, -0.4879,
+ -0.0646, -0.0833, -0.0981, -0.1637, -0.0102, -0.5135, -0.3484,
+ -0.3294, +0.1523, +0.7086, +0.1241, +0.1427, -0.1268, -0.2152,
+ -0.4389, -0.3871, -0.2253, +0.2274, +0.1638, +0.3830, +0.0758,
+ +0.2766, -0.4313, -0.3447, +0.5139, +0.0702, -0.7301, +0.2489,
+ -0.2315, +0.4823, -0.1761, +0.1126, -0.2033, +0.6136, +0.1210,
+ +0.4397, +0.2120, -0.3228, -0.0294, +0.0316, -0.0530, -0.5844,
+ +0.1468, +0.5722, +0.5126, -0.3906, +0.1985, +0.4183, -0.4121,
+ +0.5311, -0.0552, +0.1256, +0.5112, -0.1565, +0.4151, -0.0674,
+ -0.7475, -0.0087, +0.4671, -0.3835, -0.8014, -0.0984, -0.4115,
+ +0.4680, -0.4746, +0.0263, +0.2254, -0.4636, -0.0526, +0.0329,
+ -0.6224, +0.1628, +0.1484, +0.2757, +0.1010, -0.0662, +0.1431,
+ +0.3350, -0.0244, -0.0363, -0.2423, +0.2825, +0.4420, +1.0574,
+ -0.5121, -0.1705, +0.4002, +0.0021, -0.4088, -0.0184, +0.1179,
+ +0.4331, -0.3388, -0.2149, +0.5182, +0.7147, +0.2308, -0.2920,
+ +0.2585, -0.0006, +0.2654, -0.0136, +0.3788, -0.3258, +0.4393,
+ +0.1283, +0.1638
+ ],
+ [
+ -0.3958, -0.1723, +0.0041, -0.1713, +0.1163, +0.9317, +0.1024,
+ +0.3821, -0.5272, -0.1965, -1.2950, -0.0896, -0.0509, +0.4697,
+ -0.9789, +0.9504, +0.9781, +0.1087, +0.3547, +0.1490, -0.6933,
+ +0.0642, -0.2842, -0.4972, -0.3845, +0.2326, -0.2337, -0.7827,
+ -0.0600, +0.5650, +0.8874, -0.3840, -0.6595, -0.6787, -0.4388,
+ -0.8687, -0.2893, -1.0843, +0.3562, +0.1733, +0.4882, -0.2395,
+ +0.3340, +0.3259, +0.0118, +0.3943, -0.1122, +0.0261, +0.2895,
+ -0.1793, -0.6270, +1.0038, -0.4197, +0.1312, +0.5332, +0.2492,
+ +0.1200, +0.6193, +0.0708, -0.0898, -0.4113, -0.2571, -0.3703,
+ +1.3534, +0.3064, -0.3420, +0.0751, -0.2390, +0.4730, -0.0710,
+ -0.6082, -0.0621, -0.7128, +0.0342, -0.2973, +1.0688, +0.5756,
+ -0.4482, -0.7317, +0.6677, -0.2893, -1.0595, +0.5063, +0.2384,
+ -0.0241, -0.0483, +0.5890, +0.4075, +0.2774, -0.3506, -0.3246,
+ -0.1290, -0.4692, -0.5019, -0.5848, -0.3720, +0.3620, -0.2611,
+ +0.8221, +0.1117, +0.1067, +0.5905, -0.3737, +0.1316, +0.4962,
+ -0.1595, +0.1623, +1.0253, +0.4063, -0.3844, +0.5407, +0.2100,
+ -0.2984, +0.8594, -0.7372, -0.1105, +0.5597, +0.1740, -0.9340,
+ -0.2020, -0.1063, +0.4312, +0.1656, -0.8614, +0.0234, +0.4053,
+ +0.2024, +0.0626
+ ],
+ [
+ +0.3669, +0.3593, -0.0679, +0.3940, -0.9204, +0.1025, -0.1689,
+ +0.6320, +0.3582, -0.2730, -0.3401, +0.5420, +0.1045, -0.1997,
+ -0.4225, +0.5526, +0.3061, -0.3005, +0.1425, +0.2908, +0.0791,
+ +0.3145, -0.3164, -0.2949, -0.2283, -0.5429, +0.1733, +0.1975,
+ +0.1159, +0.3973, -0.5349, +0.1466, -0.2287, -0.4473, -0.4484,
+ -0.1103, +0.4081, -0.2773, +0.3694, -0.6277, -0.0604, -0.2044,
+ +0.2405, -0.8861, -1.1240, +0.0556, +0.0223, +0.0884, -0.6452,
+ +0.0812, +0.2555, -0.5136, -0.2579, -0.0254, +0.4603, -0.3547,
+ +0.2863, +0.0858, -0.2448, -0.1999, -0.3094, -0.7570, -0.1114,
+ -0.0045, +0.6206, -0.2205, -0.0834, -0.5264, +0.5787, +0.2510,
+ +0.3055, +0.6086, +0.1200, +0.0357, -0.1737, -0.1313, +0.4764,
+ -0.3230, -0.3782, +0.3621, -0.2281, -0.4303, +0.5640, +0.5459,
+ -0.0745, -0.2958, +0.1598, -0.2153, +0.2673, +0.4034, +0.0226,
+ +0.1286, -0.3545, -0.4070, -0.2406, -0.1634, -0.0783, +0.6329,
+ +0.3980, -0.2605, +0.2381, -0.2010, -0.1000, +0.3910, +0.0025,
+ -0.2878, +0.0189, +0.2230, +0.4205, +0.1812, +0.0964, -0.6297,
+ +0.2513, -0.2243, +0.0616, +0.2949, -0.8054, -0.0157, -0.1560,
+ -0.4856, +0.1065, -0.3170, -0.3207, -0.4832, -0.1724, -0.1985,
+ +0.1615, -0.5231
+ ],
+ [
+ +0.1502, +0.1263, +0.3691, -0.2445, -0.2294, +0.1696, +0.4260,
+ -0.4073, -0.3526, -0.0995, +0.0118, -0.2520, -0.5770, +0.1645,
+ -0.5140, -0.1315, -0.4054, +0.4050, +0.4091, +0.4156, +0.1958,
+ -0.0018, +0.4402, +0.0407, -0.1550, +0.3260, -0.5984, -0.5423,
+ -0.0081, +0.3311, -0.2417, -0.2983, -0.0229, -0.5054, +0.0148,
+ +0.1414, -0.1635, +0.6437, +0.9040, -0.1526, +0.6908, +1.2097,
+ -0.1414, -0.5378, -0.4508, +0.0576, -0.5288, -0.6764, +0.9012,
+ +0.1000, -0.2793, -0.2411, -0.0810, +0.6758, +0.3308, -0.5293,
+ -0.2459, -0.0823, +0.0820, -0.7715, +0.5418, -0.5643, -0.3646,
+ +0.4732, -0.0883, -0.0692, +0.3908, -0.3652, -0.4002, -0.3069,
+ +0.2307, -0.3974, -0.2452, -0.6176, +0.1380, +0.2980, +0.6655,
+ -0.2056, +0.0333, -0.3240, -1.2843, -0.1259, +1.1622, +0.3627,
+ -0.1679, +0.6800, -0.2267, +0.2362, -0.0507, -0.1413, +0.2503,
+ -0.5978, -0.9194, +0.2369, +0.5321, -0.4427, +0.2876, +0.3368,
+ +0.5545, -0.4450, +0.2571, +0.4898, +0.6034, +0.2236, +0.0011,
+ -0.4392, +0.3809, -0.2146, -0.1374, +0.0637, -0.4852, -0.0325,
+ +0.5547, -0.5392, +0.3382, -0.0263, +0.1119, -0.5638, +0.8715,
+ -0.2044, -0.7598, +0.6241, +0.2881, -0.3804, +0.4588, +0.2541,
+ +0.3476, -0.0141
+ ],
+ [
+ +0.2340, -0.3097, +0.1328, +0.1492, +0.2735, -0.7588, -0.2059,
+ +0.2854, -1.0919, +0.3341, -0.1496, -0.0754, -0.6094, +0.2697,
+ -0.2989, -0.3690, +0.1993, +0.2189, +0.1199, +0.0099, -0.1689,
+ +0.2214, -0.1943, +0.1307, -0.3045, +0.3797, +0.0547, +0.6835,
+ -0.9322, -0.0897, -0.3947, +0.2783, -0.2957, -0.8735, -0.0857,
+ -0.5275, +0.5872, +0.1125, +0.3264, +0.1085, -0.2542, -0.1712,
+ -0.1670, -0.0907, -0.4145, -0.1559, -0.1683, +0.1396, -0.0608,
+ -0.4183, +0.1501, -0.0744, +0.6009, -0.3488, +0.0600, -0.1671,
+ -0.9331, -0.2067, +0.2982, -0.4334, -0.9677, +0.1867, -0.0084,
+ -0.4228, -0.2115, +0.3280, +0.2394, +0.0311, -0.0103, +0.2755,
+ +0.4475, -0.1920, +0.1652, +0.1196, -0.1093, -0.4222, +1.0664,
+ +0.1558, +0.3881, -1.4208, -0.6818, -0.0486, -0.0218, +0.2288,
+ -0.5064, +0.1701, +0.3040, -0.0079, -0.0437, -0.1605, -0.6087,
+ -0.2500, +0.0799, +0.5584, +0.6784, +0.2731, -0.2145, +0.2343,
+ +0.2560, +0.1749, -0.3732, +0.0208, -0.7439, -0.0895, +0.2646,
+ -0.2037, -0.6270, -0.9166, +0.4650, +0.0876, +0.4140, -0.5085,
+ +0.6740, -0.9125, +0.2592, +0.8056, +0.2206, -0.2435, +0.0648,
+ +0.0790, +0.0676, +0.6078, +0.1500, +0.2579, +0.6270, -0.4166,
+ +0.2167, +0.2587
+ ],
+ [
+ -0.6869, -1.2532, +0.5147, +1.2637, -0.2554, +0.8228, +0.2481,
+ -0.5951, -1.2476, +0.6364, +1.5374, -0.0955, +0.0997, -0.6819,
+ +0.2029, -0.6230, +0.1415, -0.0057, -0.6143, +0.8542, -0.9662,
+ -0.2502, -0.4263, +0.7339, -0.6119, +1.3317, -0.3264, -0.2859,
+ +0.8607, +0.4652, +0.7761, -0.1911, +0.9349, -1.2767, -0.3979,
+ -0.1446, +0.3565, +0.0987, +0.4651, +0.4175, -0.8598, -0.0698,
+ +0.2101, -1.0191, +0.3386, -0.8061, +0.1306, +0.2496, +0.1610,
+ -0.3182, -0.3485, -0.2170, -0.8648, -0.7257, -0.7880, -1.0330,
+ -0.2050, +1.1819, +0.0586, -1.4075, -0.5363, -0.6277, +0.4401,
+ +0.1976, -0.0799, +0.4374, +0.0549, -0.8748, +0.3757, +0.2235,
+ +0.1204, +0.4534, +1.1956, +0.6497, -0.8471, -0.0833, -0.2274,
+ +0.3909, +0.5884, -0.2598, -0.0392, +0.1970, +0.5909, -0.7688,
+ +0.3490, +0.6633, +2.0425, +0.4622, -0.8812, -0.4726, +0.9418,
+ -0.1776, -1.1585, -0.3635, +0.7697, +0.4182, +0.2191, -0.2996,
+ -0.8620, -0.4153, -0.2173, -0.8207, +0.5243, -0.5698, +0.0565,
+ +0.2763, -0.4199, +0.2476, +0.6535, -0.4769, -0.4259, +0.2979,
+ -0.1168, -0.3108, +0.1613, +0.3998, +0.5336, -0.4033, +0.0084,
+ +0.9511, -0.1251, -0.2039, -0.2658, -0.5147, +0.3438, -0.3128,
+ -0.2120, +0.4101
+ ],
+ [
+ +0.2121, +0.0458, +0.0966, -0.1909, -0.1630, -0.2852, +0.0075,
+ -0.2155, -0.0629, +0.1217, +0.0489, +0.2674, -0.1357, +0.7580,
+ +0.0394, +0.1849, +0.2186, +0.0919, -0.0582, +0.0811, -0.2470,
+ +0.4404, +0.4534, -0.0258, +0.4894, +0.1105, +0.1572, +0.1051,
+ -0.2135, +0.1338, -0.2483, +0.2294, +0.4080, -0.2635, -0.6115,
+ -0.6237, -0.1793, +0.5117, -0.2792, +0.0733, +0.5426, -0.2688,
+ -0.4095, -0.1793, -0.0157, +0.0190, +0.4212, -0.0357, +0.6304,
+ -0.3873, +0.3924, -0.0861, +0.6672, -0.4723, -0.1297, -0.3288,
+ -0.6972, -0.1781, -0.4545, +0.5582, -0.1303, -0.0516, +0.7788,
+ +0.0142, -0.2343, +0.6808, -0.0081, -0.2134, -0.0809, -0.2294,
+ -0.1111, -0.6365, -0.1107, +0.3189, -0.5341, -0.0996, +0.0316,
+ -0.5004, +0.1849, +0.3280, +0.0008, -0.3973, +0.4816, +0.1103,
+ +0.1240, -0.4628, +0.1310, -0.6613, -0.3732, -0.1561, -0.3627,
+ -0.1388, +0.1114, +0.2950, +0.0092, -0.1535, -0.2932, +0.0699,
+ -0.0546, -0.1053, +0.4289, -0.2362, -0.2584, -0.1726, -0.0949,
+ -0.0362, +0.2322, +0.3950, +0.4641, +0.7640, +0.3092, +0.4914,
+ +0.2736, +0.3157, +0.5094, -0.2677, -0.0304, +0.5290, -0.1541,
+ +0.4361, +0.7528, +0.1171, -0.4145, -0.6882, +0.3426, +0.0556,
+ -0.4773, -0.3244
+ ],
+ [
+ +0.1956, +0.1411, -0.1178, -0.4152, -0.4311, +0.8176, +0.0779,
+ -0.3809, -0.4114, +0.4712, -0.4344, -0.2139, -0.1640, -0.2804,
+ -0.1627, +0.4153, +0.1441, -0.0034, +1.2698, +0.6388, +0.6887,
+ +0.3232, +0.6699, -0.4265, -0.2310, -0.4578, -0.1124, -0.0999,
+ +0.6439, +0.2424, -0.8201, -0.9492, +0.3796, +0.0581, -0.4657,
+ -0.2927, +0.2837, +0.1804, -0.1202, +0.3552, +0.3751, +0.1974,
+ +0.2472, +0.4008, +0.0195, +0.3877, -0.0637, +0.2603, -0.3156,
+ -0.2780, -0.4614, -0.3423, +0.5843, -0.4884, -0.2875, +0.1293,
+ -0.0482, +0.3154, -0.1461, -0.2471, +0.6120, +0.0867, +0.4732,
+ -0.1967, -0.2645, +0.9138, -0.5977, -0.2765, -0.4727, -0.5815,
+ +0.0225, -0.0835, -0.2688, +0.4517, -0.5937, +0.0246, +0.6287,
+ -0.0022, -0.3399, -0.3237, -0.2632, -0.5175, +0.3992, +0.0535,
+ +0.0226, +0.2662, +0.1523, -0.6824, -0.3497, -0.1999, +0.1842,
+ +0.1421, -0.1967, -0.4185, -0.2236, +0.0956, -0.2740, -0.0225,
+ +0.0631, +0.6854, -0.0791, -0.0231, -0.4041, -0.1458, -0.1564,
+ +0.6051, +0.9266, +0.4423, -0.0485, +0.1817, +0.0502, -0.4416,
+ +0.3662, -0.0397, +0.1136, +0.4185, -0.9586, +0.5222, +0.4192,
+ +0.7460, -0.1631, -0.1646, -0.0479, -0.3892, -0.2540, +0.9087,
+ -0.0765, +1.2772
+ ],
+ [
+ +0.4488, -0.3346, +0.8797, +0.4681, +0.1887, +0.1747, +0.6390,
+ +0.4812, -0.2087, +0.0780, +0.1529, +0.4104, -0.1816, +0.3295,
+ +0.0669, +0.2162, -0.0938, +0.2174, -0.1737, -0.1142, -0.4596,
+ -0.8221, +0.1460, -0.0529, +0.0091, +0.2910, -0.0069, +0.0269,
+ +0.3302, +0.2057, -0.2453, -0.1601, -0.3126, -0.1870, +0.4375,
+ +0.1843, -0.1943, -0.3884, -0.3279, +0.2304, -0.4774, -0.2126,
+ -0.0953, -0.2638, -0.2560, +0.3985, -0.4843, +0.0108, -0.3235,
+ +0.4747, +0.0984, +0.4887, -0.0731, -0.1361, -0.2360, +0.5858,
+ +0.6585, -0.1947, +0.3593, -0.1992, +0.1642, -0.1906, +0.5165,
+ +0.3017, +0.1850, +0.4195, -0.5015, +0.4992, +0.1888, +0.2433,
+ -0.0199, +0.2201, +0.2489, -0.0059, +0.3244, +0.0615, -0.0830,
+ +0.0901, +0.0987, -0.1308, -0.2390, +0.3367, +0.1630, -0.0879,
+ -0.5759, -0.3706, +0.1402, +0.1441, -0.6210, +0.4549, +0.3207,
+ -0.0909, -0.3474, +0.0062, -0.2868, +0.4860, +0.3282, -0.0616,
+ +0.0435, -0.1916, -0.1337, +0.1767, -0.0441, +0.1377, -0.0714,
+ -0.2422, +0.4145, -0.2775, +0.3438, -0.2590, +0.2416, +0.0796,
+ +0.2678, -0.5077, -0.0722, +0.0602, +0.2200, +0.3370, -0.1364,
+ +0.3795, +0.2717, -0.1259, +0.3194, +0.0890, +0.4020, -0.6233,
+ +0.4707, -0.2599
+ ],
+ [
+ +0.4315, -0.5242, +0.2993, +0.2586, -0.4536, +0.7252, +1.0447,
+ +0.6436, +0.6565, -0.0306, -0.3917, +0.0166, -0.8798, -0.1608,
+ -0.4328, +0.0445, +0.3390, +1.2367, +0.9440, +0.9838, -0.4572,
+ -0.4492, +0.4107, -0.0530, -0.4856, +1.1638, -0.2589, +0.6477,
+ -0.5231, -0.0183, -0.4494, -0.6078, +0.3157, +0.0966, +0.4945,
+ +0.7510, +0.4720, -0.5626, -0.6421, +0.6448, -0.5423, +0.1364,
+ -0.0387, -0.2223, -0.0231, -0.6804, +0.2425, -0.1449, -0.0750,
+ +0.4714, -0.4510, +0.8352, +0.1629, +0.0985, -0.1184, +1.0701,
+ +0.6010, -0.6381, -0.3502, -0.5364, -0.7213, +0.3615, +0.7297,
+ -0.7086, +0.6527, +0.3366, -0.2960, -0.8704, +0.0380, -0.8244,
+ -0.6834, -0.2081, -0.4857, -0.8519, -0.2393, -0.3309, -0.3599,
+ +0.1116, -0.4067, +0.5794, -0.5252, +0.2352, +0.2287, -1.0552,
+ -0.2218, -0.3554, -0.1419, -0.6236, -0.2989, -1.2390, -0.2218,
+ +0.4722, -0.1092, +0.3008, -0.0389, -0.3754, +1.4747, -0.2283,
+ +0.4314, -1.1489, -0.7093, +0.6276, +0.1810, +0.5491, -0.5756,
+ +0.3173, +0.6483, +0.8906, -0.4209, -0.5796, +1.0200, -0.6163,
+ -0.1214, -0.1258, +0.5805, +0.2950, +0.2307, +0.4381, +0.4400,
+ -0.1583, +0.5816, -0.2036, -0.5437, -0.4232, +0.0940, -0.2808,
+ +0.3216, -0.2525
+ ],
+ [
+ +0.0742, +0.4380, -0.1123, +0.1466, -0.2904, +0.2372, -0.0534,
+ +0.1450, +0.4487, +0.1276, +0.2094, +0.2912, -0.4848, -0.1227,
+ -0.0124, +0.1027, -0.2706, -0.4136, +0.2279, +0.3685, +0.5077,
+ +0.4813, -0.2295, -0.0581, -0.2173, +0.0079, -0.4921, +0.0092,
+ +0.3458, +0.6057, -0.5006, -0.2395, +0.5917, +0.1108, +0.2833,
+ +0.2301, +0.1825, +0.1964, -0.0255, -0.0449, -0.0345, -1.0167,
+ +0.0476, -0.2173, +0.0279, +0.0429, +0.2997, +0.1938, -0.3537,
+ -0.2747, +0.2032, -0.2481, -0.0964, -0.7288, -0.4086, -0.3281,
+ -0.5330, -0.0353, +0.0908, -0.0745, -0.3914, -0.0477, +0.3210,
+ -0.4763, +0.4682, +0.1382, -0.1023, -0.4761, -0.3149, +0.2353,
+ -0.5013, +0.3278, +0.7215, +0.5220, +0.2365, +0.0376, +0.0850,
+ +0.0728, -0.5511, -0.2774, +0.3453, +0.5757, -0.4881, +0.1291,
+ +0.3019, -0.5095, -0.3132, -0.0783, +0.3169, +0.1090, -0.2678,
+ +0.0573, +0.0323, +0.4465, +0.2120, +0.1226, -0.2121, -0.5436,
+ -0.3721, -0.2470, +0.2039, -0.2365, -0.2653, -0.6544, +0.2113,
+ +0.0409, -0.2423, -0.0809, -0.3150, +0.4188, +0.2396, +0.0892,
+ -0.3252, +0.0785, -0.0765, +0.0001, -0.1093, +0.0154, +0.2728,
+ -0.3279, -0.5862, -0.3453, +0.3352, +0.2447, +0.1718, -0.0457,
+ +0.1011, +0.0055
+ ],
+ [
+ +0.0624, +0.4458, +0.4019, +0.8994, -0.6486, -0.1769, +0.4868,
+ +0.9355, -0.2429, +0.7262, +0.6965, -0.0365, -0.6536, +0.3626,
+ -0.2547, -0.1860, +0.2543, +0.4959, -0.6441, +0.2759, +0.4728,
+ -0.7154, +0.4143, -0.5522, +0.4175, -0.4754, -0.2388, +0.6940,
+ +0.1767, -0.0695, -0.5299, -0.7597, +0.2607, +0.0011, -0.2511,
+ +0.2057, -0.2618, +0.8556, -0.0538, +0.6507, -0.0294, +0.0506,
+ +0.5690, +0.9084, +0.3703, +0.3960, +0.6274, -0.2553, -0.3905,
+ -0.4587, +0.6875, -0.7533, +0.2636, +0.0411, +0.0147, -0.4051,
+ -0.2924, +0.0527, -0.6806, -0.0558, +0.3568, +0.0074, +0.7132,
+ +0.3295, -0.4066, +0.7340, +0.1515, -0.5188, -0.5649, -0.2111,
+ +0.0307, +0.4785, +0.1403, +0.3972, +0.3874, -0.6252, -0.7443,
+ +0.3098, -0.0559, -0.4157, +0.0956, -0.5464, +0.1054, -0.0222,
+ -0.2876, -0.7069, -0.7060, -0.5730, -0.3187, -0.3308, +1.0375,
+ -0.8244, -0.9502, -0.0767, +0.5329, +0.1996, -0.0616, -0.7486,
+ -0.3553, +0.6040, -0.8704, +0.2485, +0.7603, -0.7057, -0.1106,
+ -0.2849, -0.3432, -0.4080, -0.3912, -0.0188, -0.3057, +0.2499,
+ -0.1263, -0.1666, -0.1307, -0.1352, +0.0337, -0.4882, -0.0702,
+ +0.1477, -0.0856, -0.2110, +0.4851, +0.0950, -0.1593, -0.0592,
+ +0.3819, -0.2539
+ ],
+ [
+ -0.3277, +0.1814, -0.3611, -0.3536, +0.9558, -0.1371, -0.9228,
+ +0.7332, -0.1135, -0.3220, +0.4618, +0.0046, -0.1908, -0.1740,
+ -0.2697, +0.1673, -0.0277, +0.2209, -0.2079, +0.5537, +0.3612,
+ +0.2695, +0.3291, -0.8728, +0.4467, -0.2909, -0.1597, -0.6550,
+ -0.0407, -0.5847, +0.3041, +0.4567, -0.0534, -0.3562, -0.6015,
+ +0.5992, +0.5897, +0.2154, -0.2170, +0.1209, +0.2172, -0.0841,
+ +0.0595, -0.2743, +0.2453, -0.0516, +0.6076, -0.1599, -0.1639,
+ +0.6758, -0.6129, -0.4856, -0.1665, +0.2961, +0.1685, -0.2497,
+ +0.7368, -0.1308, -0.0867, +0.2630, -0.8968, -0.5963, -0.3214,
+ +0.1025, +0.1405, +0.1901, +0.5998, -0.3181, -0.4843, +0.5493,
+ -0.0508, +0.0764, -0.4598, +0.1588, +0.5656, -0.4946, +0.2046,
+ -0.3919, +0.0494, -0.1187, -0.3681, +0.2047, +0.0572, -0.0279,
+ +0.3694, -0.2163, +0.1243, -0.1322, +0.1684, -0.2716, -0.2936,
+ -0.1226, +0.3318, +0.5098, +0.5054, +0.6682, -0.1864, -0.6823,
+ -0.1102, -0.2002, -0.3101, -0.4739, +0.7084, +0.2078, -0.0477,
+ +0.5757, +0.2804, -0.0118, -0.1011, -0.4933, +0.1299, +0.0906,
+ +0.1697, +0.1583, +0.2360, -0.0804, +0.8859, -0.2989, +0.0533,
+ +0.2189, -0.4457, +0.3204, -0.3140, +0.0131, -0.1737, +0.2181,
+ -0.4677, -0.1006
+ ],
+ [
+ -0.8126, +0.1990, +0.5124, -0.6074, +0.1914, +0.0813, -0.4273,
+ -0.9015, -0.6596, -0.7723, +0.0850, +0.8301, +0.3937, -0.0051,
+ -0.4537, +0.0449, +1.8714, -0.9737, -0.6382, +0.9047, +0.4053,
+ +0.6448, -0.6425, -0.2780, -0.5496, -0.7814, +0.1890, -0.0449,
+ +0.3741, -0.3408, -0.0122, +0.0116, -0.5959, +0.1219, -0.5759,
+ -0.1331, -0.4107, -0.0134, -0.3225, +0.2390, -0.2296, +0.9920,
+ -0.1071, +0.3630, +0.8198, +0.0303, +0.3771, -0.8828, +0.6714,
+ -0.1488, +0.0408, -0.3381, +0.3740, +0.6765, +0.2284, +0.1534,
+ +0.0127, -1.0164, +0.2159, +0.3989, -0.0969, +0.4181, -0.6163,
+ +0.2185, +0.5617, -0.5112, +0.2564, -0.2430, +0.2221, +0.7438,
+ +0.2085, -0.2271, -0.7645, +0.2447, +0.0580, -0.2986, -0.3843,
+ +0.4457, +1.1948, +0.3098, +0.4203, +0.1285, +0.1100, +0.0654,
+ +0.1632, -0.1969, +0.4257, -0.2921, -0.4148, -0.6491, +0.0640,
+ +1.0732, +0.3787, -0.8488, +0.7749, -0.6143, -0.3522, -0.6646,
+ -0.0218, -0.4335, +0.1399, +0.6476, -1.1843, -0.2402, -0.4294,
+ +0.9316, -0.2125, -0.4109, +1.2925, +0.3828, +0.3296, -0.0682,
+ -0.3338, +0.6236, +0.5535, -0.7328, +0.2679, -1.2653, +0.4066,
+ +1.0549, +0.7709, +0.1907, -0.0912, -0.5897, +0.4094, -0.2027,
+ -0.7482, +0.0041
+ ],
+ [
+ +0.0151, -0.3742, +0.0016, +0.2834, +0.1383, +0.0585, -0.7797,
+ +0.2568, -0.2497, +0.0606, +0.1941, +0.1929, +0.0807, -0.0506,
+ +0.0821, +0.2228, +0.0671, -0.3058, +0.1571, +0.0677, -0.2029,
+ +0.2194, -0.2530, +0.0500, -0.4600, -0.2309, -0.0687, -0.3576,
+ +0.0130, -0.0976, -0.0143, +0.1618, -0.3840, -0.0062, +0.1015,
+ +0.2622, +0.0436, -0.2084, -0.3667, -0.0176, +0.3798, -0.1638,
+ +0.3623, +0.0450, +0.1132, -0.2585, +0.3003, +0.0910, -0.3317,
+ -0.3344, -0.0952, -0.2291, +0.2999, -0.0652, +0.2557, -0.3650,
+ +0.0745, +0.0989, +0.1088, +0.2606, -0.3433, -0.2269, +0.1071,
+ -0.4127, +0.0438, -0.0027, -0.4558, -0.8596, -0.0528, -0.3395,
+ +0.2788, -0.0144, -0.5132, -0.1118, +0.1520, +0.1987, -0.6925,
+ -0.3463, -0.5606, +0.2373, -0.0452, -0.1289, +0.4662, -0.3166,
+ +0.0866, +0.2533, +0.4591, -0.0308, -0.3316, +0.1370, -0.1116,
+ -0.1013, -0.0797, +0.1959, -0.4299, -0.1954, +0.2309, +0.2581,
+ -0.0489, +0.1615, +0.6893, +0.1740, +0.1636, -0.1154, +0.3753,
+ +0.0447, +0.0770, +0.1540, -0.2353, +0.2607, -0.1375, +0.2752,
+ +0.0977, -0.1261, +0.6568, +0.0207, +0.1612, +0.2390, -0.7583,
+ -0.0295, -0.1044, -0.3573, -0.0536, +0.1232, -0.4262, +0.0862,
+ -0.0726, +0.3601
+ ],
+ [
+ -0.5548, -0.1920, -0.1439, -0.2483, -0.2082, +0.2122, +0.2975,
+ -0.0369, +0.1039, +0.1244, -0.2222, -0.4510, -0.0367, -0.3843,
+ +0.0420, -0.0774, -0.4945, -0.1076, +0.0751, -0.3280, +0.1379,
+ -0.3938, -0.3873, +0.3270, +0.0236, +0.0715, +0.0896, +0.1184,
+ -0.2641, +0.0510, -0.3702, +0.0130, +0.3300, +0.0556, +0.2294,
+ +0.1442, -0.1642, +0.2728, -0.2139, +0.0856, +0.2201, -0.1087,
+ +0.3973, -0.1710, -0.3188, -0.2484, -0.2577, +0.4702, -0.4588,
+ -0.1338, -0.0958, -0.1490, -0.0467, +0.2776, -0.1214, +0.0956,
+ -0.2453, -0.1851, -0.6091, -0.2544, -0.0672, +0.0316, -0.2612,
+ -0.1510, +0.0608, -0.4044, -0.5566, -0.3592, -0.5053, -0.2740,
+ -0.5723, -0.2479, -0.3828, -0.0039, +0.2360, -0.3965, +0.2531,
+ -0.2019, -0.5607, +0.1221, -0.0773, -0.0489, -0.4456, -0.0804,
+ +0.0646, +0.2497, -0.4190, +0.0741, -0.6103, -0.4852, +0.0652,
+ +0.1799, +0.2872, -0.4064, +0.1900, +0.0633, +0.0661, +0.0996,
+ -0.2651, -0.0885, -0.2680, -0.5878, -0.1839, +0.2367, +0.3337,
+ +0.1498, -0.3725, +0.3615, -0.5109, -0.1843, -0.1727, -0.1397,
+ +0.1574, +0.0561, +0.3344, +0.0321, +0.0132, +0.0869, -0.2513,
+ +0.2337, -0.2482, -0.0790, +0.1544, -0.3034, -0.1849, +0.0757,
+ -0.2174, -0.5574
+ ],
+ [
+ +0.5490, -0.4549, -0.1807, -0.1592, -0.3788, -0.5189, -0.3193,
+ -0.2197, +0.1731, +0.0376, -0.0203, +0.1929, +0.2335, -0.1647,
+ -0.1995, +0.0219, +0.0582, +0.4244, -0.5565, +0.0563, -0.1738,
+ +0.0395, +0.3419, -0.4511, +0.3530, -0.0868, +0.1509, -0.3145,
+ +0.1942, -0.5813, -0.5611, -0.2145, +0.3324, -0.1938, -0.1914,
+ -0.1679, +0.1673, +0.0441, -0.1303, -0.0111, -0.5023, -0.2911,
+ +0.2364, -0.0646, -0.0100, -0.0791, +0.2281, -0.1580, +0.5276,
+ -0.0730, +0.3710, -0.0632, -0.2827, -0.4295, -0.9110, -0.0882,
+ -0.0346, -0.1583, -0.7173, -0.1413, -0.6280, +0.1766, -0.2437,
+ -0.3187, -0.2748, -0.1086, -0.2328, +0.3354, -0.3041, -0.0570,
+ +0.1021, -0.3893, +0.0137, -0.1443, +0.2737, -0.0007, -0.3881,
+ +0.1483, +0.5163, -0.3890, -0.2129, -0.0672, +0.0883, +0.3756,
+ -0.5196, -0.0377, +0.3687, +0.0005, -0.0266, -0.5761, -0.1695,
+ -0.3244, +0.2822, +0.5312, -0.4635, +0.0570, +0.1477, -0.0760,
+ -0.0655, -0.0777, -0.3997, -0.6029, +0.0564, -0.4778, -0.3137,
+ -0.5685, -0.1534, -0.1205, -0.1739, +0.3745, +0.1266, -0.1687,
+ -0.7521, +0.1720, -0.6872, +0.2064, -0.1344, +0.1887, -0.1305,
+ +0.2296, -0.2478, +0.1684, -0.0571, -0.0419, -0.3555, +0.0154,
+ -0.3511, -0.0239
+ ],
+ [
+ -0.3780, -0.0914, -0.1854, -0.0867, +0.0707, -0.0432, +0.1008,
+ -1.0046, +0.1248, +0.0778, -0.0427, +0.2416, +0.0008, -0.0101,
+ -0.4476, -0.5558, +0.0581, -0.6113, -0.2540, -0.6178, -0.4318,
+ -0.3423, +0.3608, -0.1651, -0.3607, +0.1386, -0.3745, +0.0981,
+ -0.4823, +0.0222, +0.2264, -0.2605, +0.3376, +0.3309, -0.2458,
+ -0.4256, -0.2320, -0.1249, +0.0601, +0.4954, +0.0609, -0.0214,
+ -0.5550, -0.5377, -0.1116, +0.3434, +0.2198, -0.2050, -0.1425,
+ -0.1160, -0.1088, +0.3296, -0.1532, -0.1229, -0.1750, -0.2386,
+ +0.2166, +0.1215, +0.1890, -0.4310, -0.2282, -0.0927, -0.1166,
+ +0.1719, -0.4427, +0.0348, -0.3925, -0.0549, -0.1108, +0.1640,
+ +0.1764, +0.2961, +0.4874, -0.5198, -0.1629, -0.1281, +0.0984,
+ +0.2756, -0.3100, +0.4790, -0.1045, -0.1158, -0.1894, -0.0491,
+ +0.2014, -0.1137, -0.3516, -0.3540, -0.2153, +0.1554, -0.2093,
+ -0.7217, -0.0483, -0.1205, -0.0052, +0.0623, -0.9125, -0.2332,
+ -0.4875, +0.5284, +0.3595, +0.2822, +0.0158, -0.4752, -0.1192,
+ +0.2230, -0.0346, -0.7476, +0.1063, +0.2522, -0.4063, -0.1613,
+ -0.0444, -0.1514, -0.1480, -0.0707, -0.0311, -0.6826, +0.0449,
+ -0.0401, -0.0937, -0.1488, -0.0981, -0.3116, +0.5926, -0.7581,
+ +0.4659, -0.1110
+ ]])
-weights_dense2_w = np.array([
-[ +0.0547, +0.0221, +0.0159, -0.3500, +0.1057, -0.3978, -0.4751, -0.2686, -0.2984, -0.3477, -0.7638, +0.3041, -0.9283, +0.3769, +0.3866, +0.1042, -0.5446, -1.0826, -0.3685, +0.0957, -1.1452, +0.4594, -0.2719, -0.5546, -0.4310, +0.4055, +0.3174, -0.6414, +0.4058, +0.0122, -0.6446, +0.0312, -0.2846, +0.3681, -0.2635, +0.4684, -0.0438, -0.1535, +0.0279, -0.3398, +0.0489, +0.2915, -0.2513, -1.0484, +0.1129, -0.7923, +0.1379, -0.2217, +0.1685, -0.0273, +0.2727, -0.1051, -0.3335, +0.4067, +0.1543, -0.0099, -0.2005, -0.5140, -0.1314, -0.0537, -0.6073, -0.2714, +0.4734, +0.0307],
-[ +0.1983, -0.4372, +0.2649, -0.6106, -0.5667, +0.2295, +0.2821, -0.1570, +0.1007, +0.0072, +0.1053, +0.1223, +0.5393, +0.0445, +0.4042, +0.1218, +0.1946, +0.3514, +0.6725, +0.3489, -0.2839, -0.3705, +0.2665, +0.2710, +0.2836, +0.1292, -0.2779, -0.3549, -0.6220, -0.0934, -0.6794, +0.2522, -0.0012, -0.7044, +0.0819, -0.1884, -0.5545, +0.2331, +0.0573, +0.1692, +0.3610, -0.5304, +0.0751, +0.4747, -0.1379, +0.1396, -0.1418, +0.2756, -0.3771, -0.5534, -0.7892, -0.5082, -0.4949, -0.5125, +0.3863, -0.4106, -0.3488, +0.3701, -0.0261, -0.2519, +0.3600, -0.0131, -0.5443, -0.2148],
-[ -0.4168, +0.0202, -0.3568, +0.3985, +0.0842, -0.1247, -0.1143, +0.3105, +0.0295, +0.1222, -0.9825, +0.2732, +0.1502, -0.1901, +0.2854, -0.0271, +0.2689, +0.2394, -0.0163, +0.3020, +0.1345, +0.2447, -0.1126, -0.5997, -0.1411, +0.3111, +0.1018, -0.1057, -0.2686, -0.0710, -0.2928, -0.0877, -0.5635, -0.0538, +0.0074, +0.0630, -0.9421, -0.1443, -0.7025, -0.5890, -0.2607, -0.3678, -0.9102, -0.0042, -0.0763, -0.2665, +0.2550, -0.1257, -0.0960, -0.4207, -0.3315, +0.3159, -0.1579, +0.6020, +0.1635, -0.1936, +0.1230, -0.0245, -0.1494, -0.1828, -0.1856, -1.0757, -0.9589, -0.2000],
-[ +0.3752, -0.3057, +0.3341, -0.2068, +0.3930, -0.3313, -0.3786, +0.2107, +0.0767, +0.2396, +0.4759, +0.4447, -0.0988, -0.3320, -0.3001, +0.1111, -0.3114, -0.0926, +0.5017, -0.0114, -0.2243, -0.0705, -0.2502, +0.1573, -0.5134, -0.0888, +0.3586, +0.1723, +0.1582, +0.3832, -0.4192, -0.3290, +0.1729, +0.0234, +0.3742, +0.2108, +0.0021, +0.1886, +0.4553, -0.0405, -0.2013, +0.0391, +0.0099, -0.3560, -0.2403, -0.5404, -0.0850, -1.1031, +0.2303, +0.2130, -0.0970, -0.0781, -0.1787, +0.0094, +0.0652, +0.0435, +0.1182, -0.3572, -0.1822, +0.3167, -0.4896, -0.3626, -0.1668, -0.2644],
-[ -0.3002, -0.1710, +0.0482, -0.2977, +0.6775, +0.2932, +0.3891, -0.1426, -0.3008, +0.1301, -0.6758, -0.1576, +0.1714, +0.3555, -0.6530, +0.2284, -0.5148, -0.2974, +0.1985, -0.0305, +0.5279, -0.3357, -0.4142, -0.2472, -0.0224, -0.1873, +0.1376, -0.4045, +0.1122, +0.2617, +0.4392, -0.1154, -0.2372, -0.0144, +0.0885, -0.4898, +0.1629, +0.2722, -0.4575, -0.2204, +0.5557, -0.3414, +0.1573, -0.0259, +0.0639, -0.1291, -0.6438, -0.6169, +0.2151, -0.0527, +0.1338, +0.1200, +0.0151, -0.4535, +0.3047, -0.4136, -0.0690, -0.8133, -0.3369, -0.2327, +0.3387, -0.6738, -0.2590, -0.2750],
-[ -0.5166, -0.2531, -0.5999, -0.0659, -0.0589, -0.1377, -0.0247, -0.3631, -0.1956, +0.2281, +0.0912, +0.2150, -0.0213, -0.2618, -0.3139, -0.6331, +0.2083, +0.0745, -0.0525, +0.4477, +0.2109, -0.1076, +0.3572, +0.4534, -0.2742, -0.0868, -0.4000, +0.3491, +0.0116, +0.1590, -0.0994, +0.0526, -0.3198, -0.2717, -0.1091, +0.2476, -0.6484, -0.0838, +0.1230, -1.4295, -0.4766, -0.0778, -0.5194, -1.0485, -0.4056, +0.5590, +0.1986, +0.0920, -0.2564, -0.0405, +0.1153, +0.0622, +0.1561, +0.6891, -0.2484, +0.3777, +0.4026, +0.4245, +0.5501, -0.2535, +0.1263, -0.5236, -0.3086, -0.4384],
-[ +0.0267, +0.4426, -0.1992, +0.0821, -0.9791, -0.3588, -0.4260, -0.1455, -0.0490, -0.1547, -0.2543, -0.3684, +0.3642, -0.0006, -0.3487, -0.0551, +0.0879, +0.1316, -0.5557, +0.5368, -0.0159, +0.3170, -0.1802, -0.6798, +0.0029, -0.2864, -0.0650, +0.1866, +0.0697, +0.5808, -0.1085, -0.2594, +0.3730, -0.0222, +0.0780, -0.1649, -0.7503, +0.2781, +0.2997, -0.6883, -0.2393, -0.9101, -0.3439, -0.0368, +0.2190, -0.1207, +0.1521, -0.6376, +0.5755, -0.2450, +0.2238, -0.3727, +0.0233, +0.0576, -0.1159, +0.4381, +0.1958, +0.0134, +0.3485, -0.4711, +0.2344, +0.0854, -1.0917, +0.3356],
-[ +0.3785, +0.3636, -0.3251, +0.3122, +0.2442, -0.5955, -0.0093, -0.3778, -0.2082, -0.1958, -0.8252, +0.1736, +0.1166, +0.8199, +0.3367, -0.1289, +0.4549, +0.2460, +0.1128, +0.3572, -0.2274, -0.2742, -0.5444, -0.1523, +0.0356, +0.3113, +0.0246, -0.5069, -0.3344, +0.1946, +0.0670, +0.1407, +0.7479, +0.3682, +0.8027, +0.2609, -0.4183, -0.1806, +0.1140, +0.2086, +0.0652, +0.0760, +0.2543, -0.7174, -0.5935, -0.2738, +0.1096, -0.4978, +0.4936, -0.2776, +0.6209, +0.1223, -0.4159, -0.2111, +0.2914, -0.3457, -0.2449, +0.0895, +0.0807, +0.5205, -0.2385, -0.1925, +0.1622, +0.0880],
-[ -0.2673, -0.3082, +0.5204, +0.3821, +0.2027, -0.0957, +0.3922, -0.0725, +0.0775, -0.1621, +0.1395, -0.0934, -0.5586, +0.4102, +0.4102, -0.0876, -0.8250, -0.3138, +0.0615, +0.0265, -0.8760, +0.3662, +0.3313, -0.0017, +0.2562, +0.0531, +0.0796, +0.0291, +0.1880, -0.2079, -1.4376, +0.0385, -0.4895, +0.4806, -0.4420, -0.4066, +0.1672, +0.0695, -1.0768, +0.0349, -0.5809, +0.0600, +0.0560, -0.1884, +0.1944, -0.4875, -0.2761, -0.1072, -0.5009, +0.2840, +0.0430, -0.4216, -0.5786, +0.0545, +0.1343, +0.3776, +0.3305, +0.4333, +0.0847, +0.4369, -0.0030, +0.0307, +0.3003, +0.2691],
-[ +0.0893, -0.4704, -0.2054, +0.3949, -0.2963, -0.2947, -0.3435, +0.3517, -0.8073, +0.0914, +0.2846, +0.0485, -0.1339, +0.1669, -0.2241, -0.7245, -0.5583, -0.0823, -0.3668, +0.0645, -0.1111, -0.3214, -0.3099, +0.1846, +0.3734, +0.0287, -0.2115, +0.0354, +0.3143, -0.1244, +0.0086, -0.0529, +0.2437, -0.3184, +0.4261, +0.0090, -0.1972, -0.2668, -0.0503, -0.3085, +0.0711, +0.0746, +0.0209, -0.2126, -0.0542, -0.0856, -0.0140, -0.5341, +0.3074, +0.6249, -0.0955, +0.1454, -0.0128, +0.1829, -0.3874, -1.1490, +0.3613, -0.0753, +0.2431, +0.0126, -0.4169, +0.4549, -0.2987, +0.1634],
-[ +0.2796, -0.8066, -0.1895, +0.0652, +0.0235, -0.0806, -0.6463, +0.2801, -0.1388, +0.2654, +0.1312, +0.2453, -0.3954, -0.6161, -0.0602, +0.0419, +0.1494, +0.2994, +0.2134, -0.1138, -0.1966, -0.3912, -0.4885, -0.4361, +0.0082, +0.2686, +0.5057, +0.2438, +0.2241, +0.2533, +0.0221, +0.2056, -0.3449, +0.1963, -0.1053, +0.1093, +0.2248, -0.1142, +0.3292, -0.0353, -0.1378, -0.4590, +0.1552, -0.6599, -0.4846, -0.2242, +0.7134, -1.2819, -0.2578, +0.0916, +0.4744, -0.1979, -0.2302, +0.0517, +0.1801, -0.0128, +0.2979, -0.6418, -0.4409, -0.1068, -0.3446, +0.0824, +0.1677, -0.2113],
-[ +0.0620, +0.0141, +0.8828, +0.1967, -0.2820, -0.3151, -0.4239, -0.0684, +0.2535, -0.1108, -0.4921, +0.1686, -0.1226, +0.0875, -0.4216, +0.2957, +0.2862, +0.0746, -0.1089, +0.0779, +0.0448, -0.1151, +0.2984, -0.2249, -0.1200, -0.1098, +0.4338, -0.3360, +0.0512, -0.1089, -0.1694, -0.0086, +0.2826, -0.0504, +0.0745, +0.1197, -0.1845, -0.0413, +0.0941, +0.1136, -0.7052, -0.9186, -0.2386, -0.1812, -0.0689, -0.7612, -0.4205, +0.2777, +0.5319, -0.3707, -0.2872, +0.0674, +0.1655, +0.3701, -0.4204, -0.0941, +0.0053, +0.1772, -0.8221, +0.3939, +0.0265, -0.0402, -0.4258, -0.4838],
-[ +0.0312, +0.4064, -0.0163, -0.3321, +0.2323, -0.2347, +0.1756, -0.1976, +0.0030, -0.3264, +0.1410, -0.8448, -0.1253, -0.1722, +0.0647, -0.6614, +0.0124, -0.5357, -0.2659, -0.5198, -0.1104, +0.0036, +0.5971, +0.2923, +0.2818, -0.3823, +0.1973, -0.0398, +0.5571, +0.1238, +0.2223, -0.1846, +0.0045, +0.2834, +0.2652, -0.5670, +0.1025, +0.0954, -0.6847, +0.2716, -0.1995, +0.2227, -0.0417, -0.5204, -0.4656, +0.0143, +0.1697, +0.2654, -0.0200, +0.0227, -0.1669, +0.0093, +0.1622, -1.0894, +0.3023, -0.0433, -0.8114, -0.3466, -0.0044, -0.4344, +0.5942, -0.2995, +0.2493, -0.2656],
-[ +0.0884, -0.1168, +0.2659, -0.2658, -0.0894, -0.3646, +0.0123, -0.2345, -0.1249, -0.5543, -0.4367, +0.0704, +0.1846, -0.5260, -0.0185, -0.1435, -0.0243, +0.2774, -0.1795, -0.2214, +0.0297, +0.1819, +0.0135, +0.0257, +0.1465, +0.5108, -0.0764, -0.2536, +0.1924, -0.3582, -0.1813, -0.2825, +0.1625, -0.4450, +0.1806, +0.2287, +0.1214, -0.2687, +0.1684, -0.4179, -0.1748, -1.4161, +0.0182, +0.3509, +0.2804, +0.1512, -0.4392, +0.1313, +0.0852, -0.6827, +0.0465, -0.1457, +0.0937, +0.4504, -0.2384, -0.2387, -0.5351, -0.4227, +0.2521, -0.1205, +0.3281, -0.4157, -0.0388, -0.0779],
-[ -0.4328, +0.1671, -0.2333, +0.3447, +0.2475, -0.0963, -0.0289, -0.1134, -0.6314, -0.0779, -0.0052, -0.5183, +0.1591, -0.1890, -0.1690, -1.2456, +0.1215, -0.7981, -0.7112, -0.1237, -0.4438, +0.2475, +0.2704, -0.3184, +0.0800, -0.3449, +0.1936, -0.2232, +0.0352, -0.0664, -0.0191, +0.1109, -0.1613, +0.1971, -0.2887, -0.6279, +0.4588, +0.2611, +0.0068, -0.1602, +0.1105, +0.1328, +0.2169, +0.0899, -0.4866, -0.2267, +0.0581, -0.2022, -0.7508, +0.0740, -0.6069, +0.5649, +0.0207, +0.1216, -0.1130, -0.8590, +0.0055, -0.0647, +0.3094, -0.3780, -0.2064, +0.4434, -0.4378, +0.2624],
-[ -0.1505, +0.4615, -0.9363, +0.1984, -0.2306, +0.1047, +0.2547, -0.4131, -0.2132, -0.6349, +0.0660, -0.0981, +0.3538, +0.5521, -0.1076, -0.4321, -0.2629, -0.2857, -0.1064, +0.1612, -0.5917, +0.1856, +0.2716, -0.6279, +0.2015, +0.0297, +0.1344, -0.6113, +0.1501, -0.0768, +0.3218, +0.5261, +0.0611, +0.1559, +0.5267, +0.0392, -0.4469, -0.3359, +0.3373, +0.1011, +0.0721, -0.0051, -0.3831, -1.0682, +0.3176, +0.0177, +0.1255, -0.0222, +0.2602, -0.0707, +0.6271, +0.0442, -0.7024, +0.3064, -0.6523, -0.1607, -0.1061, +0.6141, +0.2525, +0.4590, -0.1475, -0.2303, -0.1497, +0.1568],
-[ -0.6547, +0.1965, +0.5732, +0.0585, -0.7985, +0.2784, +0.1409, +0.3753, +0.5077, -0.2973, +0.4522, -0.0481, -0.0250, -0.1732, -0.0189, +0.1741, +0.1811, -0.5026, +0.3383, -0.2984, -0.1815, -0.2687, +0.1435, -0.5299, -0.5446, +0.2488, +0.0848, +0.2456, -0.6651, -0.4723, -0.2933, -0.2168, +0.1354, -0.1201, +0.7322, +0.3879, -0.5529, +0.0442, +0.1429, +0.2459, -0.3643, -1.2003, -0.0014, -0.0881, -0.2888, -0.1497, -0.4499, +0.2563, +0.1399, +0.3984, -0.3034, -0.2152, -0.1062, -0.0971, +0.4006, -0.2250, -0.3419, -0.2266, -0.3736, +0.5701, -0.6925, -0.0455, -0.0159, -0.5060],
-[ +0.2558, +0.0784, +0.5193, +0.1619, +0.2345, -0.3461, +0.1533, +0.0035, -0.6782, -0.8183, -0.9718, +0.4590, +0.1314, +0.2691, +0.0578, +0.3015, +0.1275, -0.2170, -0.1059, -0.3437, +0.2150, -0.0420, -0.1466, -0.3230, -0.2263, -0.2463, +0.3428, -0.2851, -0.1670, +0.8334, -0.3321, -0.5703, +0.4210, -0.3807, +0.5608, +0.1184, +0.0216, +0.3875, -0.0818, -0.3773, +0.2697, +0.0836, -0.5769, +0.1107, +0.2502, +0.1319, +0.1555, -0.5250, -0.0333, -0.2451, -0.0840, -0.2520, -0.5473, +0.5264, -0.2354, -0.4220, -0.0929, -1.0100, -0.2290, +0.3894, +0.1722, +0.2778, +0.2404, +0.5252],
-[ +0.3719, -0.1570, +0.0631, -0.1366, -0.0117, +0.1695, +0.2635, -0.5559, -0.5966, +0.0401, +0.4796, -0.0389, +0.4392, -0.1852, +0.4559, +0.0249, +0.1135, +0.1914, -0.0850, +0.8742, +0.3766, -1.2051, +0.1491, +0.3556, -0.6834, -0.6127, -0.3816, -0.2803, -0.9287, -0.6655, +0.4073, -0.1513, +0.3072, -0.1859, -0.6259, -0.1803, +0.0372, +0.0066, +0.0768, +0.3041, +0.4044, +0.2719, +0.0495, -0.4712, -0.0753, -0.1619, +0.4040, +0.3667, -1.2573, -0.0153, +0.2433, -0.4797, -0.1008, +0.2793, -0.5162, +0.0750, -0.1875, +0.6019, +0.2983, -0.2629, +0.3859, -0.1606, -0.0607, +0.2640],
-[ -0.7689, +0.1244, -0.0722, +0.1658, +0.0536, +0.0774, -0.0666, -0.3190, +0.3863, +0.0221, +0.3311, -0.0757, +0.2848, -0.4570, +0.1558, +0.1559, +0.1904, +0.2411, -0.0255, +0.2793, +0.2985, -0.3438, +0.0476, -0.4403, -0.5639, +0.1262, -0.2366, -0.5360, -0.0511, +0.1175, -0.2260, -0.4008, -0.3002, -0.7550, -0.7351, -0.0725, -0.3370, +0.5923, -0.2017, +0.1863, +0.3965, -0.3253, -0.0685, +0.0485, -0.0183, +0.1959, +0.2554, -0.1661, -0.9667, +0.1877, -0.1062, -0.4295, -0.2307, +0.0769, +0.1511, -0.7353, -0.4450, +0.2015, -0.3559, +0.6302, +0.1058, +0.3851, +0.0694, -0.5665],
-[ +0.2654, -0.7518, +0.1643, -0.0339, -0.0219, -0.0515, +0.4850, +0.1158, -0.3727, +0.1568, -0.2977, +0.3162, +0.0700, -0.4247, +0.2545, +0.2225, -0.0498, +0.4013, -0.1575, -0.3545, -0.2154, -0.9544, -0.0608, +0.2827, +0.2211, +0.1790, -0.0234, -0.1396, -1.2595, -0.1827, +0.2853, +0.0978, +0.1027, -0.2280, -0.5227, -0.5996, +0.2517, +0.3419, +0.4186, +0.4399, +0.4078, -0.3085, +0.1905, +0.3559, -0.1620, +0.3125, -0.0422, +0.1617, -0.0414, +0.4358, -0.4426, -0.4533, -0.7251, -0.4293, +0.0632, +0.0825, +0.1159, +0.6398, +0.2352, +0.3725, +0.3426, +0.1757, -0.2817, -0.5600],
-[ +0.0965, +0.1435, -0.0668, -0.0310, +0.0492, +0.3276, +0.0812, +0.1402, +0.0513, -1.0857, -0.1374, -1.0262, -0.7472, +0.1752, +0.1458, -0.3731, -0.2896, +0.1206, +0.2268, -0.4120, +0.2665, -0.4842, -0.0096, -0.3069, -0.0961, -0.1954, +0.3195, -0.4060, -0.2027, +0.1026, +0.3581, +0.0684, +0.2964, -0.3857, +0.3346, +0.2853, -0.1779, +0.6816, -0.1396, -0.1068, +0.0874, +0.2093, +0.0690, -0.1075, +0.3425, +0.0184, +0.5206, +0.3363, +0.2432, +0.1155, -0.4405, -0.4702, +0.0007, -0.6360, -0.1712, +0.0258, +0.1292, +0.1699, +0.0017, +0.1035, -0.0856, +0.3821, +0.0642, -0.1730],
-[ -0.2957, -1.8336, +0.0635, -0.1502, -0.3054, -0.0347, +0.4553, -1.5017, -0.1386, +0.2204, -1.5949, -0.1060, +0.0207, -0.3453, +0.1805, +0.1862, +0.1077, +0.0503, +0.4847, +0.0824, -0.1334, +0.1013, -0.0132, -0.2091, -0.0147, +0.3173, -0.5393, -0.1905, -0.6108, -0.4315, +0.1379, +0.3715, +0.4988, +0.0204, -1.0445, -0.7534, +0.3054, +0.1166, -0.2072, +0.2696, -0.0510, -0.2593, -0.1224, -0.7100, -0.0739, -0.4827, +0.2711, -0.1706, +0.3453, +0.2951, +0.0905, -0.7676, +0.3072, +0.4110, -0.7400, -0.0282, +0.3160, +0.0045, +0.3315, -0.1876, -0.5153, -0.0300, +0.0528, -0.0902],
-[ -0.0392, -0.2831, -0.8638, +0.0181, -0.1839, +0.1190, +0.1256, +0.0349, +0.0335, +0.3621, +0.0015, -0.0992, -0.2544, -0.6373, -0.5993, +0.3642, +0.0229, -1.3911, +0.0442, +0.3622, -0.0907, +0.0980, -0.1975, +0.2308, -1.1896, -0.4979, +0.1135, -0.0943, +0.0679, -0.0002, -0.0083, -0.8543, +0.2544, -0.0756, -0.9005, -0.0970, -0.0499, +0.2011, -0.0504, -0.4152, -0.1189, +0.0047, +0.1132, +0.1040, -0.0365, -0.1372, +0.0665, -0.3832, -0.3141, +0.0644, -0.0858, -0.2961, +0.2374, +0.3307, +0.2823, -0.0944, -0.1386, -0.1009, +0.1643, -0.8802, -0.2065, +0.2246, +0.1913, -0.0572],
-[ -0.1170, -0.4247, +0.2971, -0.0218, +0.2794, -0.3040, +0.1894, -0.0772, -0.4478, +0.0155, -0.8504, -0.2509, -0.0805, +0.0955, +0.2145, +0.3553, -0.4790, +0.0649, -0.0476, -0.0949, -0.0201, +0.0573, +0.1713, +0.0237, -0.1585, +0.2141, -0.3027, -0.2567, -0.1553, +0.1717, -0.2864, +0.1060, -0.0100, -0.7441, -0.0440, -0.5248, +0.4325, +0.0117, -0.0124, +0.4722, +0.3972, +0.3061, -0.0881, +0.0888, +0.1247, +0.0465, -0.3472, +0.0608, +0.1640, +0.0900, +0.0040, -0.2854, -0.3570, -0.2206, +0.4373, -0.0944, -0.0799, -1.0422, +0.0771, -0.6116, +0.5273, -0.0734, +0.0059, +0.0125],
-[ -0.1478, -0.0775, -0.4148, +0.2235, +0.0244, -0.4050, -0.1933, -0.1451, +0.3546, +0.4780, -0.0377, +0.3747, -0.2634, +0.1820, -0.2871, -0.0375, -0.1472, -1.0087, +0.3116, +0.0882, +0.1714, -0.1267, +0.0243, +0.1244, -0.6763, +0.3206, +0.1243, +0.3372, +0.0311, +0.2017, -0.1272, +0.1254, +0.2171, +0.1646, -0.3122, -0.2863, -0.0401, +0.0408, +0.2649, -0.9490, +0.1101, +0.0612, +0.0200, +0.0067, -0.1735, +0.4192, +0.5672, -0.4306, -0.2337, +0.1219, -0.0581, -0.6563, +0.2676, +0.0907, +0.0774, +0.3393, +0.3514, -0.5195, +0.2571, -1.0322, -0.3714, +0.1705, -0.2050, -0.1214],
-[ +0.2841, +0.2037, +0.0734, -0.3167, -0.2534, +0.3772, +0.3707, -0.0807, +0.2971, +0.1787, +0.0742, -0.7424, +0.0534, -0.6033, -0.2538, -0.1693, -0.0417, +0.1408, -0.0786, +0.0125, -0.2959, +0.3026, +0.1068, +0.3710, -0.0259, -0.2119, +0.2311, +0.1579, +0.4271, -0.1637, -0.1047, -1.4823, +0.1537, -0.6320, +0.0265, -0.3799, +0.2478, -0.5812, -0.1404, -0.0219, -0.1906, -0.0507, +0.1606, +0.3727, +0.2747, +0.0747, -0.1603, +0.3651, +0.0592, -0.2988, +0.1446, -0.4449, +0.0282, +0.1628, +0.1572, -0.9307, -0.5926, +0.0564, +0.4344, -0.2915, -0.0055, -0.0388, -0.2319, +0.0708],
-[ -0.1260, -1.1956, -0.3519, -0.1696, -0.5884, -0.3108, -0.2285, +0.2627, +0.3962, +0.0449, +0.0626, +0.2328, +0.0144, +0.1303, +0.3914, -0.8420, +0.4524, -0.4737, -0.5874, -0.2379, -0.0688, -0.0159, +0.1504, -0.8424, -0.3590, -0.3149, -0.3955, -0.0819, -0.2932, +0.1551, -0.0380, -0.3986, -0.0895, -1.1964, +0.2346, +0.0107, -0.5550, +0.0978, -0.2178, -0.0702, +0.0130, -0.0487, +0.1236, +0.2701, -0.0855, -0.6003, +0.0025, -0.4898, -0.4901, +0.3732, -0.1348, -0.0001, +0.0022, +0.4124, -0.2319, -0.8846, +0.1981, +0.3517, +0.3260, +0.2913, -0.6865, -0.1172, -0.1017, -0.2988],
-[ -0.1994, -0.0318, -0.6611, +0.0667, +0.0348, -0.2005, -0.0708, -0.8554, -0.2964, +0.1114, +0.2106, -0.3456, +0.0631, -0.6458, -0.4482, +0.4112, +0.4312, +0.0396, -0.8510, +0.3383, -0.3657, -0.3998, -0.0279, -0.3247, +0.2809, +0.0671, -0.1980, -0.3156, -0.1614, +0.1241, +0.1267, +0.0882, -0.8523, +0.3680, -0.1008, +0.3258, +0.7330, -0.0226, +0.2324, +0.2983, -0.4784, -0.0821, -0.3784, -0.5416, -0.0020, +0.0128, -0.1557, +0.1735, -0.0400, +0.3065, +0.0703, -0.1273, +0.3064, -0.0101, -0.5155, +0.1910, +0.0411, +0.2573, -0.3383, +0.1305, +0.0244, -0.0700, -0.5478, -0.2243],
-[ +0.6525, -0.1060, +0.0967, -0.2523, -0.0679, -0.2359, -0.1002, -0.1302, -0.2785, -0.0323, -0.2069, -0.4863, +0.4068, -0.2921, +0.0689, +0.0659, +0.3440, +0.0730, -0.2341, +0.1442, +0.0321, -0.4033, +0.3169, +0.2174, -0.3649, -0.3458, -0.0410, +0.1900, -0.3263, +0.0535, +0.2253, -0.0717, +0.2190, -0.3860, +0.4562, -0.0471, -0.6580, +0.1243, +0.0968, -0.0801, +0.2969, -0.1420, +0.0635, +0.3387, -0.0512, +0.0064, +0.3651, -0.0423, +0.0007, -0.5414, -0.1172, -0.1081, -0.1545, -0.0802, -0.9081, +0.1538, -0.0143, +0.0015, -0.2125, -0.1439, +0.3589, -0.6707, -0.6915, +0.2103],
-[ +0.1954, +0.0473, +0.0005, -0.2376, +0.2730, -0.2364, +0.1537, -0.3518, -0.2333, -0.6985, +0.1143, -0.4291, -0.4548, -0.0803, -0.5521, -0.4564, -0.5651, -1.0630, +0.1796, -0.0002, +0.0015, -0.3317, -0.7872, -0.0555, -0.0872, -0.0989, -0.2793, +0.2904, -0.2892, +0.2572, +0.2525, -0.3601, +0.1851, -0.3061, +0.4080, -0.9798, -0.0559, -0.0152, -0.2210, -0.2351, -1.2633, -1.3520, +0.1842, -0.8754, -0.3290, -0.2398, -0.1657, -0.3064, +0.4170, -0.1810, +0.3617, -0.0774, +0.1052, -1.0043, -0.0412, +0.1861, -0.0364, -0.0832, -0.3337, -0.0208, -0.4717, +0.2991, +0.5363, -0.7141],
-[ -0.2813, -0.3716, -0.0886, -0.5633, +0.1087, +0.1772, -0.0322, -0.1692, +0.3300, -1.0514, -0.1952, -0.5817, +0.1098, +0.2299, +0.1408, -0.8174, -1.5817, -0.0897, +0.4067, -0.8538, +0.2466, -0.2321, -0.0760, +0.3167, +0.1953, -0.0280, +0.1107, -0.1015, +0.1602, -0.1283, +0.0893, +0.2528, +0.3058, +0.4486, +0.0661, -0.6155, +0.1135, -0.0380, -0.1616, -0.2837, +0.0692, +0.0797, -0.0934, +0.1645, -0.6896, -0.1260, +0.0314, -0.0450, -0.2893, -0.1417, -0.0603, -0.3250, +0.2633, -0.4442, -0.2169, +0.0100, -1.6046, -0.8446, +0.0547, -0.2022, +0.1854, +0.2163, +0.1098, -0.4998],
-[ -0.2718, +0.0985, +0.1143, +0.5034, +0.1062, -0.2774, +0.0928, +0.4507, -0.2889, +0.1647, +0.1606, -0.5096, +0.0797, +0.2081, +0.1015, -0.0662, -0.5561, +0.0133, -0.1913, +0.4173, -0.2062, -0.0683, -0.0707, -0.3881, -0.1940, -0.1059, +0.1708, -0.0068, +0.4992, +0.1805, -0.0863, -0.1116, +0.2974, +0.6512, +0.2988, -0.7671, -0.3240, -0.2382, -0.3154, -0.4172, -0.0090, +0.3568, +0.0629, -0.4475, +0.0085, +0.3164, +0.8345, -0.9105, +0.4016, +0.0489, +0.1487, -0.1455, -0.0914, +0.3481, -0.0170, -0.2977, +0.0686, -0.3068, +0.4279, +0.1365, +0.0191, +0.3697, +0.2504, -0.2336],
-[ -0.4281, -0.1639, -0.6842, -0.0854, -0.3867, +0.1215, +0.2188, -0.0905, -0.0237, +0.3002, -0.1625, -0.0496, +0.2249, +0.0999, -0.0021, -0.0105, +0.0438, -0.2453, -0.7972, -0.0544, -0.6363, +0.4864, +0.1242, +0.0230, +0.3307, -0.4536, -0.1405, +0.2291, -0.3801, -0.1614, -0.0584, +0.2719, -0.2294, +0.1266, -0.7109, -0.3877, +0.3089, -0.3075, -0.5052, +0.2617, -0.8302, -0.1543, +0.4105, -0.1404, -0.2835, -0.1752, -0.3642, +0.1386, -0.1469, +0.3241, +0.0407, +0.1294, +0.0788, -0.0815, -0.7150, +0.2538, +0.5408, +0.5778, +0.2923, -0.3580, -0.0519, +0.2803, +0.0072, +0.1857],
-[ +0.1413, -0.4943, -0.6837, +0.2482, -0.1298, -0.2851, -0.0800, -0.9522, -0.0827, -0.4602, +0.1367, +0.2338, +0.4496, +0.0029, -0.6388, -0.3566, -0.1129, -0.2587, +0.1929, +0.2315, -0.1974, +0.1578, +0.2540, +0.2304, +0.0193, -0.2805, -0.0064, -0.3831, +0.2310, +0.2366, -0.0409, +0.0743, -0.6095, +0.3397, -0.5128, -0.0056, +0.3138, +0.4122, +0.0952, -0.1192, -0.1181, -0.1224, +0.3857, -0.1165, -0.0761, -0.5138, -0.4998, -0.1310, -1.3272, -0.0823, +0.2054, +0.3836, +0.1094, -0.1651, +0.1319, +0.0349, +0.0455, +0.3051, -0.2890, -0.3378, +0.4504, -0.4409, +0.0342, +0.2857],
-[ -0.6909, -0.2404, -0.5480, +0.1982, +0.7179, -0.1566, +0.5150, -0.3021, -0.1896, +0.3692, -0.2610, +0.1676, +0.2646, -0.0779, -0.6376, -0.4375, +0.0814, -0.0594, +0.1491, +0.6636, -0.0098, -0.4666, -0.5695, -0.4680, +0.3753, -0.2631, -0.3479, -1.0949, -0.1768, -0.0397, -0.2667, +0.2302, -0.3895, +0.2984, -0.1895, -0.1393, -0.1342, +0.5137, +0.0543, -0.1336, -0.0678, -0.9658, -0.4799, +0.4449, -0.0855, -0.0889, +0.0750, -0.0107, -0.8546, -0.1215, -0.0314, +0.0430, +0.4070, -0.4824, +0.0688, +0.3415, +0.0656, +0.0570, +0.0387, +0.4817, +0.1426, +0.0509, +0.0760, -0.4065],
-[ +0.4383, +0.1584, -0.0754, +0.1745, +0.0786, +0.2143, +0.1374, +0.0865, +0.4707, -0.6604, +0.4382, +0.2705, -0.0253, +0.2995, -0.4382, -0.0289, -0.4109, +0.0659, -0.0184, +0.3955, -0.0828, -0.7735, -0.0186, -0.3625, -0.3181, -0.1457, +0.3396, -0.2431, -0.1825, +0.1364, +0.1260, +0.0534, +0.2614, -0.0357, +0.2487, +0.1936, +0.4056, +0.2736, +0.3650, +0.2727, +0.3510, +0.0828, +0.1987, +0.0946, -0.3942, +0.2064, +0.1439, +0.1201, -0.4372, +0.2936, +0.1877, +0.1580, -0.2083, -0.2638, +0.0890, -0.4047, +0.0004, -0.0605, -0.2715, +0.0797, +0.1276, +0.4446, -0.2733, +0.2584],
-[ -0.5070, -0.6084, +0.1098, +0.2952, +0.3233, +0.1273, -0.1590, +0.4029, -0.0075, -0.2986, -0.0453, -0.0251, +0.0636, -0.3285, +0.3005, +0.4278, -1.2692, -0.3260, -0.3904, -0.4674, -0.1919, +0.1708, -0.2957, -0.3654, +0.0608, +0.3880, -0.3380, -0.0002, -0.1227, +0.0483, -0.3408, +0.2696, -0.2904, -0.8352, +0.2176, -0.8516, +0.1110, -0.0138, -0.6308, -0.2065, +0.5916, -0.0596, -0.0420, +0.4001, +0.1048, -0.1863, +0.2619, +0.0696, +0.2273, -0.1749, -0.4023, +0.4499, -1.5990, -0.4454, -0.0222, -0.4018, -0.3324, +0.1569, -0.0777, +0.0774, -0.2870, +0.2780, +0.1298, -0.5494],
-[ +0.4041, +0.2116, +0.1746, +0.3060, +0.3644, +0.2566, -0.2467, +0.0528, -0.1645, -0.2514, +0.3191, -0.0146, -0.2756, -0.1343, -0.1539, -0.4656, -0.0026, -0.0629, -0.3565, -0.7495, -0.6157, -0.2922, +0.0272, +0.3853, -0.3030, +0.1152, +0.6219, +0.0596, +0.2660, +0.3633, +0.3082, +0.4234, +0.1700, -0.7490, +0.6056, +0.0380, -0.1250, +0.1593, -0.0863, -0.3877, -0.0154, -0.6906, -0.1813, -0.1751, -0.0309, +0.0954, -0.0752, +0.1333, -0.3153, +0.0735, +0.2958, -0.0313, -0.0686, -0.0086, -0.3676, +0.4638, -0.0175, +0.0595, +0.4441, +0.0093, +0.2578, +0.1221, +0.0885, +0.2014],
-[ -0.5199, +0.6037, +0.1349, +0.0017, +0.1035, -0.1073, +0.4821, -0.2727, -0.7271, +0.4909, -0.4462, +0.0574, +0.2442, -0.4101, +0.2368, -0.0281, +0.1593, +0.2608, -0.1477, -0.0326, +0.1544, -0.2897, -0.3711, -1.0289, -0.1497, +0.3172, -0.6857, +0.1492, -0.0524, +0.1699, +0.0543, -0.1961, +0.0100, -0.5156, -0.5196, +0.0112, -0.3831, -0.2663, -0.4071, -0.5762, -0.4060, -0.1983, +0.4095, +0.0808, +0.1072, +0.2126, +0.1083, -0.3055, +0.4092, +0.0916, -0.0140, +0.0065, -0.2017, -0.8640, +0.0456, -0.0038, +0.2211, -0.3172, +0.0554, -0.1270, -0.1246, -0.0759, -0.3650, -0.3657],
-[ -0.3915, -0.5535, -0.1423, -0.3716, -0.7515, +0.3826, +0.1549, -0.0311, +0.1627, -0.5930, +0.5855, -0.1633, -0.5803, -0.2441, +0.4444, -0.0405, +0.5196, +0.3439, -0.7971, +0.3043, -0.1354, -0.3644, +0.4925, +0.1056, +0.1867, +0.3991, -0.6626, +0.1049, -0.0140, -0.8950, +0.1062, -0.0186, +0.0854, -0.2033, +0.1403, -0.3018, -0.6041, -0.4544, +0.3293, -1.0832, +0.0505, +0.1097, -0.4619, -0.3131, +0.5037, -1.0137, -0.3421, +0.1212, -1.0994, +0.0358, +0.4906, -0.0352, -0.1116, -0.1726, -1.1999, -0.4828, +0.3461, -0.2870, -0.1895, +0.0537, +0.0167, +0.0602, -0.2372, -0.1231],
-[ -0.2542, +0.8363, -0.2559, +0.0872, -0.1544, +0.1869, +0.4374, -0.4973, +0.3678, -0.8425, -0.9891, +0.1042, +0.1624, -0.0964, -0.1170, +0.2177, +0.1344, -0.3417, +0.5302, -0.3181, -0.8319, -0.0489, -0.3692, +0.3340, -0.1902, -0.0889, -0.0784, -0.2664, -1.1404, +0.2895, +0.0599, +0.0680, +0.4447, -0.1955, -0.2036, +0.1605, -0.4091, +0.3005, +0.4971, +0.0056, -1.0584, -0.9754, +0.4259, -0.4642, +0.3212, -1.0444, -0.4395, +0.1104, -0.2354, -0.2754, -0.1138, -0.1852, +0.5298, -0.1715, -0.6177, -0.5564, -0.5845, -0.9398, -0.5432, -0.4941, -0.5598, -0.2745, -0.7410, +0.0811],
-[ +0.3484, +0.2363, -0.2313, +0.2903, +0.0599, +0.1981, +0.0264, +0.0365, -0.6788, +0.5058, +0.5024, -0.1606, -0.1466, +0.0896, -0.1695, -1.3626, +0.2203, -0.0972, -0.0547, -0.2063, +0.3971, -0.3022, -0.0741, +0.4433, +0.0614, +0.0450, -0.2246, -0.3360, -0.5529, +0.0350, -0.2026, -0.1587, -0.1705, +0.0967, -0.3402, +0.2256, +0.0723, +0.2559, +0.2409, +0.0809, +0.2522, +0.1735, +0.2135, -1.4875, -0.6041, +0.3822, -0.0542, -0.7500, +0.2439, +0.2342, -0.2002, +0.2322, -0.7495, +0.1338, +0.0136, -0.5508, +0.0944, +0.1229, -0.3225, +0.2776, -0.0289, +0.0075, +0.1089, +0.4093],
-[ -0.4983, -0.0860, -0.6441, +0.0981, -0.1997, -0.1528, -0.3994, -0.0600, -0.1746, -0.2651, -0.2522, +0.0370, -0.0651, -0.1543, -0.0061, -0.1030, -0.8072, -0.5816, -0.1532, -0.4045, +0.0006, +0.2646, +0.4261, +0.3321, +0.1915, -0.0374, -0.2416, +0.2430, +0.2274, +0.1678, -0.1648, +0.5931, -0.3600, -0.0454, -0.2038, +0.3763, +0.1858, -0.1298, -0.5252, +0.4314, +0.3626, -0.6726, -0.1011, +0.0262, -0.1636, +0.1911, -0.8712, +0.5409, +0.0053, +0.4764, -0.5827, +0.2690, +0.1905, -0.2930, -0.5309, +0.0933, +0.6593, +0.0569, +0.1535, -0.0866, -0.2559, -0.1172, -0.7115, -0.0318],
-[ -0.3941, +0.2379, -0.7244, -0.5779, -0.1544, +0.0214, +0.1138, -0.0033, +0.2314, -0.5746, +0.1439, -0.2131, -0.3561, -0.9263, -0.4184, -0.0513, +0.5047, -0.0148, +0.2949, -0.4070, +0.2619, +0.0486, -0.9044, -0.0877, +0.1956, -0.2011, -0.4901, +0.6367, -0.1576, -0.2315, +0.0778, -0.3715, +0.2394, -0.0715, -0.0091, +0.3945, +0.1454, +0.2826, +0.2854, +0.0383, -0.7265, -0.4513, -0.0195, +0.1877, +0.1825, -0.1004, +0.0741, -0.5238, -0.7622, +0.4092, +0.4336, +0.1936, +0.3382, +0.3516, +0.2307, -1.4502, +0.5835, -0.5750, -0.7338, +0.2978, -0.5406, +0.0339, -0.3202, +0.2325],
-[ -0.0698, -0.8776, -0.9628, -0.2211, +0.0842, +0.2107, +0.0941, -0.2500, -0.3662, +0.0578, -0.4750, -0.2181, -0.1686, -0.2689, +0.1411, -0.8256, +0.3186, -0.3517, -0.4490, +0.0117, +0.2536, -0.0792, +0.0725, +0.0385, +0.2386, +0.0666, -0.2312, +0.0256, +0.1604, -0.0002, -0.0714, -0.6004, -0.1841, -1.4967, -0.5932, +0.2548, -1.1410, -0.4043, -0.5033, -0.2187, -0.7987, +0.5275, +0.0285, -0.8600, -0.2614, +0.0639, +0.3257, +0.4107, +0.2087, -0.1072, -0.1157, +0.0467, -0.6435, -1.0427, -0.5286, +0.0459, +0.1097, -0.2149, +0.0394, -0.3587, +0.1313, -0.6886, -0.1345, -0.5884],
-[ +0.5300, -0.3907, -0.0105, -0.7121, -0.3486, +0.0401, +0.2562, +0.3037, +0.2092, -0.0210, +0.3676, -0.0227, -0.1761, -0.1304, +0.0840, -0.1310, +0.2111, +0.0926, -0.2739, -0.3635, -0.5617, -0.1553, +0.0314, -0.4018, +0.4185, +0.0401, -0.1099, +0.2949, +0.2019, -0.1762, -0.3477, +0.3448, +0.3568, +0.0361, +0.3788, -0.1996, +0.1723, -0.1428, +0.0066, +0.3473, -0.3308, +0.4851, +0.1993, +0.2379, -0.1148, -0.1366, +0.1673, +0.0433, +0.4188, +0.1589, +0.1478, -0.2602, -0.3324, +0.4604, -0.4275, -0.1584, +0.1039, +0.1074, -0.4238, +0.7423, -0.3097, +0.4578, +0.0754, -0.2779],
-[ +0.1529, -0.1575, +0.0819, +0.0579, +0.4000, -0.2372, +0.2025, +0.3456, +0.4460, +0.6892, -0.3688, +0.0596, +0.7114, +0.0582, +0.2526, +0.0559, -0.3033, -0.2083, -0.2725, +0.2148, +0.6348, -0.0939, -0.3589, +0.3578, -0.0897, -0.4104, -0.2510, -0.1750, -0.0342, +0.2579, -0.2709, +0.1463, -0.2980, +0.6216, -0.3951, +0.2358, +0.5241, -0.1989, +0.0439, +0.2978, +0.2848, +0.4379, -0.1006, +0.4004, -1.3318, +0.0721, -0.7419, -0.4410, +0.1182, -0.1377, -0.3649, +0.3684, -0.1349, -0.3452, +0.1427, -0.3848, -0.1854, -0.2795, -0.0527, -0.1123, -0.0352, -0.5523, -0.0433, +0.5344],
-[ -0.5747, +0.6322, -0.8440, -0.1528, -0.1161, +0.0448, -0.2353, +0.6576, +0.3179, +0.1904, -0.5284, +0.1620, -0.6215, -0.2991, +0.1852, +0.0115, -0.2674, -0.6372, +0.3602, -0.1317, +0.0330, +0.0931, -0.0091, -0.2444, -0.1673, +0.1395, -0.2460, +0.0833, -0.0209, -0.5390, -0.1847, -0.3628, +0.1574, -0.2920, -0.2394, +0.4293, -0.0784, +0.5356, +0.2715, -0.2624, -0.5728, -1.0559, -0.2006, +0.4380, +0.2419, -0.1679, +0.5417, +0.1381, -0.2034, -0.0121, +0.3109, +0.4409, +0.6114, -0.1056, -0.5598, -0.3813, -0.1363, +0.0551, +0.4501, -0.1133, +0.0976, +0.4507, +0.5136, -0.4507],
-[ -0.9244, -0.6286, -0.3487, +0.3031, +0.5490, -0.0417, +0.1368, +0.0454, +0.1623, -0.2627, +0.1115, +0.2481, +0.1029, -0.8995, -0.2601, +0.0153, -0.1716, +0.2178, +0.1816, +0.4099, +0.3247, -0.5553, -0.6924, -0.0171, +0.0062, -0.1994, -0.2239, -0.0970, +0.4365, -0.2650, +0.0827, -0.5745, -0.1020, +0.0077, -0.2992, -0.2860, -0.3540, +0.1319, -0.2205, -0.1654, -0.6664, +0.3699, +0.5765, +0.4030, -0.1225, -0.0918, +0.0005, +0.2558, -0.2505, +0.2503, -0.3338, -0.0020, +0.1167, -0.9499, -0.1115, +0.1646, +0.2288, -0.6132, -0.0171, -0.6352, +0.3016, -0.8156, -0.0234, -0.1960],
-[ -0.1446, -0.0614, -0.5054, +0.0903, -0.6342, -0.3637, -0.4531, +0.3534, -0.3720, +0.1497, -0.0799, -0.4266, -0.4212, -0.0637, +0.2497, -0.2035, +0.0224, -0.2292, -0.4062, -0.1081, -0.8317, +0.3876, -0.1462, +0.3375, -0.2768, +0.2942, -0.0415, -0.0010, +0.1652, +0.3646, -0.4710, -0.3447, -0.3278, +0.2597, -0.1056, -0.2106, +0.0542, -0.0294, +0.2012, +0.2639, -0.1646, -0.0958, +0.7079, +0.1167, +0.3802, -0.3459, -0.1004, +0.3548, +0.3814, +0.1147, -0.0515, +0.0656, +0.0187, +0.4013, -0.4644, +0.3470, +0.0240, +0.0587, +0.3188, +0.3168, +0.0652, -0.1883, -0.1926, -0.2713],
-[ -0.5894, -0.5153, -1.0262, -0.2579, -0.1002, +0.0868, -0.2158, -0.5245, +0.1173, -0.5855, +0.1135, +0.1471, -0.1395, +0.0561, -0.7122, -0.1065, -0.0323, -0.7822, -0.1447, -0.0733, +0.2652, +0.0712, +0.3987, +0.2479, -0.0321, +0.0163, -0.4509, +0.5805, +0.4090, +0.0009, +0.0661, -0.2575, +0.4356, +0.1165, -0.4437, -0.0218, -0.0202, -0.0969, -0.0273, -0.3226, -0.0146, -1.0215, -0.2444, -0.3282, +0.1432, +0.1515, -0.0272, -0.5475, -0.0752, -0.0464, +0.3280, +0.2803, +0.4469, -0.1728, +0.1299, -0.3028, +0.1950, -0.1140, +0.1167, -0.7595, +0.0355, -0.3649, +0.0557, +0.3914],
-[ -0.0846, -0.1685, +0.2284, -0.2308, -0.2823, -0.1744, -0.4141, +0.2608, -0.0387, -0.3320, -0.1776, +0.1127, +0.2196, +0.2047, +0.1583, -0.4179, -1.1789, -0.2604, +0.2216, -0.2943, -0.1386, +0.2381, +0.2102, -0.9876, +0.2734, +0.2302, +0.0747, -0.0731, +0.3148, -0.7059, -0.0752, +0.2228, +0.2243, -0.0902, +0.1300, +0.1532, -0.0828, -0.4113, -0.3630, +0.1029, +0.1319, +0.2420, +0.0834, +0.2050, -0.1922, -0.2458, -0.1244, +0.1475, +0.0999, +0.3175, +0.0888, +0.5254, +0.1428, +0.1467, -0.4229, -0.7336, -0.1727, -0.0493, +0.3679, +0.1458, -0.1008, -0.0171, -0.2563, -0.1038],
-[ +0.1402, -0.1713, +0.0748, -0.1560, -0.2416, +0.4341, +0.6550, -0.3423, +0.0628, +0.1346, +0.4624, +0.2883, -0.0514, -0.4130, -0.5822, +0.5217, -0.1437, +0.3471, +0.2181, -0.2431, -0.5769, -0.0424, +0.2626, +0.4983, +0.2075, -0.1028, +0.0161, +0.1407, -0.0833, +0.2390, +0.0417, +0.2823, +0.5103, -0.6378, -0.0536, -0.0393, -0.0651, +0.2310, +0.1614, +0.3542, -0.9074, -0.6099, -0.6084, -0.2096, +0.3871, -0.4172, -0.3355, -0.0663, +0.0204, -0.2276, +0.0557, -0.4072, -0.0672, -0.5691, -0.0667, +0.1840, +0.0315, -0.5422, +0.2810, -0.6101, +0.0672, +0.2098, +0.2070, -0.0607],
-[ +0.1965, -0.2065, +0.3365, -0.2497, -0.0590, +0.0630, +0.3852, -0.0385, -0.2316, +0.1742, +0.0175, +0.3616, +0.0664, +0.0959, -0.4834, -0.0115, -0.3736, -0.6134, +0.4486, -0.6497, -0.4091, -0.2319, +0.4347, -0.1304, -0.3359, -0.1652, +0.2525, +0.0212, +0.0533, +0.2644, -0.4857, +0.0716, +0.1842, -1.0370, +0.2084, +0.3405, -0.5086, +0.0427, -0.5776, -0.2903, -0.2391, -0.2570, -0.3302, -0.4522, +0.1341, +0.1451, -0.6259, +0.3231, +0.1005, -0.7788, +0.2834, +0.4262, -0.6278, -0.2713, -0.7403, +0.0574, +0.0764, -0.7498, -0.2167, -0.2668, +0.2389, +0.3858, +0.4294, -0.1692],
-[ -0.6005, -0.3342, -0.0341, -0.0976, -0.1294, -0.0055, +0.1565, +0.1378, -0.4799, -0.0769, +0.0385, +0.4254, +0.0979, +0.2879, -0.3212, +0.7339, -0.2134, -0.3846, -0.1997, +0.0673, +0.5370, -0.2301, +0.1499, +0.2798, +0.3384, +0.1293, -0.2867, -0.4863, +0.3093, +0.1156, -0.3691, -0.0511, -0.6717, +0.2799, +0.1184, +0.7869, +0.0988, +0.2327, -0.3219, -0.3663, -0.1863, -0.2751, -0.6367, +0.1387, -1.2061, +0.5445, -0.2497, -0.6187, -0.3262, +0.2336, +0.0923, +0.4471, +0.4191, +0.5987, +0.5211, -0.2479, -0.0383, -0.0975, +0.0296, -0.6031, +0.2865, -0.6888, -0.4697, +0.3444],
-[ -0.8969, -0.3619, -0.2047, -0.1343, -0.3042, -0.1042, -0.0415, -0.1624, -0.2147, -0.1016, -0.7889, +0.3418, +0.0868, -0.4342, -0.2084, +0.3734, +0.4318, -0.1115, +0.2490, +0.4559, -0.2937, -0.5159, -1.1121, -0.0804, +0.1388, -0.4097, +0.1953, -0.0861, +0.0755, +0.0578, -0.0600, -0.0519, +0.2378, -0.7286, -0.8340, -0.9214, -0.1790, -1.2709, -0.5294, +0.0270, -0.4837, +0.1236, +0.3863, -0.3191, +0.1822, -0.1040, -0.3779, +0.1810, -0.0920, -0.1269, +0.5072, -0.3267, +0.3822, -1.1616, +0.2350, +0.4796, +0.1842, -0.1957, +0.0444, -0.6974, -0.4900, -0.4579, -0.1375, -0.5128],
-[ +0.4125, +0.1846, -0.2687, +0.4047, +0.2415, -0.3568, -0.5222, +0.0550, -0.2090, -0.3538, +0.4196, -0.2383, -0.2984, +0.0796, -0.2891, -0.0922, -0.4071, -0.5568, -0.2258, -0.0513, +0.3008, -0.4999, -0.0981, +0.2177, +0.4061, +0.3386, +0.0729, +0.2200, +0.0887, +0.2734, +0.1983, -0.3363, -0.0570, +0.0283, +0.4889, +0.5389, -0.4052, -0.5635, +0.3627, -0.2224, -0.0141, -0.0919, +0.2747, -0.1352, -0.0483, +0.2405, -0.1205, +0.1157, +0.1593, -0.6906, +0.3747, +0.0316, -0.3510, -0.0224, -0.1504, +0.2385, +0.2176, -0.6219, +0.0703, +0.6161, +0.1639, -0.3518, +0.0277, +0.5706],
-[ +0.2870, -0.7338, -0.1045, -0.0942, +0.0845, +0.3805, +0.0079, -0.7205, +0.0955, -0.4537, +0.0731, +0.1386, +0.2017, +0.2059, -0.3269, -0.5290, -0.8150, -0.6405, +0.1613, -0.1068, +0.1682, +0.0145, +0.0655, -0.0025, -0.2245, +0.4070, +0.1686, -0.8228, +0.2429, -0.0431, +0.0035, +0.0513, -0.0154, +0.1894, +0.2753, +0.2020, -0.0720, -0.1562, -0.2747, -0.1583, -0.9408, -0.8700, -0.2165, +0.0506, -1.3863, -0.0658, -0.3209, -0.3702, -0.6101, -0.0353, +0.1048, +0.1970, +0.2671, -0.3384, +0.1256, -0.2245, -0.4526, -0.0493, -0.3827, +0.0560, +0.0338, -0.1525, -0.2141, -0.0425],
-[ -0.1422, +0.1337, -0.9957, -0.5735, -0.2927, -0.4815, +0.4319, +0.0342, +0.0668, +0.3405, -0.0740, -0.1619, +0.5172, -0.4340, +0.1856, +0.2209, -0.4643, +0.6153, +0.4239, -0.9462, +0.2372, +0.1935, +0.0449, +0.0913, +0.5925, +0.0728, -0.3116, +0.3045, -0.1049, -0.3677, -0.2878, -0.2252, +0.1939, -1.5561, +0.0153, -0.1803, -0.6259, -0.3834, -0.6172, -0.0133, -0.2826, -0.2731, +0.3053, +0.0552, -0.0550, -0.5861, -0.2372, +0.1009, +0.2500, -0.4699, +0.0561, -0.2214, +0.3366, +0.1667, -0.0716, -0.0938, +0.0177, -0.9000, +0.1185, -0.3892, +0.1251, -0.1854, +0.1612, -0.2577],
-[ +0.4538, -0.9701, +0.1504, +0.4843, -0.9331, +0.1328, -0.3539, -0.5484, +0.2910, -0.1758, +0.1974, -0.1809, -0.3994, -1.0207, +0.1626, -0.3537, +0.3522, +0.3263, -1.0539, +0.1426, -0.8538, -0.0698, +0.1850, +0.7717, +0.4812, -0.0657, +0.8718, -0.6112, +0.0877, -0.4540, +0.5209, +0.2496, -0.1358, -0.2268, +0.1259, -0.3139, -0.2353, -1.0745, +0.4902, +0.3386, -0.7974, -1.2774, +0.0222, -0.0120, +0.3418, +0.0277, -0.1518, +0.1329, -0.2840, -0.6863, -0.1258, +0.0503, +0.6224, -0.9175, -0.4380, +0.0616, -0.2948, -0.1367, -0.7437, -0.5496, -0.0115, -0.2441, -1.3192, +0.0898],
-[ -0.8492, +0.2324, -1.0937, -0.0072, -0.5556, +0.1550, -0.0198, +0.2518, -0.2527, -0.4283, +0.0591, -0.5192, +0.1214, -0.0950, +0.0202, +0.4282, +0.2584, -0.7877, -0.8089, +0.0275, -0.5099, +0.3571, +0.0930, +0.0660, -0.0577, -0.3545, +0.0622, +0.5885, +0.3251, -0.6699, +0.4005, +0.1462, -0.1288, -0.8976, -0.5042, +0.1200, +0.1997, -0.0740, +0.0969, +0.2668, -0.6573, -0.0003, +0.3727, +0.0478, +0.1457, -0.9810, -0.1764, +0.1550, -0.2832, +0.4197, -0.4164, -0.1324, +0.0982, +0.3429, +0.1463, +0.0178, +0.2783, +0.1799, +0.4229, +0.0707, -1.0676, +0.0656, -0.2406, +0.1123],
-[ -0.2739, +0.4278, +0.5050, +0.4886, +0.0866, -0.6754, -0.2957, -0.7517, -0.1715, -0.0754, -0.0733, +0.0049, +0.4403, -0.5811, +0.1439, -0.1410, -0.4331, +0.0514, -0.1729, +0.4406, +0.0236, +0.1144, +0.3210, -0.0241, -0.1087, -0.7359, +0.4433, -0.1967, +0.4850, -0.3577, -0.2777, -0.1381, +0.0488, +0.4510, +0.0785, -0.1526, -0.0759, +0.3004, -0.0124, -0.3421, -0.3625, -0.2688, -0.6088, +0.1834, -0.1742, -0.3992, -0.0729, -0.0954, +0.1403, +0.2244, -1.0269, +0.0389, +0.0357, +0.2483, -0.0966, -0.1649, +0.0946, +0.0789, -0.8485, +0.8510, -0.2052, +0.0063, +0.3289, -0.2707],
-[ -0.0008, -0.1527, +0.1871, +0.0008, -0.5502, +0.1705, -0.0862, -1.7449, -0.4099, -1.2881, -0.2889, -0.6813, -0.1696, -0.3554, -0.0171, -0.1756, +0.0394, -0.0584, +0.0541, +0.2665, +0.2842, +0.7106, -0.1510, +0.1608, -0.0213, +0.4420, -0.5489, -0.2275, +0.2123, +0.2702, +0.1270, +0.1165, +0.0307, -0.9451, +0.5018, -0.7310, +0.4341, -0.0568, -0.1530, +0.3782, -0.8706, -0.1489, -0.3021, -0.3795, +0.0077, +0.3951, +0.0642, +0.0071, +0.0698, -0.6238, -0.0427, +0.0675, +0.0150, -0.3453, -0.6300, +0.1152, +0.0628, -0.1176, +0.1059, -0.3573, -0.0405, -0.4776, -0.3119, -0.1392],
-[ -0.1531, +0.2170, +0.1452, +0.3291, -0.1676, +0.4282, +0.6817, -1.1171, -0.0246, -0.1068, -0.1326, +0.0996, +0.5856, +0.0621, -0.4004, -1.4584, +0.1328, +0.2980, +0.6669, +0.2422, -0.5000, -0.0695, +0.0159, -0.5761, -0.2003, +0.1373, -0.1083, -0.7715, -0.4855, +0.1736, +0.1171, +0.1248, -0.9882, -0.0027, +0.1430, +0.2150, +0.0139, +0.3390, +0.2071, +0.0626, -0.3002, -0.4146, -0.2301, +0.1151, -0.3078, -0.7258, -0.1942, +0.0928, +0.4019, -0.5398, -0.1712, +0.3604, -0.0307, +0.5086, +0.1574, +0.1295, -0.1964, +0.2544, -0.4195, -0.1106, +0.1878, -0.7051, -0.3494, -0.2784],
-[ -0.1671, +0.2359, -0.3504, -0.0875, -0.0657, -0.0707, -0.2190, +0.3783, +0.0052, +0.3745, -0.5688, +0.2605, -0.3190, +0.5080, +0.4697, -0.0987, +0.2703, +0.1677, -0.6767, -0.3178, +0.4836, +0.5635, -0.7103, -0.0746, +0.1034, +0.2430, -0.4251, -0.1090, -0.5547, +0.2012, -0.3403, -0.3141, +0.1168, -0.2846, -0.3791, -0.6774, -0.1252, -0.2180, -0.0656, +0.0353, -0.7226, +0.2728, -0.1778, -0.3260, +0.3339, +0.0653, +0.3684, -0.1632, +0.2573, -0.2883, +0.0009, +0.1928, -1.0397, -0.7210, -0.8038, -0.2165, +0.1618, -0.0957, +0.2977, +0.2513, +0.0480, -0.4479, -0.0804, -0.1824],
-[ +0.3119, +0.0566, +0.0424, -0.4121, +0.2908, -0.0512, +0.0101, -0.2033, -0.0291, -0.4058, +0.1809, -0.3684, -0.1681, +0.3278, -0.1494, +0.3727, -0.5309, +0.2718, +0.3946, -0.6974, -0.1518, -1.1048, +0.0306, +0.2203, +0.1070, +0.4206, +0.2177, -0.0350, -0.2504, -0.1273, +0.2011, -0.3807, -0.0330, -0.0830, +0.0246, +0.2361, +0.2504, -0.0618, -0.4662, +0.1870, -0.0266, -0.7132, -0.1990, +0.2201, +0.2257, +0.2032, +0.5247, +0.0135, -0.5164, -0.4449, -0.1256, -0.2228, -0.3297, -0.0180, -0.4429, -1.1518, -0.6446, +0.0484, -0.0231, -0.1286, +0.2235, +0.4159, -0.4084, +0.1132],
-[ +0.2173, -0.4447, +0.0845, -0.0702, +0.1410, +0.0165, -0.2067, -0.0764, +0.2809, +0.1371, -0.6168, +0.0406, -0.4437, -0.1373, -0.0030, -0.3000, -0.3696, -0.3191, -0.1415, +0.2761, -0.0324, +0.0190, -0.1383, +0.0778, -0.5184, +0.1510, -0.0283, -0.6965, +0.3637, -0.2210, -0.0611, -0.0446, +0.1991, -0.0131, +0.3577, -0.5313, +0.0258, -0.5449, -0.6727, -0.1732, +0.1289, -0.2922, -0.2036, -0.2062, -0.5262, +0.2311, -0.5273, -0.3758, +0.0734, +0.2520, +0.5800, +0.1337, -0.0203, +0.2392, +0.4818, +0.1183, -0.2960, -1.3139, -0.3598, -0.4217, +0.5906, +0.3120, +0.0842, -0.0189],
-[ -0.2034, -0.2470, +0.0815, +0.3712, -0.2452, -0.2641, -0.4384, -0.0659, -0.1397, -0.0294, +0.5793, +0.4600, -0.6904, +0.1172, -0.3046, +0.3242, +0.0302, -1.3304, +0.3182, -0.1053, +0.3679, -0.3855, -0.2545, -0.2798, -0.2702, +0.0962, -0.3428, +0.1185, +0.0799, -0.1985, -0.7122, -0.1967, -0.1748, +0.0686, +0.5070, +0.2390, -0.3882, -0.1285, +0.1746, +0.0770, -0.7113, -0.3933, +0.0402, -0.5497, +0.1689, -0.0035, -0.1905, -0.4365, +0.1926, -0.0179, +0.2188, +0.1091, +0.2962, -0.0157, -0.1560, -0.1427, -0.3535, +0.3942, -0.8826, -0.0166, +0.1164, -0.8110, +0.5112, -0.4452],
-[ +0.1235, -0.1364, +0.0059, -0.1658, +0.1140, +0.2574, +0.0619, -0.0737, +0.2568, -0.1101, -0.0517, +0.0775, +0.3710, -0.3755, -0.5272, -0.1628, +0.0063, -0.2183, +0.3528, +0.3519, -0.0413, -0.1653, -0.1039, +0.1532, -0.0121, +0.0628, +0.1186, -0.0342, +0.6432, +0.2785, +0.1194, -0.1340, -0.0801, +0.5283, +0.0979, +0.1328, -0.0234, +0.0730, -0.2662, +0.3805, +0.2164, -0.5923, +0.2952, -0.1686, +0.0913, +0.4924, -0.6039, -0.2342, +0.0168, -0.4053, -0.1432, +0.1093, -0.5354, -0.1532, -0.0843, -0.2759, -0.5059, -0.5240, +0.2169, +0.1137, +0.1778, -0.8917, -0.0479, -0.4231],
-[ -0.0225, +0.2392, +0.2313, +0.2092, -0.2090, +0.5269, -0.2119, -0.6104, +0.2067, +0.1138, -0.0775, +0.2780, -0.3904, +0.2525, -0.5334, -0.0438, +0.3420, -0.1981, +0.3290, -0.3555, -0.2135, -0.1317, +0.2700, -0.0619, -0.6285, +0.2862, +0.3542, -0.6501, +0.2822, +0.1852, +0.2532, -0.0958, +0.2226, +0.0876, +0.0229, +0.0259, -0.1851, -0.2623, +0.0520, +0.1087, -0.1129, +0.4673, +0.0371, -0.5383, -0.2881, -0.3649, -0.2050, +0.0659, -0.1629, -0.2505, +0.2957, +0.1168, +0.1865, +0.3650, -0.2477, +0.2141, +0.1328, -0.3441, -0.4943, -0.1007, +0.2719, -0.2334, -0.0244, +0.2138],
-[ +0.0426, +0.2374, -0.6527, +0.2165, -0.0192, -0.2015, +0.1225, +0.4667, -0.2282, -0.1058, +0.1764, +0.3174, +0.1419, -0.2757, +0.1073, +0.0635, +0.0248, -0.3573, -0.4414, -0.0629, -0.3135, -1.3118, +0.1522, -0.0582, +0.0370, +0.4431, +0.3450, -0.1012, -0.5598, +0.1954, -0.0399, +0.1511, +0.3362, +0.0511, +0.0086, +0.6763, -0.3848, +0.3133, -0.4143, +0.0054, -0.2434, -0.0314, +0.4777, -0.2695, +0.1945, -0.4941, +0.2321, -0.2950, -0.2499, -0.7564, +0.2191, +0.0811, -0.6030, +0.0595, +0.2227, +0.1896, +0.1723, +0.0892, -0.2741, +0.4445, +0.3701, -0.4163, -0.3526, +0.0082],
-[ +0.2931, -0.0836, +0.1128, -0.2699, -0.1293, -0.9413, -0.3849, -0.0243, -0.1199, -0.0149, -0.1323, +0.1631, -0.3434, -0.7035, -0.4271, -0.0106, +0.5124, +0.3303, -0.4026, +0.1950, -0.1408, -0.3412, +0.0869, -0.3608, -0.4225, +0.1374, +0.1295, +0.2215, +0.6199, +0.5064, -0.0815, +0.1034, -0.2661, +0.2258, -0.0738, +0.1143, +0.2495, +0.2205, +0.1754, -0.4842, -0.1246, -0.2890, +0.3604, -0.9065, -0.3236, -0.1017, +0.2657, +0.2487, +0.1089, -0.1155, +0.3416, +0.0721, -0.0109, -0.0288, -0.1186, +0.2537, +0.2910, -0.2570, -0.4873, -0.0378, +0.4349, +0.1140, -0.8302, +0.1782],
-[ +0.1030, +0.1304, -0.0909, -0.2364, -0.2500, -0.3028, -0.0546, -0.6416, -0.1898, -0.3917, -0.2705, -0.3312, +0.3570, -0.2017, -0.0537, -0.6308, +0.0019, -0.1418, +0.2843, -0.0999, -0.5335, +0.1763, -0.3687, +0.1857, +0.0332, +0.4558, +0.2883, -0.0218, -0.2059, +0.4931, +0.4608, +0.0538, -0.5530, -0.1249, +0.1417, -0.6702, -0.2335, -0.7719, +0.2778, +0.0543, -0.0728, +0.1623, +0.4363, -0.3137, -1.1796, +0.3349, -0.1091, -0.1050, -1.2196, +0.1470, -0.3972, +0.5019, +0.1066, +0.4256, -0.1710, -1.0880, -0.0445, +0.2020, +0.0078, +0.2894, -0.1972, -0.4168, -0.5523, +0.0526],
-[ -0.1724, -0.1460, -0.4037, +0.0507, +0.3517, -0.1470, +0.2463, -0.9503, -0.5646, +0.2897, -0.3478, +0.0671, -0.0199, -0.2202, -0.1675, -0.9212, +0.4622, +0.1569, -0.0368, +0.1945, -0.0634, -0.9858, +0.0529, -0.0555, +0.1661, -0.0465, -0.0869, -0.0138, +0.0404, -0.7938, +0.0083, +0.3436, -1.1259, +0.1878, -0.5468, +0.0276, -0.1077, +0.5194, -0.1782, +0.1574, +0.3799, +0.0166, +0.1506, -0.2308, -0.5062, -0.6700, +0.0766, -0.2727, -0.5081, +0.0889, +0.0337, -0.0512, +0.2099, -0.3992, +0.2682, -0.1567, +0.1432, +0.1219, -0.1049, +0.2016, -0.2421, +0.3822, -0.3316, -0.0221],
-[ -0.0998, +0.3567, -0.9238, +0.2816, -0.0369, +0.3637, -0.1214, -0.4277, -0.4980, -0.0801, +0.1680, -0.4083, -0.4140, -0.1989, +0.1607, -0.4560, +0.1918, -0.2292, -0.0623, -0.3424, -0.1217, -0.0239, +0.3148, +0.0673, +0.4032, +0.2976, -0.1841, +0.4275, -0.3250, -0.3160, +0.0484, +0.3713, +0.3938, +0.0258, -0.2029, -0.0053, -0.4931, +0.2625, -0.3302, -0.0181, -0.8182, -0.2774, -0.1506, -1.1460, -0.4011, -0.2439, +0.0196, +0.2232, +0.8174, -0.0484, +0.1209, -0.0140, -0.3340, +0.3268, +0.0327, -0.1059, +0.1514, +0.3105, -0.0121, -0.3407, -0.1831, -0.1004, +0.3739, +0.1763],
-[ +0.4708, -0.0521, +0.0590, -0.1178, +0.0997, +0.5031, -0.3283, -0.4129, -0.0462, -0.9110, -0.1623, -0.7761, -0.0343, -0.1479, -0.2679, -1.0075, +0.4896, -0.2684, +0.1089, -0.5597, -0.1109, -0.1651, +0.4689, +0.6028, -0.6288, -0.0128, -0.3020, +0.0826, -0.0618, +0.5606, +0.6067, -0.0180, +0.4340, -0.4646, +0.2367, -0.1164, -0.5773, -0.0936, -1.4304, -0.2006, +0.2534, +0.1214, +0.4082, +0.4421, -0.0296, +0.7033, +0.4593, +0.0166, -0.3860, -0.4448, +0.0253, +0.3424, +0.1747, +0.4142, -0.5072, +0.0198, -0.2323, +0.2584, -0.5340, -0.2674, +0.3111, +0.0950, -1.2430, -0.3871],
-[ -0.3554, -0.4261, -0.3969, +0.1330, +0.3218, -0.1343, +0.3053, -0.5123, -0.0876, -0.1438, +0.1724, +0.4915, +0.3161, -0.6318, +0.0695, -0.0161, -0.0747, -0.1576, +0.2199, +0.0535, +0.3710, -0.1703, +0.0093, -0.2971, -0.3412, +0.0165, +0.1949, -0.2908, +0.1133, -0.0025, -0.0251, -0.3991, -0.5825, +0.1080, -0.5219, +0.3805, -0.0868, -0.0036, -0.4767, +0.3711, -0.0467, -0.3188, +0.3101, -0.4350, -0.5693, +0.0831, -0.0943, +0.0603, -0.3070, +0.1510, -0.3361, -0.3525, -0.0654, -0.2628, +0.0655, -0.3440, +0.0953, -0.0180, -0.3156, -0.1640, -0.2534, +0.2776, -0.5039, +0.4039],
-[ +0.1528, -0.4957, -0.3149, -0.6788, +0.5233, +0.3255, +0.7413, +0.1437, +0.7073, -0.1607, -0.0156, +0.8259, -0.4460, -0.4434, -0.0353, +0.1706, +0.0603, -0.2323, +0.3872, -0.2852, +0.1093, +0.5235, -0.4943, -0.0429, +0.0298, +0.3845, -0.4493, -0.5962, +0.2980, +0.1263, +0.4735, +0.3274, +0.2746, -0.2191, +0.0693, -0.1408, +0.3724, -0.1717, -0.4673, +0.0807, -0.3967, -0.4441, +0.1146, +0.3469, +0.0416, +0.4874, +0.2353, -0.2750, -0.2053, +0.3934, +0.3132, +0.5396, +0.7412, -0.6986, +0.2424, -0.2640, -0.4363, -1.1939, -0.1710, +0.2154, -0.1753, +0.0985, +0.2595, +0.2793],
-[ -0.0573, +0.0183, -0.8290, -0.3792, -0.4697, +0.1927, +0.2986, +0.0933, +0.6088, -0.0466, +0.0604, +0.2636, -0.2967, +0.7121, -0.3530, +0.4662, -0.1525, -1.1248, +0.1679, +0.1166, -0.1709, -0.0463, +0.2697, -0.1441, +0.1371, -0.8555, -0.7195, -0.0514, -0.1252, -0.2504, -0.1861, -0.2676, +0.3947, +0.2097, +0.1032, -0.1152, -0.6395, +0.0102, -0.3397, +0.9433, -1.0032, +0.3374, +0.3034, -0.5279, +0.2076, -0.2374, -0.2158, +0.6702, +0.3128, -0.0549, +0.0874, -0.4102, +0.1829, -0.4387, -0.5966, +0.2051, +0.4078, +0.1916, -0.1082, -0.0840, +0.0112, +0.2095, +0.4739, +0.0592],
-[ +0.0712, -0.1285, -0.3152, -0.2810, +0.1589, -0.5851, +0.2913, +0.4122, +0.3443, +0.1250, +0.3089, -0.6933, -0.1485, -0.2361, +0.0330, -0.0679, +0.5881, +0.0105, -0.6269, -0.3111, -0.0086, +0.3774, +0.1192, +0.3908, +0.2166, +0.0512, +0.0148, +0.1214, +0.0431, +0.3745, +0.1041, +0.1479, +0.0928, +0.2105, -0.2576, +0.1054, +0.1603, -0.0741, -0.9277, +0.0946, -0.4804, -0.8540, +0.2943, -0.2224, -0.3795, -0.2643, -0.3990, +0.1907, -0.0094, +0.2209, -0.3091, -0.3027, -0.2061, -0.0633, +0.1596, -0.0254, +0.0329, +0.1977, -0.0670, -0.0397, -0.2621, +0.1125, -0.3700, +0.0390],
-[ +0.3480, -0.7664, -0.4568, +0.1871, +0.5560, -0.1744, +0.3469, -0.2509, +0.2379, -0.0506, +0.2119, +0.3410, +0.2622, -0.6715, +0.1367, -0.4652, -1.4492, +0.2345, -0.0107, +0.3638, +0.1392, +0.1721, +0.1263, -0.4381, -0.1557, -0.0970, +0.4355, -0.3398, +0.3974, +0.1136, -0.1181, -0.0664, -0.0990, +0.2637, +0.0006, +0.1281, +0.0642, +0.4717, -0.3359, +0.0537, -0.0195, -0.3825, +0.1724, +0.3125, -0.4619, -0.2560, -0.1729, +0.0146, -0.9450, -0.0293, -0.1295, -0.1973, +0.3303, -0.4519, +0.3595, +0.2745, +0.0131, +0.0422, -0.5244, +0.0894, +0.1912, -0.3745, +0.1748, +0.0928],
-[ -0.1506, +0.2073, +0.2138, -0.2598, -1.1459, +0.2474, +0.2124, +0.2297, +0.0995, +0.4783, +0.1605, -0.6660, -0.4947, -0.1636, -1.4091, +0.2500, -0.1069, +0.0376, -0.2405, +0.1701, +0.1519, -0.4186, +0.4935, -0.8247, +0.1552, +0.1344, -0.1138, -0.3214, +0.1920, -0.6936, -0.3714, -0.1434, +0.1774, +0.1123, +0.1861, +0.7214, -0.0433, -0.1770, +0.2506, -0.5951, -0.0325, -0.2234, -0.4408, -0.5731, +0.4697, -0.0485, -0.2623, +0.3801, -0.2302, -0.4792, -0.0723, -0.8690, +0.4120, +0.0801, -0.5035, +0.6318, -0.4286, -1.7760, -0.1839, +0.1031, +0.0964, +0.2205, +0.1453, +0.1327],
-[ +0.0565, +0.1102, +0.0555, -0.3907, +0.3093, +0.6011, -0.1821, -0.8135, -0.3734, -0.4417, +0.3651, -0.3520, -0.6925, +0.0480, +0.4059, -0.0637, +0.1310, +0.1907, +0.1613, -0.2027, +0.1738, -0.4830, +0.4008, -0.2709, +0.0293, +0.2790, -0.2094, -0.3615, +0.1121, -0.3976, +0.2432, +0.1350, -0.3801, +0.0290, -0.3612, -0.1686, -0.2163, -0.2304, -0.6177, +0.3902, -0.3066, +0.2993, +0.0292, +0.3404, -0.0150, -0.1280, -0.2364, +0.1865, +0.0298, -0.2680, -0.1932, -0.1310, -0.2946, -0.9964, -0.4285, -0.4160, -0.1354, +0.2941, +0.0927, -0.1026, -0.1780, +0.1622, +0.0649, -0.8204],
-[ +0.1894, -0.0970, -0.2627, -0.2888, -0.1052, -0.0090, +0.1697, +0.1585, +0.0807, +0.2906, -0.1213, -0.4320, -0.3194, +0.4379, -0.3009, +0.2913, -0.0138, -0.2332, -0.2100, -0.0920, +0.0030, -0.1944, -0.1362, -0.0683, +0.1916, +0.2277, +0.0020, +0.0376, -0.2581, +0.0203, +0.0945, -0.0273, -0.1834, -0.1477, +0.3891, -0.8760, -0.7327, -0.3924, -0.7739, -0.2062, -0.9386, +0.0510, +0.1158, -0.5032, +0.0522, +0.0838, -0.2942, +0.0945, -0.2562, -0.2678, +0.0716, +0.1929, -0.2012, -0.6123, -0.3913, +0.0878, +0.4618, +0.3128, +0.2354, -0.1198, +0.2178, +0.4765, -0.2785, -0.1888],
-[ -0.2206, +0.3318, +0.2938, +0.4148, -0.0502, +0.6339, +0.1075, +0.0466, -0.0205, -0.0399, +0.1343, -0.1876, +0.1697, -0.1137, -0.3068, -1.2581, -0.4032, -0.2526, -0.0501, -0.4212, +0.2251, -0.1790, -0.4869, +0.6200, -0.5371, -0.5877, +0.0569, -0.3732, +0.1879, -0.5597, +0.3479, -0.6712, +0.2906, -0.3752, -0.3008, -0.0225, -0.0610, -0.1636, +0.4039, +0.1432, +0.2402, -0.0871, +0.1529, +0.0566, +0.1538, +0.1572, +0.1036, -0.0355, -0.7213, +0.2796, +0.1821, +0.1483, +0.2256, -0.2517, +0.2175, -1.6318, -0.3699, +0.0168, +0.1499, -0.2434, +0.4927, +0.3871, +0.4436, +0.3241],
-[ -0.3785, +0.3710, +0.5153, -0.2213, +0.1006, +0.0343, -0.3430, -1.3048, +0.2934, -1.1390, +0.0764, -0.4633, -0.3503, -0.1963, -0.6778, +0.1066, +0.3581, -0.4359, +0.2323, -0.0946, +0.3556, +0.0036, +0.1852, -0.4234, -0.7639, +0.1503, +0.5572, -0.0908, -0.0304, +0.3589, +0.4023, +0.2161, -0.3031, -0.5656, +0.4415, -0.2330, -0.2778, -0.1847, -0.4498, -0.1618, +0.0821, -0.0945, -0.2184, -0.4628, +0.4103, +0.3438, -0.2311, -0.2477, +0.3549, +0.3910, +0.1714, +0.2460, -0.5765, -0.3045, -0.0702, -0.1728, -0.4134, -0.1338, -1.0295, +0.2805, -0.6990, +0.7314, +0.2259, -0.0369],
-[ -0.7765, -0.8213, +0.0711, +0.2292, +0.2640, -0.1111, +0.0706, -0.9447, -0.0118, +0.0427, +0.2097, -0.0662, -0.2773, -0.4894, -0.7694, -0.3649, +0.1166, -0.3336, +0.3578, +0.0796, -0.1630, -0.1352, -0.0720, +0.1224, -0.3877, +0.1955, -0.1440, -0.0612, +0.1912, -0.1973, -0.0973, -0.0560, -0.7027, +0.2532, -0.3607, -0.1223, +0.0162, -0.0028, +0.4377, -0.0581, -0.3754, -0.2387, +0.0088, -0.0455, -0.1477, +0.4253, -0.0914, -0.7833, -0.1639, -0.0433, +0.0863, +0.2265, -0.0409, +0.0313, +0.1362, +0.4949, -0.0978, -0.5833, +0.0432, -0.4087, -0.1731, -0.0662, +0.4147, +0.1439],
-[ +0.0350, +0.1548, +0.0131, +0.0115, -0.3387, +0.2374, +0.3363, -0.5082, +0.5767, -1.2487, +0.1592, +0.1192, -0.9356, +0.0592, +0.4122, -0.4330, -0.3213, -1.4197, +0.3280, -0.2136, -0.4984, +0.2073, -0.0745, -0.2410, -0.2374, -0.0251, +0.2538, +0.2056, +0.0789, -0.5060, +0.3261, +0.2714, -0.3186, -0.1567, -0.0758, +0.2377, +0.1467, +0.5026, -0.3973, +0.9726, -0.0972, -0.0295, +0.0114, -0.3803, +0.2799, -0.3394, +0.1301, +0.0501, -0.1194, +0.3699, +0.0053, -0.4543, +0.2368, -0.1180, -0.0139, -0.3556, -0.1657, +0.2425, +0.1212, +0.0460, -0.3302, +0.0835, +0.1524, +0.2809],
-[ +0.5912, +0.3751, -0.7060, -0.6319, -0.0354, +0.0242, +0.0191, +0.1079, -0.2649, +0.3621, +0.0965, -0.0276, -1.0230, -0.3146, +0.2075, -0.6826, -0.3492, -0.0961, -0.5934, -0.6186, +0.0199, +0.2130, -0.7184, +0.4223, +0.0614, +0.1626, +0.2471, +0.2255, -0.2649, +0.1865, +0.2010, -0.0649, -0.7986, +0.3571, -0.7812, +0.0793, -1.1885, -0.7985, -0.4967, -0.0632, +0.1954, -0.3144, +0.1585, -0.2425, +0.0907, +0.0252, -0.9084, +0.3666, -0.5707, -0.5022, +0.2995, +0.2105, +0.5991, +0.0387, +0.0628, +0.1833, -0.1081, -0.6146, -1.9594, +0.3486, +0.4696, -0.0909, +0.2579, -0.8427],
-[ +0.0336, -0.4557, -0.6614, +0.4449, +0.0964, +0.1173, -0.4679, +0.3083, -0.3942, +0.2012, +0.0582, -1.3162, +0.0455, -0.5111, -0.6087, +0.2155, -0.0063, -0.1217, -0.0372, +0.0719, +0.3264, +0.4321, -0.5644, +0.4457, +0.6958, +0.3130, +0.1354, -0.0940, +0.1247, -0.1034, -0.3069, -0.5462, -0.3833, -0.2013, +0.0727, -0.2046, -0.6196, -0.2577, +0.1981, +0.0947, +0.2343, +0.2706, -0.0317, -0.4985, +0.2393, +0.2797, -0.0232, -0.4649, +0.6968, +0.1224, -0.0383, -0.5945, -0.5035, +0.0959, -0.3727, +0.7081, -0.1661, +0.1211, -0.1007, -0.2776, +0.2769, +0.3188, -0.8125, -0.2640],
-[ -0.2121, +0.1708, -0.0225, -0.0678, -0.0867, -0.0663, +0.2636, +0.2387, +0.2040, -0.2074, -0.4069, -0.1904, -0.0885, -0.4112, -0.5617, +0.3723, +0.4653, -0.2569, -0.3289, +0.4304, -0.0073, +0.0809, -0.0856, -0.0631, -0.2508, -0.3386, -0.8901, +0.1858, -0.1145, -0.0091, -0.0037, +0.3607, -0.0357, -0.7050, -0.2968, +0.3616, +0.2470, +0.2633, -0.0279, +0.0722, -0.4222, -0.1375, -0.4831, -0.2887, +0.0935, -0.0073, -0.4007, -0.1702, -0.2263, +0.3825, +0.1574, +0.6085, -0.1626, -1.7196, +0.3131, +0.2672, -0.1385, +0.3224, +0.3787, -0.0462, -0.3012, -0.5527, -0.4602, +0.1942],
-[ -0.6093, -0.9537, +0.1757, -0.3976, -0.0383, +0.7251, +0.3466, +0.4402, -0.0774, -0.4007, +0.0816, -0.0457, -0.1168, +0.2660, +0.1250, -0.5599, +0.2008, +0.8158, -0.4430, +0.4986, -0.5222, +0.3090, +0.0151, -0.1805, +0.1431, -0.1892, -0.6358, -0.2858, -0.2296, -0.1724, -0.4177, +0.0810, +0.0851, -0.0888, +0.2480, -0.2108, +0.2010, +0.0679, +0.0160, +0.1122, -0.5618, +0.0329, -0.1360, -0.5033, -0.3957, -0.2492, +0.5305, -0.7473, -0.2721, -0.0429, -0.0304, +0.0405, +0.6790, -0.1740, +0.3304, -0.0981, -0.4455, -0.0456, -0.1221, +0.2468, -0.6452, +0.0697, +0.3481, -0.0379],
-[ -0.1121, -0.5130, -0.5136, +0.3138, +0.2760, -0.3535, -0.3125, +0.3587, -0.4589, -0.1302, -0.3529, +0.4531, +0.1770, +0.2400, -0.0107, -0.2273, -0.0549, -0.1933, +0.0799, +0.0211, +0.0974, -0.3228, -0.1341, -0.5369, +0.2466, -0.2529, -0.0108, -0.3154, -0.0725, -0.1345, -0.2088, -0.0873, -0.3675, +0.0120, +0.0838, -0.1347, +0.2473, +0.4509, +0.4634, +0.1623, +0.0152, +0.4995, +0.4125, -0.0801, -0.9684, -1.0005, +0.1577, +0.3948, -0.1291, +0.1197, -0.0382, +0.1272, -0.4528, -0.1108, -0.2218, -1.0994, -0.0977, -0.3832, +0.1989, +0.3940, +0.2129, -0.1267, +0.2891, -0.4566],
-[ +0.2013, -0.4966, +0.3134, +0.2968, +0.4050, +0.3077, -0.0970, +0.0265, -0.6194, -0.4650, +0.2879, -0.5189, +0.0415, -0.0279, -0.2265, +0.2703, -0.0049, -0.1062, +0.0758, +0.5811, -0.4047, -0.4008, -0.5073, -0.1825, +0.3934, +0.1870, +0.0549, +0.2662, -0.1832, +0.0716, -0.5844, +0.0985, +0.1388, -0.4097, +0.3492, +0.3050, -0.3009, -0.3748, -0.0855, -0.2690, +0.0865, +0.0847, -0.2502, +0.4930, -0.4957, -0.0679, +0.2032, -0.5270, -0.0298, -0.6239, -0.3869, +0.1205, +0.2789, -0.4187, -0.4100, -1.3293, +0.0339, -1.2127, -0.4629, -0.4488, -0.3622, +0.3658, -0.1273, -0.9988],
-[ +0.0618, -0.6976, -0.2739, -0.4951, +0.3629, -0.0572, -0.0423, -0.1126, -0.0084, +0.0039, -1.1347, +0.0766, +0.5972, -0.2661, -0.1608, -0.1188, -0.5734, +0.2740, -0.1348, -0.0046, -0.2420, +0.4932, -0.3493, +0.0077, -0.2928, +0.1936, -0.4306, +0.0672, -0.2478, +0.2933, +0.4783, +0.1112, +0.0508, +0.5279, -0.0602, -0.6082, +0.0254, -0.1455, +0.0860, -0.0137, +0.2181, +0.4595, -0.1020, +0.2738, -0.3845, +0.1527, +0.0903, +0.2459, -0.1028, -0.0204, +0.3592, -0.1899, +0.0156, -0.3667, +0.2428, -0.2370, +0.4264, -0.1857, +0.1354, -0.1368, +0.1373, +0.3646, -0.1913, -0.2312],
-[ -0.1679, -0.2973, +0.3421, +0.2689, -0.0877, +0.2735, -0.1347, -0.2523, -0.0631, +0.1108, +0.2597, +0.4530, +0.1214, -0.1416, -0.5936, -0.1322, -0.2734, -0.7423, +0.1697, +0.0126, -0.2423, -0.0829, +0.4345, +0.2280, +0.1167, +0.0169, -0.1051, +0.4623, +0.1274, +0.1364, -0.7264, +0.2868, +0.2049, +0.0837, -0.6358, +0.0789, +0.1073, +0.5686, +0.3086, -0.5808, +0.7224, -0.5558, -0.5012, -0.0334, +0.1128, -0.4420, +0.0341, -0.0761, -0.6116, -0.1187, -0.0079, +0.1517, +0.1157, -0.0825, +0.0421, -0.4036, +0.2306, -0.1724, +0.0817, +0.0796, +0.2520, -0.0839, -0.1000, +0.2560],
-[ -0.1568, +0.1256, +0.2687, +0.5304, +0.0616, +0.2620, -0.1174, -0.0828, +0.2457, -0.7009, -0.2341, +0.1980, -0.1387, +0.0767, -0.1147, -0.3794, -0.0804, -0.9129, +0.4222, -0.0307, -0.4511, +0.0235, +0.2063, -0.0281, -0.6208, -0.3369, -0.2876, -0.1240, +0.0289, -0.1814, -0.0107, -0.6183, -0.0970, -0.1725, +0.0277, -0.2143, +0.4770, -0.3520, +0.2918, -0.2149, +0.0670, +0.2961, +0.0475, -0.2314, +0.4138, -0.6241, -0.5202, +0.6909, -0.1022, -1.0779, +0.0202, +0.3129, -0.1340, +0.0622, -0.1117, -0.2848, +0.1219, -0.2674, +0.2004, -0.4155, -0.0463, +0.1513, -0.0398, +0.3006],
-[ -0.6542, +0.7595, -1.3221, +0.0988, -0.3465, +0.4240, -0.0449, -0.8170, +0.0414, +0.1441, -0.6610, +0.0711, +0.1398, +0.6336, +0.0080, -0.0566, -0.0857, +0.1501, -0.0995, +0.1385, +0.2677, +0.0367, +0.1083, -0.0359, -0.1822, +0.1932, -0.1764, -0.4851, -0.0244, -0.3504, -0.0213, -0.1195, -0.2686, -0.5418, -0.4927, +0.3825, -0.0737, +0.0830, -0.2684, +0.2176, +0.1968, -0.2227, -0.3244, -0.6385, +0.1551, -0.2165, -0.0925, +0.1828, +0.4494, -0.1357, -0.0456, -0.0027, +0.1056, +0.3863, -0.1894, +0.0876, -0.1854, +0.1973, +0.3061, +0.0674, +0.6454, -0.2473, +0.2778, +0.3394],
-[ +0.1184, +0.0655, -0.4564, +0.1047, +0.0245, -0.3896, -0.4310, +0.2791, -0.4074, -0.2665, -0.4304, +0.6561, -0.6748, +0.1907, +0.5614, -1.5843, -0.0335, +0.1814, +0.3863, -0.3579, +0.0952, -0.3241, +0.0511, +0.4439, +0.5712, -0.4604, +0.1338, +0.7400, +0.2259, -0.5242, -0.5329, -0.4611, -0.1593, +0.0052, +0.1623, -0.3202, -0.5784, +0.0174, -0.8842, -0.4272, +0.3299, -0.2110, +0.0281, +0.4345, -0.0094, +0.4800, +0.0468, -0.1435, -0.1890, +0.4818, +0.3842, +0.5413, +0.0015, -0.1571, -0.0965, -0.2082, +0.3220, -0.4657, -0.2957, -0.4660, +0.1112, +0.0833, -1.0452, +0.2931],
-[ -0.1050, -0.3930, -0.8470, -0.1539, +0.0283, +0.0506, -0.2962, +0.1335, +0.1858, +0.2597, +0.1192, +0.0226, -1.1154, +0.4943, -0.2086, +0.3223, -0.2796, -0.7304, -0.3808, -0.2430, +0.1130, -1.4927, -0.0413, +0.1508, +0.2756, -0.1085, +0.0958, -0.0511, -0.1654, -0.5590, +0.4892, +0.3117, -0.4354, -0.5566, -0.2910, +0.1871, -0.3210, +0.0707, -1.4751, -0.0064, -0.3395, +0.1091, -0.3423, -0.1070, +0.6077, -0.6818, +0.0364, +0.1810, -0.2418, -0.4348, +0.2138, -0.4457, +0.1850, +0.1663, -0.4589, -0.0590, +0.0140, -1.0031, +0.1671, +0.3095, -0.1959, -0.2354, +0.1129, -0.0914],
-[ +0.1642, +0.1094, +0.3448, -0.0749, -0.0180, +0.2558, +0.4060, +0.3335, +0.4197, -0.1441, -0.2556, +0.6254, -0.3226, -0.6062, -0.2805, -0.1570, -0.3601, -0.3835, -0.2042, -0.0328, +0.1023, +0.0759, +0.2519, -0.1706, -0.0075, -0.4085, -0.3140, -0.1070, +0.0632, +0.0191, -0.4709, -0.2254, +0.0114, +0.3076, +0.2059, +0.5133, -0.2243, +0.2795, +0.3773, +0.0803, -0.4325, -0.9119, -0.1979, -0.6436, -0.2572, -0.3237, -0.4447, +0.5916, -0.3867, +0.0101, +0.1406, -0.1133, +0.2802, -0.6540, -0.3323, +0.4628, -0.0367, -0.2508, +0.2539, -0.3993, -0.5283, -0.2690, -0.3873, -0.3024],
-[ -0.1436, -0.5517, -0.4431, +0.5327, -0.2588, +0.0900, -0.4125, -0.2162, -0.1184, +0.2474, -0.1347, +0.1252, -0.0133, +0.0987, -0.4174, +0.3728, -0.1239, -0.2282, +0.0385, -0.1100, +0.6123, -0.4759, -0.3614, -0.0685, +0.3599, -0.0198, +0.1704, -0.0608, -0.0503, +0.4438, -0.7307, +0.3350, +0.1720, +0.4469, -0.0751, +0.0401, +0.3470, -0.0172, +0.0262, -0.0346, +0.1317, -0.1553, +0.2946, -0.2742, +0.2364, -0.0640, +0.2536, -1.0183, +0.0773, -0.2492, +0.0397, -0.3045, -0.3429, -0.3352, -0.5485, +0.3430, +0.1481, -0.4997, +0.0928, -0.2616, -0.1770, +0.5925, +0.1034, +0.1339],
-[ -0.2951, +0.0378, +0.0823, +0.0307, +0.0271, +0.3036, -0.0292, -0.2978, +0.0779, +0.1428, -0.4928, +0.2944, +0.2024, +0.1920, -1.0302, +0.3304, +0.0657, +0.0634, +0.3791, +0.0085, +0.0081, +0.2927, -0.0241, -0.2411, -0.7849, -0.1806, -0.0433, +0.3816, -0.0558, -0.1094, -0.0139, +0.1603, +0.4586, -0.7991, +0.1147, -0.5045, +0.0183, -0.3893, -0.0443, -0.1665, +0.0342, -0.2120, -0.1391, -0.4926, +0.1438, +0.1863, -0.7227, +0.3673, -0.1077, -0.9778, +0.7210, +0.3733, +0.0778, -0.4336, -0.3407, -0.0074, +0.0330, -0.4428, +0.1380, -0.8513, +0.0357, +0.4141, +0.1583, +0.2167],
-[ +0.2654, +0.0174, +0.2618, +0.1341, -0.1338, -0.1338, -0.2252, -0.1168, -0.0680, -0.1107, -0.7590, +0.0632, -0.0997, +0.2548, -0.8639, -0.7354, +0.2814, -0.4214, +0.2266, +0.0072, +0.1706, +0.3742, +0.2437, -0.5361, -0.2646, -0.3248, +0.1836, -1.9472, -0.0832, -0.0410, +0.4056, -0.4654, -0.3995, -0.4292, -0.4182, -0.4856, -0.8076, -0.7141, -0.2657, +0.0958, +0.0713, -0.2720, -0.2588, -0.5835, +0.4793, -0.4319, -0.1098, -0.3144, +0.4965, -0.4547, +0.3820, +0.4288, +0.0844, +0.5179, -0.0320, -0.8708, -0.0751, +0.1578, +0.0879, -0.4416, +0.1729, -0.1362, -0.5350, -0.3401],
-[ -0.2118, +0.3834, +0.3130, +0.3395, -0.3651, -0.0606, +0.4956, +0.0693, -0.0051, -1.4244, +0.1108, +0.0637, +0.1052, -0.0301, -0.0014, +0.0911, -0.8848, +0.1114, +0.0666, +0.3995, +0.4920, -0.5034, -0.3851, +0.1373, -0.1200, +0.3886, +0.0684, -0.0183, -0.4282, -0.0734, -0.1273, -0.4760, +0.1408, +0.5883, -0.0509, -0.2998, -0.3337, +0.1388, -0.2568, -0.1320, +0.1283, -0.5020, +0.1919, +0.1973, +0.3350, -0.0218, +0.7082, -0.2393, +0.0386, -0.9842, -0.6694, -0.5423, +0.0867, -0.8208, -0.1974, +0.3153, -0.2347, -0.7509, +0.1957, -0.2120, -0.1423, +0.0256, -0.5109, -0.5835],
-[ -1.1792, -0.6405, -0.2588, -0.0688, -0.5575, +0.2734, -0.2927, -0.9779, +0.3497, -0.7755, -0.3234, -0.2550, +0.3339, -0.4122, -0.0858, +0.3816, +0.4377, -0.9395, -0.0228, +0.2162, -0.0766, -0.2358, -1.2153, -0.0550, -0.0737, +0.2427, -0.2674, +0.1653, -0.3603, +0.2592, -0.3009, +0.0850, -0.1091, -0.6973, -0.4073, -0.6798, -0.0625, -0.3739, -0.0816, +0.0060, +0.1769, +0.5716, -0.2536, -0.3430, +0.1475, +0.0754, -0.1260, +0.2230, +0.0758, -0.1088, -0.0445, +0.2242, +0.1145, +0.4178, -0.6738, -0.2665, -0.0909, -0.7142, -0.1012, -0.4404, +0.0002, -0.0546, -0.3006, -0.0512],
-[ -0.9125, +0.3809, -0.2227, +0.1087, -0.3885, +0.2956, +0.2774, -0.5007, -0.3132, +0.0619, -0.1097, +0.1279, -0.0931, +0.1050, -0.3562, -1.4404, -0.4041, -0.1452, +0.2098, -0.3736, +0.4604, +0.3447, +0.3285, -0.4358, -0.0095, -1.4794, +0.1615, -0.3714, -0.1101, +0.2171, -0.2488, -0.5689, -0.0069, -0.3341, +0.4860, +0.1670, -0.5619, -0.2339, -0.4304, -0.1604, -0.1719, -0.1354, -0.1688, +0.5730, +0.0874, +0.9201, +0.4451, -0.1082, +0.5830, -0.5734, +0.8476, +0.1526, -0.0611, +0.0482, +0.4043, +0.1631, +0.0934, +0.5185, -0.4728, -0.7169, +0.2903, -0.1128, +0.1467, +0.0853],
-[ +0.2255, -0.1422, +0.6191, -0.5573, -0.4242, +0.6153, -0.0805, -0.6878, +0.0707, +0.1314, -1.1376, -0.4014, +0.0828, -0.1102, +0.4117, +0.1082, -0.1197, -0.0014, +0.2616, -0.4504, -0.1758, -0.5121, +0.4080, -0.7097, -1.0162, -0.0971, -0.1583, -0.4393, +0.2060, -0.2875, -0.0826, +0.0484, +0.1807, -1.0531, +0.1788, -0.2329, -1.2088, -1.2534, -0.3840, -0.3139, +0.1190, -0.4243, -0.3891, -0.1715, +0.2351, -0.0939, -0.1855, -0.4761, +0.4378, +0.1383, -0.0800, +0.1091, -0.3985, +0.0516, -0.1441, +0.0286, -1.0542, +0.4448, -0.8192, +0.4307, -0.2630, -0.6092, -0.0993, -0.1385],
-[ +0.1763, -0.3222, +0.2001, -0.5100, -0.0191, +0.3838, -0.2628, +0.4131, -0.3282, +0.5341, +0.1770, -0.3993, -0.4334, +0.3543, +0.4917, -0.3028, -0.5898, +0.2188, +0.4483, -0.4407, -0.1927, +0.0154, +0.1614, -0.7020, +0.3948, +0.1950, +0.0146, +0.4208, +0.3840, -0.2642, +0.7406, -0.1180, -0.0369, -0.8693, +0.2694, -0.0968, +0.0402, -0.1230, -0.2885, +0.0380, -0.4557, +0.2529, -0.1008, -0.1731, -0.8810, -0.2787, +0.4076, +0.1796, +0.4104, +0.3133, -0.5395, +0.0393, -0.2067, +0.7584, -0.3746, +0.0869, +0.6750, +0.3594, -0.3354, +0.2386, -0.1971, +0.0392, -0.0169, -0.1902],
-[ +0.2144, -0.3314, +0.2725, -0.0827, -0.0906, +0.0674, +0.1273, -0.4302, +0.2808, -0.8198, -0.0832, +0.3300, +0.4027, +0.0423, +0.2126, +0.1215, +0.1076, -0.3192, -0.0130, +0.2427, -0.1374, +0.1292, +0.1993, -0.5142, -0.1865, +0.0820, +0.0993, +0.1877, -0.3977, +0.0706, -0.7814, +0.2711, +0.4268, -0.1433, +0.4873, +0.5543, +0.0717, +0.2401, -0.0935, -0.2784, +0.2711, +0.2732, -0.8383, -0.2575, -0.0303, +0.0535, +0.1117, -0.3160, +0.2767, +0.1754, +0.0219, -0.0515, +0.0079, -0.7837, +0.1359, +0.0749, -0.2690, +0.1145, -0.1394, +0.2234, -0.8230, +0.2444, -0.5010, -0.0515],
-[ -0.7577, -0.1246, -0.6416, -0.1292, +0.1269, -0.1601, -0.7096, +0.5698, +0.1452, +0.2287, -0.1673, +0.1212, -0.0779, -0.3946, -0.6451, -1.1095, -0.7062, -0.0777, +0.1132, -0.2283, +0.0272, -0.0535, -0.0579, +0.3027, +0.3611, -0.0492, +0.0490, +0.1978, -0.1055, +0.1079, +0.2022, +0.1964, -0.3552, +0.0624, -0.2604, -0.3808, +0.0454, +0.3496, +0.1034, -0.1317, +0.2831, -0.8189, +0.2068, -0.0665, -0.2932, -0.3625, +0.1067, -0.3037, +0.3838, +0.0383, +0.1815, +0.2562, -0.0403, -0.0175, -0.1908, -0.7806, +0.1274, +0.1829, -0.1783, +0.2590, -0.4242, -0.0020, +0.2163, -0.7718],
-[ -0.1172, -0.2910, +0.1343, +0.1023, +0.2716, +0.2049, -0.6185, +0.2182, -0.1194, -0.0311, -0.4619, +0.2636, +0.2120, -0.2086, +0.0149, +0.0339, +0.2969, -0.3070, -0.2462, -0.1908, -0.2441, +0.3313, +0.6891, +0.1639, -1.0531, -0.1253, -0.2737, +0.2814, +0.1508, +0.1255, +0.4555, -0.0806, -0.0359, +0.0192, -0.0501, +0.3172, +0.0013, -0.8248, -0.1446, -0.1389, +0.3792, +0.3625, -0.2145, +0.0517, +0.2897, +0.0143, +0.0080, +0.1945, -0.4495, -0.0941, +0.5322, +0.2886, -0.0868, -1.5349, +0.0948, -0.7860, +0.5374, -0.5335, -0.0638, -0.1858, +0.0161, -0.2840, -0.3180, +0.3528],
-[ -0.3348, +0.2055, -0.9754, -0.4012, +0.4188, -0.2831, +0.1521, +0.1827, +0.1194, +0.0318, -0.0500, -0.4176, -0.3061, +0.0976, -0.0334, -0.0595, -1.2187, -0.2892, -0.0487, -0.3854, -0.0304, +0.1867, -0.0166, +0.2530, +0.2887, -0.2363, -0.1904, +0.2580, +0.0583, +0.3023, -0.0038, -0.3527, +0.3573, -0.0487, -0.0710, -0.4197, +0.1109, +0.1214, -0.5087, +0.3008, -1.3029, -0.4291, -0.0687, +0.1112, +0.1664, +0.4177, +0.0462, +0.0217, +0.3115, +0.2880, +0.1207, -0.1077, +0.1978, +0.0262, +0.2084, -0.4996, +0.0478, +0.3084, -0.0012, -0.2354, -0.5644, +0.1193, +0.0854, -0.5877],
-[ -0.3103, -0.3814, +0.1322, -0.1447, -0.2558, +0.0371, +0.0856, +0.1248, +0.2103, -0.2475, -0.2205, +0.3099, +0.3163, -0.1651, +0.2838, +0.2346, -0.3855, -0.2486, -0.3396, -0.0437, +0.3671, -0.0069, +0.4828, -0.6932, -0.7277, +0.3441, -0.8020, +0.4863, +0.1061, -0.2418, -0.2396, -0.0053, -0.1668, -0.2948, -0.0782, -0.0149, +0.3159, +0.2116, +0.2267, -0.2058, +0.1034, -0.0827, +0.0529, +0.0069, +0.1822, +0.0000, +0.0525, +0.2258, -0.2335, -0.0016, -0.1231, +0.8993, -0.6615, -0.8643, -0.1698, -0.1447, +0.0801, -1.4432, -0.2538, +0.1848, +0.1005, +0.3882, +0.0458, +0.0405],
-[ +0.3984, +0.1613, +0.5291, +0.1697, -0.2074, -0.4148, -0.3233, -0.3691, -0.1697, -0.0608, -1.2200, +0.2840, -0.7305, -0.2600, +0.2990, +0.0959, -0.0343, +0.2958, +0.1014, -0.2986, -0.6878, +0.1185, -0.4202, -0.5000, -0.2732, +0.0477, +0.0419, -0.4453, -0.3634, -0.2955, +0.1807, +0.2088, -0.1500, -0.1789, -0.2411, -0.3513, -0.2156, +0.1619, -0.7682, -0.2928, +0.2605, +0.4007, +0.1044, -0.7360, +0.1440, -0.4713, -0.2737, -0.5854, +0.0717, +0.5728, +0.3894, +0.1652, -0.5978, +0.2093, +0.2174, -0.3677, -0.2305, -0.1676, -1.2163, -0.3159, -0.5652, -0.1905, -0.1668, +0.2184],
-[ -0.0008, -1.0383, +1.1172, -0.3757, +0.1185, +0.2778, +0.1407, -0.1279, -0.5174, -0.4343, +0.0887, -0.0483, -0.0541, -0.3713, -0.3302, +0.4045, +0.4483, -0.6313, +0.0040, +0.1367, +0.2285, -0.2697, -1.1601, +0.0076, +0.1744, +0.1132, -0.1431, -0.3811, -0.6136, +0.2844, -0.1848, -0.5152, -1.0414, -0.4109, -0.7278, -0.0349, +0.1370, -0.1978, +0.5068, +0.1623, -0.2598, -0.5556, +0.2846, -0.1811, -1.5462, -0.2162, +0.5351, -0.2391, -0.1035, -0.2865, -0.1122, +0.4251, -0.2923, -0.8803, +0.1712, +0.1824, +0.2363, -0.6512, +0.2178, -0.4485, -0.3429, -0.1578, +0.1009, -0.1692],
-[ +0.0041, +0.4229, +0.0388, +0.5734, +0.1830, -0.5990, +0.0260, -0.4107, -0.1851, -0.2277, -0.0275, -0.2505, +0.4437, +0.3490, +0.2597, -0.1346, -0.5125, -0.1878, -0.4422, +0.0793, +0.0946, +0.1463, +0.3695, +0.4150, +0.2463, -0.4557, +0.4123, +0.2879, +0.6034, -0.5302, -0.7214, -0.2835, -0.0240, +0.2951, +0.3102, -0.2566, -0.0515, -0.1121, -0.5604, -0.3810, +0.4285, +0.9055, -0.2602, +0.2380, -0.3954, -0.0396, +0.6154, +0.0981, +0.4571, +0.0322, +0.2965, +0.1396, -0.0881, -0.0175, +0.3386, -0.0699, +0.1114, +0.3103, +0.0885, -0.2483, +0.3396, -0.5895, -0.4524, +0.4458],
-[ -0.7421, -0.1838, +0.0929, +0.1654, -0.1778, +0.1589, +0.1777, +0.1539, +0.6931, -0.0002, +0.0366, -0.2482, +0.3404, -0.6776, -0.0599, -0.9906, -0.1703, -0.2741, -0.2623, +0.2435, +0.1282, -0.2218, -0.4463, -0.0515, -0.1126, +0.5793, -0.4053, +0.3077, -0.2113, -0.1654, -0.4019, +0.3054, -0.2755, -0.0359, -1.3564, +0.7528, +0.0788, +0.2060, +0.1633, -0.4355, +0.2035, -0.2194, -0.0381, -0.1512, -0.7473, +0.2736, -0.0204, -0.4578, -0.4144, +0.0076, -0.6070, +0.0851, +0.4764, -0.3511, -0.1171, -0.8141, +0.1976, +0.2906, +0.0918, +0.2261, +0.2769, +0.1746, +0.5881, -0.8917],
-[ -0.3276, -0.1296, +0.3245, -0.0630, +0.1080, -0.0923, -0.0555, -0.4351, -0.4805, +0.1625, -0.7317, +0.0232, -0.0290, -1.2621, +0.0074, +0.6063, -0.0992, +0.2137, -0.0525, -0.1596, +0.2326, +0.7151, -0.2879, -0.9427, +0.0728, +0.3451, -1.3029, -0.1453, -0.0766, -0.1260, +0.2174, +0.2524, -0.0272, -0.9901, -0.2757, -0.0532, +0.0768, -0.6334, +0.2368, +0.1227, -0.6449, -0.0662, +0.3466, -0.1741, +0.1209, +0.4601, +0.1192, -0.0727, -0.3973, -0.2250, +0.1601, +0.1562, -0.2805, -0.0830, -0.0274, -0.4325, +0.0951, -0.1183, +0.1025, +0.0261, -0.6047, -0.0146, -0.1957, +0.0218],
-[ +0.1081, +0.3138, +0.3278, -0.7791, +0.1543, -0.1908, +0.3635, +0.0070, +0.3577, -0.0404, -0.8582, -0.4834, +0.3016, -0.6306, -0.4563, +0.1801, -0.2791, -0.6206, +0.0517, +0.5410, +0.1347, +0.4778, +0.0558, -0.0759, -0.0772, +0.1917, -0.7159, -0.0643, -0.1721, -0.5170, -0.3511, -0.3017, +0.1299, -0.7527, -0.1136, -0.3605, -0.3682, -0.0709, +0.0723, -0.2196, -0.9063, -0.3520, -0.3413, +0.2594, +0.1649, -0.5071, -0.1584, +0.1231, +0.0057, -0.4875, +0.2410, -0.2405, +0.3705, -1.0071, +0.3241, +0.0207, -0.4803, -0.4314, +0.1130, -0.0724, +0.2252, -0.2790, +0.0415, +0.0660],
-[ -1.0239, +0.0612, -0.1775, +0.0616, +0.3968, +0.1192, -0.0637, -1.3325, +0.0141, -0.3692, -0.2163, +0.1634, +0.1818, +0.1767, -0.3110, -0.5755, -0.2020, -0.1910, +0.4489, -0.0309, +0.2252, +0.0045, +0.0525, -0.9357, +0.0912, -0.2257, +0.2897, +0.4927, +0.0509, -0.3725, +0.2843, -0.8260, -0.1409, -1.0330, -0.1377, +0.2625, +0.0637, -0.5822, -1.0901, +0.2305, -0.0809, -0.4811, -0.2776, +0.1618, -0.6189, +0.1608, +0.2586, -0.4005, -0.0048, -0.4438, -0.0799, +0.1356, +0.0141, -0.1191, +0.3150, -0.4819, -0.2142, +0.1938, +0.2875, -0.5401, +0.0929, -0.3865, -0.0821, -0.5999],
-[ +0.4043, -0.0639, -0.3917, +0.0908, +0.0894, -0.4655, -0.2022, +0.3332, -0.2707, +0.0466, +0.1355, +0.1318, -0.3180, -0.3957, -0.0124, -0.7214, -0.2792, +0.3177, -0.5455, -0.5225, -0.2927, -0.2688, +0.0192, +0.3940, +0.0514, +0.2258, -0.3504, -0.0024, +0.0145, -0.2194, -0.0040, +0.2842, -0.0667, -0.4815, +0.2162, +0.1778, -0.7473, +0.4520, +0.1720, -0.5224, -0.0490, -0.5519, -0.3571, +0.4386, -0.1868, -0.2627, -0.3350, -0.7849, -0.1009, +0.1432, -0.2389, +0.1923, -0.4800, +0.0100, -0.0507, +0.0151, +0.3257, +0.0299, +0.0118, +0.2283, -0.2633, +0.2229, -0.7595, +0.1507],
-[ +0.2797, -0.2386, -0.0121, +0.2439, -0.0317, -0.0390, +0.0581, -0.8813, -0.5392, -0.2527, -0.4720, +0.4787, +0.3710, +0.0434, +0.0702, -1.0678, -0.0195, -0.6846, -0.7418, +0.0543, -0.3187, -0.1510, -0.3590, -0.0902, +0.2195, +0.0943, -0.0384, -0.7203, +0.0316, -0.0647, +0.1894, +0.2490, -1.3374, +0.3883, +0.1207, +0.4036, +0.3255, +0.3757, +0.2444, +0.2612, -1.5274, +0.1092, +0.5718, -0.1929, -0.1531, -0.2330, +0.0539, +0.2055, -0.8240, +0.1292, -0.4835, +0.5281, +0.1944, -0.3389, -0.3689, +0.4941, +0.0330, +0.0938, +0.4999, -0.2465, -0.2547, +0.3286, -0.2172, +0.4791],
-[ +0.4580, +0.6728, +0.1603, -0.5751, -0.8616, +0.0422, -0.3104, -0.2042, +0.4133, +0.3150, -0.8036, -0.5332, +0.5432, +0.2999, +0.1480, -0.2845, -0.9013, -0.0924, -0.6048, -0.1631, -0.1127, -0.3833, -0.5830, -1.1764, -1.2800, -0.0174, -0.2561, +0.1081, +0.3352, +0.1175, +0.3419, +0.7590, +0.4220, -0.8411, +0.0312, +0.3287, +0.2295, -0.0867, -0.6239, +0.0633, +0.3005, -0.0838, -0.4589, -0.2385, +0.2734, -0.2946, -0.2759, -0.4446, +0.0052, -0.3499, -0.3503, +0.1211, -0.1839, -0.2803, +0.0158, +0.2441, +0.4413, -0.4929, +0.3714, +0.5445, -0.0731, -0.3297, -0.5428, +0.4811],
-[ -0.3528, +0.2554, +0.1195, +0.2853, -0.0731, -0.0237, -0.0755, +0.3719, -0.5900, +0.3071, +0.1961, -0.3822, -0.3113, +0.3011, +0.1113, -0.1598, -0.0299, +0.6281, +0.1811, +0.1312, +0.1971, -0.4736, +0.7463, -0.0154, +0.4255, -0.3671, +0.3200, -0.1815, -0.4259, +0.1115, +0.4232, -0.3993, +0.0706, -0.1901, +0.1188, -0.6964, -0.5131, -0.5996, -0.0103, +0.1504, +0.0713, -0.0430, -0.8008, +0.1890, -0.2637, +0.1984, +0.0119, +0.1025, -0.9490, -0.0255, +0.2795, +0.2354, -0.1830, +0.1894, -0.1928, -0.8840, +0.3929, +0.1748, +0.1588, +0.4326, -0.0759, +0.1664, +0.2102, -0.3707],
-[ +0.0479, -0.0155, -0.3830, +0.0390, -0.0793, -0.1159, -0.0263, -0.3720, -0.9581, +0.2546, -0.4353, +0.2756, -0.0628, +0.0360, +0.1591, -0.7122, +0.1463, -0.1078, -0.5880, +0.1476, -0.0437, -0.6911, -0.0355, +0.2766, -0.3426, +0.2286, -0.2323, -0.2819, -0.0887, +0.5000, -0.0338, -0.1563, -0.0168, +0.0500, -0.1077, +0.4968, -1.1365, +0.1814, -0.1388, -0.1080, +0.0761, -0.4107, +0.3764, +0.3308, +0.0905, -0.2821, -0.2366, -0.2618, +0.2762, -0.2521, +0.1400, -0.1133, +0.0411, -0.0475, -0.4804, +0.4348, -0.1652, +0.0103, +0.2100, -0.3716, +0.1860, -0.3946, -0.1734, +0.2052],
-[ -0.0266, -0.2590, -0.1527, +0.2632, -0.1506, -0.0040, -0.3828, -0.7623, -0.1620, -0.1641, +0.0927, +0.1030, -0.1890, +0.2110, +0.1634, -1.4356, +0.1170, -0.7333, -0.3429, -0.3402, +0.5740, +0.2288, +0.0264, -0.0770, +0.0611, +0.2538, +0.5611, -0.0635, -0.0885, -0.0698, +0.2153, +0.0752, -0.2368, +0.2113, -0.8473, -0.7176, -0.3615, -0.2906, +0.0310, +0.0041, -0.3076, +0.1850, +0.0959, -0.1510, +0.1042, +0.0781, +0.1000, -0.0701, -0.0252, +0.6513, +0.1680, +0.3624, -0.5958, -0.6897, +0.1336, -0.0600, +0.0437, -0.2525, +0.1216, -0.2053, +0.0452, +0.8903, -0.0487, -0.0072]
+weights_dense1_b = np.array([
+ -0.0148, -0.0390, -0.2168, -0.0866, -0.0677, -0.1575, +0.0077, -0.1385,
+ -0.0953, -0.2318, -0.1402, -0.0267, -0.0565, -0.1655, -0.0944, -0.1856,
+ +0.1183, -0.0606, -0.1517, -0.1972, -0.0256, -0.1761, -0.2543, -0.1125,
+ -0.1902, -0.1462, +0.0160, -0.2130, -0.1644, +0.0530, -0.0384, -0.1030,
+ -0.1822, -0.0219, -0.1597, -0.1946, -0.1177, -0.1970, -0.1569, -0.2162,
+ -0.0256, -0.2618, -0.2127, -0.0910, -0.1862, -0.0517, -0.0811, -0.2137,
+ +0.0810, -0.2098, -0.2763, -0.0980, -0.0986, -0.0983, -0.2186, -0.1723,
+ -0.0822, -0.1072, -0.1466, -0.3015, +0.2120, -0.0178, +0.0700, -0.1122,
+ -0.2641, -0.1767, -0.0722, +0.0859, -0.3453, -0.2988, -0.0838, -0.1928,
+ -0.0916, -0.1749, -0.0969, -0.2420, -0.0859, -0.1487, -0.0692, -0.0028,
+ -0.0989, -0.1322, -0.0582, -0.2906, -0.1255, -0.0026, +0.0352, -0.2485,
+ -0.0592, -0.0695, -0.1047, -0.1616, -0.2268, -0.1474, -0.2683, +0.1161,
+ -0.1794, -0.1011, -0.1924, +0.0348, -0.0169, -0.3281, -0.2085, -0.2750,
+ -0.3329, -0.1793, -0.2296, -0.2289, -0.1589, -0.3225, +0.0159, -0.2951,
+ -0.0156, -0.0544, -0.1193, -0.1563, -0.1691, -0.1292, +0.0228, -0.2741,
+ -0.0235, -0.0564, +0.1007, -0.0648, -0.1383, -0.0235, -0.0557, -0.0005
])
-weights_dense2_b = np.array([ +0.2226, +0.0124, +0.0027, +0.2335, +0.0952, +0.0250, +0.1087, +0.1225, +0.0476, +0.1535, +0.0940, +0.0421, +0.0967, +0.0431, -0.2867, -0.1520, -0.0796, +0.0041, +0.0599, +0.0139, -0.0608, -0.0695, +0.0222, +0.0420, -0.0988, +0.0851, +0.2547, +0.0361, +0.0341, +0.0986, +0.1827, -0.1344, +0.1575, +0.0374, +0.0497, -0.1436, +0.1622, +0.2187, +0.0257, +0.0680, -0.0228, +0.0215, +0.1596, -0.0594, -0.0886, -0.0006, -0.0940, +0.1568, +0.0610, +0.1915, +0.1162, +0.0765, -0.1731, -0.0258, +0.0896, -0.2285, +0.0948, +0.0286, +0.1174, +0.0382, +0.2536, +0.3435, +0.0281, +0.2328])
+weights_dense2_w = np.array(
+ [[
+ +0.0547, +0.0221, +0.0159, -0.3500, +0.1057, -0.3978, -0.4751, -0.2686,
+ -0.2984, -0.3477, -0.7638, +0.3041, -0.9283, +0.3769, +0.3866, +0.1042,
+ -0.5446, -1.0826, -0.3685, +0.0957, -1.1452, +0.4594, -0.2719, -0.5546,
+ -0.4310, +0.4055, +0.3174, -0.6414, +0.4058, +0.0122, -0.6446, +0.0312,
+ -0.2846, +0.3681, -0.2635, +0.4684, -0.0438, -0.1535, +0.0279, -0.3398,
+ +0.0489, +0.2915, -0.2513, -1.0484, +0.1129, -0.7923, +0.1379, -0.2217,
+ +0.1685, -0.0273, +0.2727, -0.1051, -0.3335, +0.4067, +0.1543, -0.0099,
+ -0.2005, -0.5140, -0.1314, -0.0537, -0.6073, -0.2714, +0.4734, +0.0307
+ ],
+ [
+ +0.1983, -0.4372, +0.2649, -0.6106, -0.5667, +0.2295, +0.2821,
+ -0.1570, +0.1007, +0.0072, +0.1053, +0.1223, +0.5393, +0.0445,
+ +0.4042, +0.1218, +0.1946, +0.3514, +0.6725, +0.3489, -0.2839,
+ -0.3705, +0.2665, +0.2710, +0.2836, +0.1292, -0.2779, -0.3549,
+ -0.6220, -0.0934, -0.6794, +0.2522, -0.0012, -0.7044, +0.0819,
+ -0.1884, -0.5545, +0.2331, +0.0573, +0.1692, +0.3610, -0.5304,
+ +0.0751, +0.4747, -0.1379, +0.1396, -0.1418, +0.2756, -0.3771,
+ -0.5534, -0.7892, -0.5082, -0.4949, -0.5125, +0.3863, -0.4106,
+ -0.3488, +0.3701, -0.0261, -0.2519, +0.3600, -0.0131, -0.5443, -0.2148
+ ],
+ [
+ -0.4168, +0.0202, -0.3568, +0.3985, +0.0842, -0.1247, -0.1143,
+ +0.3105, +0.0295, +0.1222, -0.9825, +0.2732, +0.1502, -0.1901,
+ +0.2854, -0.0271, +0.2689, +0.2394, -0.0163, +0.3020, +0.1345,
+ +0.2447, -0.1126, -0.5997, -0.1411, +0.3111, +0.1018, -0.1057,
+ -0.2686, -0.0710, -0.2928, -0.0877, -0.5635, -0.0538, +0.0074,
+ +0.0630, -0.9421, -0.1443, -0.7025, -0.5890, -0.2607, -0.3678,
+ -0.9102, -0.0042, -0.0763, -0.2665, +0.2550, -0.1257, -0.0960,
+ -0.4207, -0.3315, +0.3159, -0.1579, +0.6020, +0.1635, -0.1936,
+ +0.1230, -0.0245, -0.1494, -0.1828, -0.1856, -1.0757, -0.9589, -0.2000
+ ],
+ [
+ +0.3752, -0.3057, +0.3341, -0.2068, +0.3930, -0.3313, -0.3786,
+ +0.2107, +0.0767, +0.2396, +0.4759, +0.4447, -0.0988, -0.3320,
+ -0.3001, +0.1111, -0.3114, -0.0926, +0.5017, -0.0114, -0.2243,
+ -0.0705, -0.2502, +0.1573, -0.5134, -0.0888, +0.3586, +0.1723,
+ +0.1582, +0.3832, -0.4192, -0.3290, +0.1729, +0.0234, +0.3742,
+ +0.2108, +0.0021, +0.1886, +0.4553, -0.0405, -0.2013, +0.0391,
+ +0.0099, -0.3560, -0.2403, -0.5404, -0.0850, -1.1031, +0.2303,
+ +0.2130, -0.0970, -0.0781, -0.1787, +0.0094, +0.0652, +0.0435,
+ +0.1182, -0.3572, -0.1822, +0.3167, -0.4896, -0.3626, -0.1668, -0.2644
+ ],
+ [
+ -0.3002, -0.1710, +0.0482, -0.2977, +0.6775, +0.2932, +0.3891,
+ -0.1426, -0.3008, +0.1301, -0.6758, -0.1576, +0.1714, +0.3555,
+ -0.6530, +0.2284, -0.5148, -0.2974, +0.1985, -0.0305, +0.5279,
+ -0.3357, -0.4142, -0.2472, -0.0224, -0.1873, +0.1376, -0.4045,
+ +0.1122, +0.2617, +0.4392, -0.1154, -0.2372, -0.0144, +0.0885,
+ -0.4898, +0.1629, +0.2722, -0.4575, -0.2204, +0.5557, -0.3414,
+ +0.1573, -0.0259, +0.0639, -0.1291, -0.6438, -0.6169, +0.2151,
+ -0.0527, +0.1338, +0.1200, +0.0151, -0.4535, +0.3047, -0.4136,
+ -0.0690, -0.8133, -0.3369, -0.2327, +0.3387, -0.6738, -0.2590, -0.2750
+ ],
+ [
+ -0.5166, -0.2531, -0.5999, -0.0659, -0.0589, -0.1377, -0.0247,
+ -0.3631, -0.1956, +0.2281, +0.0912, +0.2150, -0.0213, -0.2618,
+ -0.3139, -0.6331, +0.2083, +0.0745, -0.0525, +0.4477, +0.2109,
+ -0.1076, +0.3572, +0.4534, -0.2742, -0.0868, -0.4000, +0.3491,
+ +0.0116, +0.1590, -0.0994, +0.0526, -0.3198, -0.2717, -0.1091,
+ +0.2476, -0.6484, -0.0838, +0.1230, -1.4295, -0.4766, -0.0778,
+ -0.5194, -1.0485, -0.4056, +0.5590, +0.1986, +0.0920, -0.2564,
+ -0.0405, +0.1153, +0.0622, +0.1561, +0.6891, -0.2484, +0.3777,
+ +0.4026, +0.4245, +0.5501, -0.2535, +0.1263, -0.5236, -0.3086, -0.4384
+ ],
+ [
+ +0.0267, +0.4426, -0.1992, +0.0821, -0.9791, -0.3588, -0.4260,
+ -0.1455, -0.0490, -0.1547, -0.2543, -0.3684, +0.3642, -0.0006,
+ -0.3487, -0.0551, +0.0879, +0.1316, -0.5557, +0.5368, -0.0159,
+ +0.3170, -0.1802, -0.6798, +0.0029, -0.2864, -0.0650, +0.1866,
+ +0.0697, +0.5808, -0.1085, -0.2594, +0.3730, -0.0222, +0.0780,
+ -0.1649, -0.7503, +0.2781, +0.2997, -0.6883, -0.2393, -0.9101,
+ -0.3439, -0.0368, +0.2190, -0.1207, +0.1521, -0.6376, +0.5755,
+ -0.2450, +0.2238, -0.3727, +0.0233, +0.0576, -0.1159, +0.4381,
+ +0.1958, +0.0134, +0.3485, -0.4711, +0.2344, +0.0854, -1.0917, +0.3356
+ ],
+ [
+ +0.3785, +0.3636, -0.3251, +0.3122, +0.2442, -0.5955, -0.0093,
+ -0.3778, -0.2082, -0.1958, -0.8252, +0.1736, +0.1166, +0.8199,
+ +0.3367, -0.1289, +0.4549, +0.2460, +0.1128, +0.3572, -0.2274,
+ -0.2742, -0.5444, -0.1523, +0.0356, +0.3113, +0.0246, -0.5069,
+ -0.3344, +0.1946, +0.0670, +0.1407, +0.7479, +0.3682, +0.8027,
+ +0.2609, -0.4183, -0.1806, +0.1140, +0.2086, +0.0652, +0.0760,
+ +0.2543, -0.7174, -0.5935, -0.2738, +0.1096, -0.4978, +0.4936,
+ -0.2776, +0.6209, +0.1223, -0.4159, -0.2111, +0.2914, -0.3457,
+ -0.2449, +0.0895, +0.0807, +0.5205, -0.2385, -0.1925, +0.1622, +0.0880
+ ],
+ [
+ -0.2673, -0.3082, +0.5204, +0.3821, +0.2027, -0.0957, +0.3922,
+ -0.0725, +0.0775, -0.1621, +0.1395, -0.0934, -0.5586, +0.4102,
+ +0.4102, -0.0876, -0.8250, -0.3138, +0.0615, +0.0265, -0.8760,
+ +0.3662, +0.3313, -0.0017, +0.2562, +0.0531, +0.0796, +0.0291,
+ +0.1880, -0.2079, -1.4376, +0.0385, -0.4895, +0.4806, -0.4420,
+ -0.4066, +0.1672, +0.0695, -1.0768, +0.0349, -0.5809, +0.0600,
+ +0.0560, -0.1884, +0.1944, -0.4875, -0.2761, -0.1072, -0.5009,
+ +0.2840, +0.0430, -0.4216, -0.5786, +0.0545, +0.1343, +0.3776,
+ +0.3305, +0.4333, +0.0847, +0.4369, -0.0030, +0.0307, +0.3003, +0.2691
+ ],
+ [
+ +0.0893, -0.4704, -0.2054, +0.3949, -0.2963, -0.2947, -0.3435,
+ +0.3517, -0.8073, +0.0914, +0.2846, +0.0485, -0.1339, +0.1669,
+ -0.2241, -0.7245, -0.5583, -0.0823, -0.3668, +0.0645, -0.1111,
+ -0.3214, -0.3099, +0.1846, +0.3734, +0.0287, -0.2115, +0.0354,
+ +0.3143, -0.1244, +0.0086, -0.0529, +0.2437, -0.3184, +0.4261,
+ +0.0090, -0.1972, -0.2668, -0.0503, -0.3085, +0.0711, +0.0746,
+ +0.0209, -0.2126, -0.0542, -0.0856, -0.0140, -0.5341, +0.3074,
+ +0.6249, -0.0955, +0.1454, -0.0128, +0.1829, -0.3874, -1.1490,
+ +0.3613, -0.0753, +0.2431, +0.0126, -0.4169, +0.4549, -0.2987, +0.1634
+ ],
+ [
+ +0.2796, -0.8066, -0.1895, +0.0652, +0.0235, -0.0806, -0.6463,
+ +0.2801, -0.1388, +0.2654, +0.1312, +0.2453, -0.3954, -0.6161,
+ -0.0602, +0.0419, +0.1494, +0.2994, +0.2134, -0.1138, -0.1966,
+ -0.3912, -0.4885, -0.4361, +0.0082, +0.2686, +0.5057, +0.2438,
+ +0.2241, +0.2533, +0.0221, +0.2056, -0.3449, +0.1963, -0.1053,
+ +0.1093, +0.2248, -0.1142, +0.3292, -0.0353, -0.1378, -0.4590,
+ +0.1552, -0.6599, -0.4846, -0.2242, +0.7134, -1.2819, -0.2578,
+ +0.0916, +0.4744, -0.1979, -0.2302, +0.0517, +0.1801, -0.0128,
+ +0.2979, -0.6418, -0.4409, -0.1068, -0.3446, +0.0824, +0.1677, -0.2113
+ ],
+ [
+ +0.0620, +0.0141, +0.8828, +0.1967, -0.2820, -0.3151, -0.4239,
+ -0.0684, +0.2535, -0.1108, -0.4921, +0.1686, -0.1226, +0.0875,
+ -0.4216, +0.2957, +0.2862, +0.0746, -0.1089, +0.0779, +0.0448,
+ -0.1151, +0.2984, -0.2249, -0.1200, -0.1098, +0.4338, -0.3360,
+ +0.0512, -0.1089, -0.1694, -0.0086, +0.2826, -0.0504, +0.0745,
+ +0.1197, -0.1845, -0.0413, +0.0941, +0.1136, -0.7052, -0.9186,
+ -0.2386, -0.1812, -0.0689, -0.7612, -0.4205, +0.2777, +0.5319,
+ -0.3707, -0.2872, +0.0674, +0.1655, +0.3701, -0.4204, -0.0941,
+ +0.0053, +0.1772, -0.8221, +0.3939, +0.0265, -0.0402, -0.4258, -0.4838
+ ],
+ [
+ +0.0312, +0.4064, -0.0163, -0.3321, +0.2323, -0.2347, +0.1756,
+ -0.1976, +0.0030, -0.3264, +0.1410, -0.8448, -0.1253, -0.1722,
+ +0.0647, -0.6614, +0.0124, -0.5357, -0.2659, -0.5198, -0.1104,
+ +0.0036, +0.5971, +0.2923, +0.2818, -0.3823, +0.1973, -0.0398,
+ +0.5571, +0.1238, +0.2223, -0.1846, +0.0045, +0.2834, +0.2652,
+ -0.5670, +0.1025, +0.0954, -0.6847, +0.2716, -0.1995, +0.2227,
+ -0.0417, -0.5204, -0.4656, +0.0143, +0.1697, +0.2654, -0.0200,
+ +0.0227, -0.1669, +0.0093, +0.1622, -1.0894, +0.3023, -0.0433,
+ -0.8114, -0.3466, -0.0044, -0.4344, +0.5942, -0.2995, +0.2493, -0.2656
+ ],
+ [
+ +0.0884, -0.1168, +0.2659, -0.2658, -0.0894, -0.3646, +0.0123,
+ -0.2345, -0.1249, -0.5543, -0.4367, +0.0704, +0.1846, -0.5260,
+ -0.0185, -0.1435, -0.0243, +0.2774, -0.1795, -0.2214, +0.0297,
+ +0.1819, +0.0135, +0.0257, +0.1465, +0.5108, -0.0764, -0.2536,
+ +0.1924, -0.3582, -0.1813, -0.2825, +0.1625, -0.4450, +0.1806,
+ +0.2287, +0.1214, -0.2687, +0.1684, -0.4179, -0.1748, -1.4161,
+ +0.0182, +0.3509, +0.2804, +0.1512, -0.4392, +0.1313, +0.0852,
+ -0.6827, +0.0465, -0.1457, +0.0937, +0.4504, -0.2384, -0.2387,
+ -0.5351, -0.4227, +0.2521, -0.1205, +0.3281, -0.4157, -0.0388, -0.0779
+ ],
+ [
+ -0.4328, +0.1671, -0.2333, +0.3447, +0.2475, -0.0963, -0.0289,
+ -0.1134, -0.6314, -0.0779, -0.0052, -0.5183, +0.1591, -0.1890,
+ -0.1690, -1.2456, +0.1215, -0.7981, -0.7112, -0.1237, -0.4438,
+ +0.2475, +0.2704, -0.3184, +0.0800, -0.3449, +0.1936, -0.2232,
+ +0.0352, -0.0664, -0.0191, +0.1109, -0.1613, +0.1971, -0.2887,
+ -0.6279, +0.4588, +0.2611, +0.0068, -0.1602, +0.1105, +0.1328,
+ +0.2169, +0.0899, -0.4866, -0.2267, +0.0581, -0.2022, -0.7508,
+ +0.0740, -0.6069, +0.5649, +0.0207, +0.1216, -0.1130, -0.8590,
+ +0.0055, -0.0647, +0.3094, -0.3780, -0.2064, +0.4434, -0.4378, +0.2624
+ ],
+ [
+ -0.1505, +0.4615, -0.9363, +0.1984, -0.2306, +0.1047, +0.2547,
+ -0.4131, -0.2132, -0.6349, +0.0660, -0.0981, +0.3538, +0.5521,
+ -0.1076, -0.4321, -0.2629, -0.2857, -0.1064, +0.1612, -0.5917,
+ +0.1856, +0.2716, -0.6279, +0.2015, +0.0297, +0.1344, -0.6113,
+ +0.1501, -0.0768, +0.3218, +0.5261, +0.0611, +0.1559, +0.5267,
+ +0.0392, -0.4469, -0.3359, +0.3373, +0.1011, +0.0721, -0.0051,
+ -0.3831, -1.0682, +0.3176, +0.0177, +0.1255, -0.0222, +0.2602,
+ -0.0707, +0.6271, +0.0442, -0.7024, +0.3064, -0.6523, -0.1607,
+ -0.1061, +0.6141, +0.2525, +0.4590, -0.1475, -0.2303, -0.1497, +0.1568
+ ],
+ [
+ -0.6547, +0.1965, +0.5732, +0.0585, -0.7985, +0.2784, +0.1409,
+ +0.3753, +0.5077, -0.2973, +0.4522, -0.0481, -0.0250, -0.1732,
+ -0.0189, +0.1741, +0.1811, -0.5026, +0.3383, -0.2984, -0.1815,
+ -0.2687, +0.1435, -0.5299, -0.5446, +0.2488, +0.0848, +0.2456,
+ -0.6651, -0.4723, -0.2933, -0.2168, +0.1354, -0.1201, +0.7322,
+ +0.3879, -0.5529, +0.0442, +0.1429, +0.2459, -0.3643, -1.2003,
+ -0.0014, -0.0881, -0.2888, -0.1497, -0.4499, +0.2563, +0.1399,
+ +0.3984, -0.3034, -0.2152, -0.1062, -0.0971, +0.4006, -0.2250,
+ -0.3419, -0.2266, -0.3736, +0.5701, -0.6925, -0.0455, -0.0159, -0.5060
+ ],
+ [
+ +0.2558, +0.0784, +0.5193, +0.1619, +0.2345, -0.3461, +0.1533,
+ +0.0035, -0.6782, -0.8183, -0.9718, +0.4590, +0.1314, +0.2691,
+ +0.0578, +0.3015, +0.1275, -0.2170, -0.1059, -0.3437, +0.2150,
+ -0.0420, -0.1466, -0.3230, -0.2263, -0.2463, +0.3428, -0.2851,
+ -0.1670, +0.8334, -0.3321, -0.5703, +0.4210, -0.3807, +0.5608,
+ +0.1184, +0.0216, +0.3875, -0.0818, -0.3773, +0.2697, +0.0836,
+ -0.5769, +0.1107, +0.2502, +0.1319, +0.1555, -0.5250, -0.0333,
+ -0.2451, -0.0840, -0.2520, -0.5473, +0.5264, -0.2354, -0.4220,
+ -0.0929, -1.0100, -0.2290, +0.3894, +0.1722, +0.2778, +0.2404, +0.5252
+ ],
+ [
+ +0.3719, -0.1570, +0.0631, -0.1366, -0.0117, +0.1695, +0.2635,
+ -0.5559, -0.5966, +0.0401, +0.4796, -0.0389, +0.4392, -0.1852,
+ +0.4559, +0.0249, +0.1135, +0.1914, -0.0850, +0.8742, +0.3766,
+ -1.2051, +0.1491, +0.3556, -0.6834, -0.6127, -0.3816, -0.2803,
+ -0.9287, -0.6655, +0.4073, -0.1513, +0.3072, -0.1859, -0.6259,
+ -0.1803, +0.0372, +0.0066, +0.0768, +0.3041, +0.4044, +0.2719,
+ +0.0495, -0.4712, -0.0753, -0.1619, +0.4040, +0.3667, -1.2573,
+ -0.0153, +0.2433, -0.4797, -0.1008, +0.2793, -0.5162, +0.0750,
+ -0.1875, +0.6019, +0.2983, -0.2629, +0.3859, -0.1606, -0.0607, +0.2640
+ ],
+ [
+ -0.7689, +0.1244, -0.0722, +0.1658, +0.0536, +0.0774, -0.0666,
+ -0.3190, +0.3863, +0.0221, +0.3311, -0.0757, +0.2848, -0.4570,
+ +0.1558, +0.1559, +0.1904, +0.2411, -0.0255, +0.2793, +0.2985,
+ -0.3438, +0.0476, -0.4403, -0.5639, +0.1262, -0.2366, -0.5360,
+ -0.0511, +0.1175, -0.2260, -0.4008, -0.3002, -0.7550, -0.7351,
+ -0.0725, -0.3370, +0.5923, -0.2017, +0.1863, +0.3965, -0.3253,
+ -0.0685, +0.0485, -0.0183, +0.1959, +0.2554, -0.1661, -0.9667,
+ +0.1877, -0.1062, -0.4295, -0.2307, +0.0769, +0.1511, -0.7353,
+ -0.4450, +0.2015, -0.3559, +0.6302, +0.1058, +0.3851, +0.0694, -0.5665
+ ],
+ [
+ +0.2654, -0.7518, +0.1643, -0.0339, -0.0219, -0.0515, +0.4850,
+ +0.1158, -0.3727, +0.1568, -0.2977, +0.3162, +0.0700, -0.4247,
+ +0.2545, +0.2225, -0.0498, +0.4013, -0.1575, -0.3545, -0.2154,
+ -0.9544, -0.0608, +0.2827, +0.2211, +0.1790, -0.0234, -0.1396,
+ -1.2595, -0.1827, +0.2853, +0.0978, +0.1027, -0.2280, -0.5227,
+ -0.5996, +0.2517, +0.3419, +0.4186, +0.4399, +0.4078, -0.3085,
+ +0.1905, +0.3559, -0.1620, +0.3125, -0.0422, +0.1617, -0.0414,
+ +0.4358, -0.4426, -0.4533, -0.7251, -0.4293, +0.0632, +0.0825,
+ +0.1159, +0.6398, +0.2352, +0.3725, +0.3426, +0.1757, -0.2817, -0.5600
+ ],
+ [
+ +0.0965, +0.1435, -0.0668, -0.0310, +0.0492, +0.3276, +0.0812,
+ +0.1402, +0.0513, -1.0857, -0.1374, -1.0262, -0.7472, +0.1752,
+ +0.1458, -0.3731, -0.2896, +0.1206, +0.2268, -0.4120, +0.2665,
+ -0.4842, -0.0096, -0.3069, -0.0961, -0.1954, +0.3195, -0.4060,
+ -0.2027, +0.1026, +0.3581, +0.0684, +0.2964, -0.3857, +0.3346,
+ +0.2853, -0.1779, +0.6816, -0.1396, -0.1068, +0.0874, +0.2093,
+ +0.0690, -0.1075, +0.3425, +0.0184, +0.5206, +0.3363, +0.2432,
+ +0.1155, -0.4405, -0.4702, +0.0007, -0.6360, -0.1712, +0.0258,
+ +0.1292, +0.1699, +0.0017, +0.1035, -0.0856, +0.3821, +0.0642, -0.1730
+ ],
+ [
+ -0.2957, -1.8336, +0.0635, -0.1502, -0.3054, -0.0347, +0.4553,
+ -1.5017, -0.1386, +0.2204, -1.5949, -0.1060, +0.0207, -0.3453,
+ +0.1805, +0.1862, +0.1077, +0.0503, +0.4847, +0.0824, -0.1334,
+ +0.1013, -0.0132, -0.2091, -0.0147, +0.3173, -0.5393, -0.1905,
+ -0.6108, -0.4315, +0.1379, +0.3715, +0.4988, +0.0204, -1.0445,
+ -0.7534, +0.3054, +0.1166, -0.2072, +0.2696, -0.0510, -0.2593,
+ -0.1224, -0.7100, -0.0739, -0.4827, +0.2711, -0.1706, +0.3453,
+ +0.2951, +0.0905, -0.7676, +0.3072, +0.4110, -0.7400, -0.0282,
+ +0.3160, +0.0045, +0.3315, -0.1876, -0.5153, -0.0300, +0.0528, -0.0902
+ ],
+ [
+ -0.0392, -0.2831, -0.8638, +0.0181, -0.1839, +0.1190, +0.1256,
+ +0.0349, +0.0335, +0.3621, +0.0015, -0.0992, -0.2544, -0.6373,
+ -0.5993, +0.3642, +0.0229, -1.3911, +0.0442, +0.3622, -0.0907,
+ +0.0980, -0.1975, +0.2308, -1.1896, -0.4979, +0.1135, -0.0943,
+ +0.0679, -0.0002, -0.0083, -0.8543, +0.2544, -0.0756, -0.9005,
+ -0.0970, -0.0499, +0.2011, -0.0504, -0.4152, -0.1189, +0.0047,
+ +0.1132, +0.1040, -0.0365, -0.1372, +0.0665, -0.3832, -0.3141,
+ +0.0644, -0.0858, -0.2961, +0.2374, +0.3307, +0.2823, -0.0944,
+ -0.1386, -0.1009, +0.1643, -0.8802, -0.2065, +0.2246, +0.1913, -0.0572
+ ],
+ [
+ -0.1170, -0.4247, +0.2971, -0.0218, +0.2794, -0.3040, +0.1894,
+ -0.0772, -0.4478, +0.0155, -0.8504, -0.2509, -0.0805, +0.0955,
+ +0.2145, +0.3553, -0.4790, +0.0649, -0.0476, -0.0949, -0.0201,
+ +0.0573, +0.1713, +0.0237, -0.1585, +0.2141, -0.3027, -0.2567,
+ -0.1553, +0.1717, -0.2864, +0.1060, -0.0100, -0.7441, -0.0440,
+ -0.5248, +0.4325, +0.0117, -0.0124, +0.4722, +0.3972, +0.3061,
+ -0.0881, +0.0888, +0.1247, +0.0465, -0.3472, +0.0608, +0.1640,
+ +0.0900, +0.0040, -0.2854, -0.3570, -0.2206, +0.4373, -0.0944,
+ -0.0799, -1.0422, +0.0771, -0.6116, +0.5273, -0.0734, +0.0059, +0.0125
+ ],
+ [
+ -0.1478, -0.0775, -0.4148, +0.2235, +0.0244, -0.4050, -0.1933,
+ -0.1451, +0.3546, +0.4780, -0.0377, +0.3747, -0.2634, +0.1820,
+ -0.2871, -0.0375, -0.1472, -1.0087, +0.3116, +0.0882, +0.1714,
+ -0.1267, +0.0243, +0.1244, -0.6763, +0.3206, +0.1243, +0.3372,
+ +0.0311, +0.2017, -0.1272, +0.1254, +0.2171, +0.1646, -0.3122,
+ -0.2863, -0.0401, +0.0408, +0.2649, -0.9490, +0.1101, +0.0612,
+ +0.0200, +0.0067, -0.1735, +0.4192, +0.5672, -0.4306, -0.2337,
+ +0.1219, -0.0581, -0.6563, +0.2676, +0.0907, +0.0774, +0.3393,
+ +0.3514, -0.5195, +0.2571, -1.0322, -0.3714, +0.1705, -0.2050, -0.1214
+ ],
+ [
+ +0.2841, +0.2037, +0.0734, -0.3167, -0.2534, +0.3772, +0.3707,
+ -0.0807, +0.2971, +0.1787, +0.0742, -0.7424, +0.0534, -0.6033,
+ -0.2538, -0.1693, -0.0417, +0.1408, -0.0786, +0.0125, -0.2959,
+ +0.3026, +0.1068, +0.3710, -0.0259, -0.2119, +0.2311, +0.1579,
+ +0.4271, -0.1637, -0.1047, -1.4823, +0.1537, -0.6320, +0.0265,
+ -0.3799, +0.2478, -0.5812, -0.1404, -0.0219, -0.1906, -0.0507,
+ +0.1606, +0.3727, +0.2747, +0.0747, -0.1603, +0.3651, +0.0592,
+ -0.2988, +0.1446, -0.4449, +0.0282, +0.1628, +0.1572, -0.9307,
+ -0.5926, +0.0564, +0.4344, -0.2915, -0.0055, -0.0388, -0.2319, +0.0708
+ ],
+ [
+ -0.1260, -1.1956, -0.3519, -0.1696, -0.5884, -0.3108, -0.2285,
+ +0.2627, +0.3962, +0.0449, +0.0626, +0.2328, +0.0144, +0.1303,
+ +0.3914, -0.8420, +0.4524, -0.4737, -0.5874, -0.2379, -0.0688,
+ -0.0159, +0.1504, -0.8424, -0.3590, -0.3149, -0.3955, -0.0819,
+ -0.2932, +0.1551, -0.0380, -0.3986, -0.0895, -1.1964, +0.2346,
+ +0.0107, -0.5550, +0.0978, -0.2178, -0.0702, +0.0130, -0.0487,
+ +0.1236, +0.2701, -0.0855, -0.6003, +0.0025, -0.4898, -0.4901,
+ +0.3732, -0.1348, -0.0001, +0.0022, +0.4124, -0.2319, -0.8846,
+ +0.1981, +0.3517, +0.3260, +0.2913, -0.6865, -0.1172, -0.1017, -0.2988
+ ],
+ [
+ -0.1994, -0.0318, -0.6611, +0.0667, +0.0348, -0.2005, -0.0708,
+ -0.8554, -0.2964, +0.1114, +0.2106, -0.3456, +0.0631, -0.6458,
+ -0.4482, +0.4112, +0.4312, +0.0396, -0.8510, +0.3383, -0.3657,
+ -0.3998, -0.0279, -0.3247, +0.2809, +0.0671, -0.1980, -0.3156,
+ -0.1614, +0.1241, +0.1267, +0.0882, -0.8523, +0.3680, -0.1008,
+ +0.3258, +0.7330, -0.0226, +0.2324, +0.2983, -0.4784, -0.0821,
+ -0.3784, -0.5416, -0.0020, +0.0128, -0.1557, +0.1735, -0.0400,
+ +0.3065, +0.0703, -0.1273, +0.3064, -0.0101, -0.5155, +0.1910,
+ +0.0411, +0.2573, -0.3383, +0.1305, +0.0244, -0.0700, -0.5478, -0.2243
+ ],
+ [
+ +0.6525, -0.1060, +0.0967, -0.2523, -0.0679, -0.2359, -0.1002,
+ -0.1302, -0.2785, -0.0323, -0.2069, -0.4863, +0.4068, -0.2921,
+ +0.0689, +0.0659, +0.3440, +0.0730, -0.2341, +0.1442, +0.0321,
+ -0.4033, +0.3169, +0.2174, -0.3649, -0.3458, -0.0410, +0.1900,
+ -0.3263, +0.0535, +0.2253, -0.0717, +0.2190, -0.3860, +0.4562,
+ -0.0471, -0.6580, +0.1243, +0.0968, -0.0801, +0.2969, -0.1420,
+ +0.0635, +0.3387, -0.0512, +0.0064, +0.3651, -0.0423, +0.0007,
+ -0.5414, -0.1172, -0.1081, -0.1545, -0.0802, -0.9081, +0.1538,
+ -0.0143, +0.0015, -0.2125, -0.1439, +0.3589, -0.6707, -0.6915, +0.2103
+ ],
+ [
+ +0.1954, +0.0473, +0.0005, -0.2376, +0.2730, -0.2364, +0.1537,
+ -0.3518, -0.2333, -0.6985, +0.1143, -0.4291, -0.4548, -0.0803,
+ -0.5521, -0.4564, -0.5651, -1.0630, +0.1796, -0.0002, +0.0015,
+ -0.3317, -0.7872, -0.0555, -0.0872, -0.0989, -0.2793, +0.2904,
+ -0.2892, +0.2572, +0.2525, -0.3601, +0.1851, -0.3061, +0.4080,
+ -0.9798, -0.0559, -0.0152, -0.2210, -0.2351, -1.2633, -1.3520,
+ +0.1842, -0.8754, -0.3290, -0.2398, -0.1657, -0.3064, +0.4170,
+ -0.1810, +0.3617, -0.0774, +0.1052, -1.0043, -0.0412, +0.1861,
+ -0.0364, -0.0832, -0.3337, -0.0208, -0.4717, +0.2991, +0.5363, -0.7141
+ ],
+ [
+ -0.2813, -0.3716, -0.0886, -0.5633, +0.1087, +0.1772, -0.0322,
+ -0.1692, +0.3300, -1.0514, -0.1952, -0.5817, +0.1098, +0.2299,
+ +0.1408, -0.8174, -1.5817, -0.0897, +0.4067, -0.8538, +0.2466,
+ -0.2321, -0.0760, +0.3167, +0.1953, -0.0280, +0.1107, -0.1015,
+ +0.1602, -0.1283, +0.0893, +0.2528, +0.3058, +0.4486, +0.0661,
+ -0.6155, +0.1135, -0.0380, -0.1616, -0.2837, +0.0692, +0.0797,
+ -0.0934, +0.1645, -0.6896, -0.1260, +0.0314, -0.0450, -0.2893,
+ -0.1417, -0.0603, -0.3250, +0.2633, -0.4442, -0.2169, +0.0100,
+ -1.6046, -0.8446, +0.0547, -0.2022, +0.1854, +0.2163, +0.1098, -0.4998
+ ],
+ [
+ -0.2718, +0.0985, +0.1143, +0.5034, +0.1062, -0.2774, +0.0928,
+ +0.4507, -0.2889, +0.1647, +0.1606, -0.5096, +0.0797, +0.2081,
+ +0.1015, -0.0662, -0.5561, +0.0133, -0.1913, +0.4173, -0.2062,
+ -0.0683, -0.0707, -0.3881, -0.1940, -0.1059, +0.1708, -0.0068,
+ +0.4992, +0.1805, -0.0863, -0.1116, +0.2974, +0.6512, +0.2988,
+ -0.7671, -0.3240, -0.2382, -0.3154, -0.4172, -0.0090, +0.3568,
+ +0.0629, -0.4475, +0.0085, +0.3164, +0.8345, -0.9105, +0.4016,
+ +0.0489, +0.1487, -0.1455, -0.0914, +0.3481, -0.0170, -0.2977,
+ +0.0686, -0.3068, +0.4279, +0.1365, +0.0191, +0.3697, +0.2504, -0.2336
+ ],
+ [
+ -0.4281, -0.1639, -0.6842, -0.0854, -0.3867, +0.1215, +0.2188,
+ -0.0905, -0.0237, +0.3002, -0.1625, -0.0496, +0.2249, +0.0999,
+ -0.0021, -0.0105, +0.0438, -0.2453, -0.7972, -0.0544, -0.6363,
+ +0.4864, +0.1242, +0.0230, +0.3307, -0.4536, -0.1405, +0.2291,
+ -0.3801, -0.1614, -0.0584, +0.2719, -0.2294, +0.1266, -0.7109,
+ -0.3877, +0.3089, -0.3075, -0.5052, +0.2617, -0.8302, -0.1543,
+ +0.4105, -0.1404, -0.2835, -0.1752, -0.3642, +0.1386, -0.1469,
+ +0.3241, +0.0407, +0.1294, +0.0788, -0.0815, -0.7150, +0.2538,
+ +0.5408, +0.5778, +0.2923, -0.3580, -0.0519, +0.2803, +0.0072, +0.1857
+ ],
+ [
+ +0.1413, -0.4943, -0.6837, +0.2482, -0.1298, -0.2851, -0.0800,
+ -0.9522, -0.0827, -0.4602, +0.1367, +0.2338, +0.4496, +0.0029,
+ -0.6388, -0.3566, -0.1129, -0.2587, +0.1929, +0.2315, -0.1974,
+ +0.1578, +0.2540, +0.2304, +0.0193, -0.2805, -0.0064, -0.3831,
+ +0.2310, +0.2366, -0.0409, +0.0743, -0.6095, +0.3397, -0.5128,
+ -0.0056, +0.3138, +0.4122, +0.0952, -0.1192, -0.1181, -0.1224,
+ +0.3857, -0.1165, -0.0761, -0.5138, -0.4998, -0.1310, -1.3272,
+ -0.0823, +0.2054, +0.3836, +0.1094, -0.1651, +0.1319, +0.0349,
+ +0.0455, +0.3051, -0.2890, -0.3378, +0.4504, -0.4409, +0.0342, +0.2857
+ ],
+ [
+ -0.6909, -0.2404, -0.5480, +0.1982, +0.7179, -0.1566, +0.5150,
+ -0.3021, -0.1896, +0.3692, -0.2610, +0.1676, +0.2646, -0.0779,
+ -0.6376, -0.4375, +0.0814, -0.0594, +0.1491, +0.6636, -0.0098,
+ -0.4666, -0.5695, -0.4680, +0.3753, -0.2631, -0.3479, -1.0949,
+ -0.1768, -0.0397, -0.2667, +0.2302, -0.3895, +0.2984, -0.1895,
+ -0.1393, -0.1342, +0.5137, +0.0543, -0.1336, -0.0678, -0.9658,
+ -0.4799, +0.4449, -0.0855, -0.0889, +0.0750, -0.0107, -0.8546,
+ -0.1215, -0.0314, +0.0430, +0.4070, -0.4824, +0.0688, +0.3415,
+ +0.0656, +0.0570, +0.0387, +0.4817, +0.1426, +0.0509, +0.0760, -0.4065
+ ],
+ [
+ +0.4383, +0.1584, -0.0754, +0.1745, +0.0786, +0.2143, +0.1374,
+ +0.0865, +0.4707, -0.6604, +0.4382, +0.2705, -0.0253, +0.2995,
+ -0.4382, -0.0289, -0.4109, +0.0659, -0.0184, +0.3955, -0.0828,
+ -0.7735, -0.0186, -0.3625, -0.3181, -0.1457, +0.3396, -0.2431,
+ -0.1825, +0.1364, +0.1260, +0.0534, +0.2614, -0.0357, +0.2487,
+ +0.1936, +0.4056, +0.2736, +0.3650, +0.2727, +0.3510, +0.0828,
+ +0.1987, +0.0946, -0.3942, +0.2064, +0.1439, +0.1201, -0.4372,
+ +0.2936, +0.1877, +0.1580, -0.2083, -0.2638, +0.0890, -0.4047,
+ +0.0004, -0.0605, -0.2715, +0.0797, +0.1276, +0.4446, -0.2733, +0.2584
+ ],
+ [
+ -0.5070, -0.6084, +0.1098, +0.2952, +0.3233, +0.1273, -0.1590,
+ +0.4029, -0.0075, -0.2986, -0.0453, -0.0251, +0.0636, -0.3285,
+ +0.3005, +0.4278, -1.2692, -0.3260, -0.3904, -0.4674, -0.1919,
+ +0.1708, -0.2957, -0.3654, +0.0608, +0.3880, -0.3380, -0.0002,
+ -0.1227, +0.0483, -0.3408, +0.2696, -0.2904, -0.8352, +0.2176,
+ -0.8516, +0.1110, -0.0138, -0.6308, -0.2065, +0.5916, -0.0596,
+ -0.0420, +0.4001, +0.1048, -0.1863, +0.2619, +0.0696, +0.2273,
+ -0.1749, -0.4023, +0.4499, -1.5990, -0.4454, -0.0222, -0.4018,
+ -0.3324, +0.1569, -0.0777, +0.0774, -0.2870, +0.2780, +0.1298, -0.5494
+ ],
+ [
+ +0.4041, +0.2116, +0.1746, +0.3060, +0.3644, +0.2566, -0.2467,
+ +0.0528, -0.1645, -0.2514, +0.3191, -0.0146, -0.2756, -0.1343,
+ -0.1539, -0.4656, -0.0026, -0.0629, -0.3565, -0.7495, -0.6157,
+ -0.2922, +0.0272, +0.3853, -0.3030, +0.1152, +0.6219, +0.0596,
+ +0.2660, +0.3633, +0.3082, +0.4234, +0.1700, -0.7490, +0.6056,
+ +0.0380, -0.1250, +0.1593, -0.0863, -0.3877, -0.0154, -0.6906,
+ -0.1813, -0.1751, -0.0309, +0.0954, -0.0752, +0.1333, -0.3153,
+ +0.0735, +0.2958, -0.0313, -0.0686, -0.0086, -0.3676, +0.4638,
+ -0.0175, +0.0595, +0.4441, +0.0093, +0.2578, +0.1221, +0.0885, +0.2014
+ ],
+ [
+ -0.5199, +0.6037, +0.1349, +0.0017, +0.1035, -0.1073, +0.4821,
+ -0.2727, -0.7271, +0.4909, -0.4462, +0.0574, +0.2442, -0.4101,
+ +0.2368, -0.0281, +0.1593, +0.2608, -0.1477, -0.0326, +0.1544,
+ -0.2897, -0.3711, -1.0289, -0.1497, +0.3172, -0.6857, +0.1492,
+ -0.0524, +0.1699, +0.0543, -0.1961, +0.0100, -0.5156, -0.5196,
+ +0.0112, -0.3831, -0.2663, -0.4071, -0.5762, -0.4060, -0.1983,
+ +0.4095, +0.0808, +0.1072, +0.2126, +0.1083, -0.3055, +0.4092,
+ +0.0916, -0.0140, +0.0065, -0.2017, -0.8640, +0.0456, -0.0038,
+ +0.2211, -0.3172, +0.0554, -0.1270, -0.1246, -0.0759, -0.3650, -0.3657
+ ],
+ [
+ -0.3915, -0.5535, -0.1423, -0.3716, -0.7515, +0.3826, +0.1549,
+ -0.0311, +0.1627, -0.5930, +0.5855, -0.1633, -0.5803, -0.2441,
+ +0.4444, -0.0405, +0.5196, +0.3439, -0.7971, +0.3043, -0.1354,
+ -0.3644, +0.4925, +0.1056, +0.1867, +0.3991, -0.6626, +0.1049,
+ -0.0140, -0.8950, +0.1062, -0.0186, +0.0854, -0.2033, +0.1403,
+ -0.3018, -0.6041, -0.4544, +0.3293, -1.0832, +0.0505, +0.1097,
+ -0.4619, -0.3131, +0.5037, -1.0137, -0.3421, +0.1212, -1.0994,
+ +0.0358, +0.4906, -0.0352, -0.1116, -0.1726, -1.1999, -0.4828,
+ +0.3461, -0.2870, -0.1895, +0.0537, +0.0167, +0.0602, -0.2372, -0.1231
+ ],
+ [
+ -0.2542, +0.8363, -0.2559, +0.0872, -0.1544, +0.1869, +0.4374,
+ -0.4973, +0.3678, -0.8425, -0.9891, +0.1042, +0.1624, -0.0964,
+ -0.1170, +0.2177, +0.1344, -0.3417, +0.5302, -0.3181, -0.8319,
+ -0.0489, -0.3692, +0.3340, -0.1902, -0.0889, -0.0784, -0.2664,
+ -1.1404, +0.2895, +0.0599, +0.0680, +0.4447, -0.1955, -0.2036,
+ +0.1605, -0.4091, +0.3005, +0.4971, +0.0056, -1.0584, -0.9754,
+ +0.4259, -0.4642, +0.3212, -1.0444, -0.4395, +0.1104, -0.2354,
+ -0.2754, -0.1138, -0.1852, +0.5298, -0.1715, -0.6177, -0.5564,
+ -0.5845, -0.9398, -0.5432, -0.4941, -0.5598, -0.2745, -0.7410, +0.0811
+ ],
+ [
+ +0.3484, +0.2363, -0.2313, +0.2903, +0.0599, +0.1981, +0.0264,
+ +0.0365, -0.6788, +0.5058, +0.5024, -0.1606, -0.1466, +0.0896,
+ -0.1695, -1.3626, +0.2203, -0.0972, -0.0547, -0.2063, +0.3971,
+ -0.3022, -0.0741, +0.4433, +0.0614, +0.0450, -0.2246, -0.3360,
+ -0.5529, +0.0350, -0.2026, -0.1587, -0.1705, +0.0967, -0.3402,
+ +0.2256, +0.0723, +0.2559, +0.2409, +0.0809, +0.2522, +0.1735,
+ +0.2135, -1.4875, -0.6041, +0.3822, -0.0542, -0.7500, +0.2439,
+ +0.2342, -0.2002, +0.2322, -0.7495, +0.1338, +0.0136, -0.5508,
+ +0.0944, +0.1229, -0.3225, +0.2776, -0.0289, +0.0075, +0.1089, +0.4093
+ ],
+ [
+ -0.4983, -0.0860, -0.6441, +0.0981, -0.1997, -0.1528, -0.3994,
+ -0.0600, -0.1746, -0.2651, -0.2522, +0.0370, -0.0651, -0.1543,
+ -0.0061, -0.1030, -0.8072, -0.5816, -0.1532, -0.4045, +0.0006,
+ +0.2646, +0.4261, +0.3321, +0.1915, -0.0374, -0.2416, +0.2430,
+ +0.2274, +0.1678, -0.1648, +0.5931, -0.3600, -0.0454, -0.2038,
+ +0.3763, +0.1858, -0.1298, -0.5252, +0.4314, +0.3626, -0.6726,
+ -0.1011, +0.0262, -0.1636, +0.1911, -0.8712, +0.5409, +0.0053,
+ +0.4764, -0.5827, +0.2690, +0.1905, -0.2930, -0.5309, +0.0933,
+ +0.6593, +0.0569, +0.1535, -0.0866, -0.2559, -0.1172, -0.7115, -0.0318
+ ],
+ [
+ -0.3941, +0.2379, -0.7244, -0.5779, -0.1544, +0.0214, +0.1138,
+ -0.0033, +0.2314, -0.5746, +0.1439, -0.2131, -0.3561, -0.9263,
+ -0.4184, -0.0513, +0.5047, -0.0148, +0.2949, -0.4070, +0.2619,
+ +0.0486, -0.9044, -0.0877, +0.1956, -0.2011, -0.4901, +0.6367,
+ -0.1576, -0.2315, +0.0778, -0.3715, +0.2394, -0.0715, -0.0091,
+ +0.3945, +0.1454, +0.2826, +0.2854, +0.0383, -0.7265, -0.4513,
+ -0.0195, +0.1877, +0.1825, -0.1004, +0.0741, -0.5238, -0.7622,
+ +0.4092, +0.4336, +0.1936, +0.3382, +0.3516, +0.2307, -1.4502,
+ +0.5835, -0.5750, -0.7338, +0.2978, -0.5406, +0.0339, -0.3202, +0.2325
+ ],
+ [
+ -0.0698, -0.8776, -0.9628, -0.2211, +0.0842, +0.2107, +0.0941,
+ -0.2500, -0.3662, +0.0578, -0.4750, -0.2181, -0.1686, -0.2689,
+ +0.1411, -0.8256, +0.3186, -0.3517, -0.4490, +0.0117, +0.2536,
+ -0.0792, +0.0725, +0.0385, +0.2386, +0.0666, -0.2312, +0.0256,
+ +0.1604, -0.0002, -0.0714, -0.6004, -0.1841, -1.4967, -0.5932,
+ +0.2548, -1.1410, -0.4043, -0.5033, -0.2187, -0.7987, +0.5275,
+ +0.0285, -0.8600, -0.2614, +0.0639, +0.3257, +0.4107, +0.2087,
+ -0.1072, -0.1157, +0.0467, -0.6435, -1.0427, -0.5286, +0.0459,
+ +0.1097, -0.2149, +0.0394, -0.3587, +0.1313, -0.6886, -0.1345, -0.5884
+ ],
+ [
+ +0.5300, -0.3907, -0.0105, -0.7121, -0.3486, +0.0401, +0.2562,
+ +0.3037, +0.2092, -0.0210, +0.3676, -0.0227, -0.1761, -0.1304,
+ +0.0840, -0.1310, +0.2111, +0.0926, -0.2739, -0.3635, -0.5617,
+ -0.1553, +0.0314, -0.4018, +0.4185, +0.0401, -0.1099, +0.2949,
+ +0.2019, -0.1762, -0.3477, +0.3448, +0.3568, +0.0361, +0.3788,
+ -0.1996, +0.1723, -0.1428, +0.0066, +0.3473, -0.3308, +0.4851,
+ +0.1993, +0.2379, -0.1148, -0.1366, +0.1673, +0.0433, +0.4188,
+ +0.1589, +0.1478, -0.2602, -0.3324, +0.4604, -0.4275, -0.1584,
+ +0.1039, +0.1074, -0.4238, +0.7423, -0.3097, +0.4578, +0.0754, -0.2779
+ ],
+ [
+ +0.1529, -0.1575, +0.0819, +0.0579, +0.4000, -0.2372, +0.2025,
+ +0.3456, +0.4460, +0.6892, -0.3688, +0.0596, +0.7114, +0.0582,
+ +0.2526, +0.0559, -0.3033, -0.2083, -0.2725, +0.2148, +0.6348,
+ -0.0939, -0.3589, +0.3578, -0.0897, -0.4104, -0.2510, -0.1750,
+ -0.0342, +0.2579, -0.2709, +0.1463, -0.2980, +0.6216, -0.3951,
+ +0.2358, +0.5241, -0.1989, +0.0439, +0.2978, +0.2848, +0.4379,
+ -0.1006, +0.4004, -1.3318, +0.0721, -0.7419, -0.4410, +0.1182,
+ -0.1377, -0.3649, +0.3684, -0.1349, -0.3452, +0.1427, -0.3848,
+ -0.1854, -0.2795, -0.0527, -0.1123, -0.0352, -0.5523, -0.0433, +0.5344
+ ],
+ [
+ -0.5747, +0.6322, -0.8440, -0.1528, -0.1161, +0.0448, -0.2353,
+ +0.6576, +0.3179, +0.1904, -0.5284, +0.1620, -0.6215, -0.2991,
+ +0.1852, +0.0115, -0.2674, -0.6372, +0.3602, -0.1317, +0.0330,
+ +0.0931, -0.0091, -0.2444, -0.1673, +0.1395, -0.2460, +0.0833,
+ -0.0209, -0.5390, -0.1847, -0.3628, +0.1574, -0.2920, -0.2394,
+ +0.4293, -0.0784, +0.5356, +0.2715, -0.2624, -0.5728, -1.0559,
+ -0.2006, +0.4380, +0.2419, -0.1679, +0.5417, +0.1381, -0.2034,
+ -0.0121, +0.3109, +0.4409, +0.6114, -0.1056, -0.5598, -0.3813,
+ -0.1363, +0.0551, +0.4501, -0.1133, +0.0976, +0.4507, +0.5136, -0.4507
+ ],
+ [
+ -0.9244, -0.6286, -0.3487, +0.3031, +0.5490, -0.0417, +0.1368,
+ +0.0454, +0.1623, -0.2627, +0.1115, +0.2481, +0.1029, -0.8995,
+ -0.2601, +0.0153, -0.1716, +0.2178, +0.1816, +0.4099, +0.3247,
+ -0.5553, -0.6924, -0.0171, +0.0062, -0.1994, -0.2239, -0.0970,
+ +0.4365, -0.2650, +0.0827, -0.5745, -0.1020, +0.0077, -0.2992,
+ -0.2860, -0.3540, +0.1319, -0.2205, -0.1654, -0.6664, +0.3699,
+ +0.5765, +0.4030, -0.1225, -0.0918, +0.0005, +0.2558, -0.2505,
+ +0.2503, -0.3338, -0.0020, +0.1167, -0.9499, -0.1115, +0.1646,
+ +0.2288, -0.6132, -0.0171, -0.6352, +0.3016, -0.8156, -0.0234, -0.1960
+ ],
+ [
+ -0.1446, -0.0614, -0.5054, +0.0903, -0.6342, -0.3637, -0.4531,
+ +0.3534, -0.3720, +0.1497, -0.0799, -0.4266, -0.4212, -0.0637,
+ +0.2497, -0.2035, +0.0224, -0.2292, -0.4062, -0.1081, -0.8317,
+ +0.3876, -0.1462, +0.3375, -0.2768, +0.2942, -0.0415, -0.0010,
+ +0.1652, +0.3646, -0.4710, -0.3447, -0.3278, +0.2597, -0.1056,
+ -0.2106, +0.0542, -0.0294, +0.2012, +0.2639, -0.1646, -0.0958,
+ +0.7079, +0.1167, +0.3802, -0.3459, -0.1004, +0.3548, +0.3814,
+ +0.1147, -0.0515, +0.0656, +0.0187, +0.4013, -0.4644, +0.3470,
+ +0.0240, +0.0587, +0.3188, +0.3168, +0.0652, -0.1883, -0.1926, -0.2713
+ ],
+ [
+ -0.5894, -0.5153, -1.0262, -0.2579, -0.1002, +0.0868, -0.2158,
+ -0.5245, +0.1173, -0.5855, +0.1135, +0.1471, -0.1395, +0.0561,
+ -0.7122, -0.1065, -0.0323, -0.7822, -0.1447, -0.0733, +0.2652,
+ +0.0712, +0.3987, +0.2479, -0.0321, +0.0163, -0.4509, +0.5805,
+ +0.4090, +0.0009, +0.0661, -0.2575, +0.4356, +0.1165, -0.4437,
+ -0.0218, -0.0202, -0.0969, -0.0273, -0.3226, -0.0146, -1.0215,
+ -0.2444, -0.3282, +0.1432, +0.1515, -0.0272, -0.5475, -0.0752,
+ -0.0464, +0.3280, +0.2803, +0.4469, -0.1728, +0.1299, -0.3028,
+ +0.1950, -0.1140, +0.1167, -0.7595, +0.0355, -0.3649, +0.0557, +0.3914
+ ],
+ [
+ -0.0846, -0.1685, +0.2284, -0.2308, -0.2823, -0.1744, -0.4141,
+ +0.2608, -0.0387, -0.3320, -0.1776, +0.1127, +0.2196, +0.2047,
+ +0.1583, -0.4179, -1.1789, -0.2604, +0.2216, -0.2943, -0.1386,
+ +0.2381, +0.2102, -0.9876, +0.2734, +0.2302, +0.0747, -0.0731,
+ +0.3148, -0.7059, -0.0752, +0.2228, +0.2243, -0.0902, +0.1300,
+ +0.1532, -0.0828, -0.4113, -0.3630, +0.1029, +0.1319, +0.2420,
+ +0.0834, +0.2050, -0.1922, -0.2458, -0.1244, +0.1475, +0.0999,
+ +0.3175, +0.0888, +0.5254, +0.1428, +0.1467, -0.4229, -0.7336,
+ -0.1727, -0.0493, +0.3679, +0.1458, -0.1008, -0.0171, -0.2563, -0.1038
+ ],
+ [
+ +0.1402, -0.1713, +0.0748, -0.1560, -0.2416, +0.4341, +0.6550,
+ -0.3423, +0.0628, +0.1346, +0.4624, +0.2883, -0.0514, -0.4130,
+ -0.5822, +0.5217, -0.1437, +0.3471, +0.2181, -0.2431, -0.5769,
+ -0.0424, +0.2626, +0.4983, +0.2075, -0.1028, +0.0161, +0.1407,
+ -0.0833, +0.2390, +0.0417, +0.2823, +0.5103, -0.6378, -0.0536,
+ -0.0393, -0.0651, +0.2310, +0.1614, +0.3542, -0.9074, -0.6099,
+ -0.6084, -0.2096, +0.3871, -0.4172, -0.3355, -0.0663, +0.0204,
+ -0.2276, +0.0557, -0.4072, -0.0672, -0.5691, -0.0667, +0.1840,
+ +0.0315, -0.5422, +0.2810, -0.6101, +0.0672, +0.2098, +0.2070, -0.0607
+ ],
+ [
+ +0.1965, -0.2065, +0.3365, -0.2497, -0.0590, +0.0630, +0.3852,
+ -0.0385, -0.2316, +0.1742, +0.0175, +0.3616, +0.0664, +0.0959,
+ -0.4834, -0.0115, -0.3736, -0.6134, +0.4486, -0.6497, -0.4091,
+ -0.2319, +0.4347, -0.1304, -0.3359, -0.1652, +0.2525, +0.0212,
+ +0.0533, +0.2644, -0.4857, +0.0716, +0.1842, -1.0370, +0.2084,
+ +0.3405, -0.5086, +0.0427, -0.5776, -0.2903, -0.2391, -0.2570,
+ -0.3302, -0.4522, +0.1341, +0.1451, -0.6259, +0.3231, +0.1005,
+ -0.7788, +0.2834, +0.4262, -0.6278, -0.2713, -0.7403, +0.0574,
+ +0.0764, -0.7498, -0.2167, -0.2668, +0.2389, +0.3858, +0.4294, -0.1692
+ ],
+ [
+ -0.6005, -0.3342, -0.0341, -0.0976, -0.1294, -0.0055, +0.1565,
+ +0.1378, -0.4799, -0.0769, +0.0385, +0.4254, +0.0979, +0.2879,
+ -0.3212, +0.7339, -0.2134, -0.3846, -0.1997, +0.0673, +0.5370,
+ -0.2301, +0.1499, +0.2798, +0.3384, +0.1293, -0.2867, -0.4863,
+ +0.3093, +0.1156, -0.3691, -0.0511, -0.6717, +0.2799, +0.1184,
+ +0.7869, +0.0988, +0.2327, -0.3219, -0.3663, -0.1863, -0.2751,
+ -0.6367, +0.1387, -1.2061, +0.5445, -0.2497, -0.6187, -0.3262,
+ +0.2336, +0.0923, +0.4471, +0.4191, +0.5987, +0.5211, -0.2479,
+ -0.0383, -0.0975, +0.0296, -0.6031, +0.2865, -0.6888, -0.4697, +0.3444
+ ],
+ [
+ -0.8969, -0.3619, -0.2047, -0.1343, -0.3042, -0.1042, -0.0415,
+ -0.1624, -0.2147, -0.1016, -0.7889, +0.3418, +0.0868, -0.4342,
+ -0.2084, +0.3734, +0.4318, -0.1115, +0.2490, +0.4559, -0.2937,
+ -0.5159, -1.1121, -0.0804, +0.1388, -0.4097, +0.1953, -0.0861,
+ +0.0755, +0.0578, -0.0600, -0.0519, +0.2378, -0.7286, -0.8340,
+ -0.9214, -0.1790, -1.2709, -0.5294, +0.0270, -0.4837, +0.1236,
+ +0.3863, -0.3191, +0.1822, -0.1040, -0.3779, +0.1810, -0.0920,
+ -0.1269, +0.5072, -0.3267, +0.3822, -1.1616, +0.2350, +0.4796,
+ +0.1842, -0.1957, +0.0444, -0.6974, -0.4900, -0.4579, -0.1375, -0.5128
+ ],
+ [
+ +0.4125, +0.1846, -0.2687, +0.4047, +0.2415, -0.3568, -0.5222,
+ +0.0550, -0.2090, -0.3538, +0.4196, -0.2383, -0.2984, +0.0796,
+ -0.2891, -0.0922, -0.4071, -0.5568, -0.2258, -0.0513, +0.3008,
+ -0.4999, -0.0981, +0.2177, +0.4061, +0.3386, +0.0729, +0.2200,
+ +0.0887, +0.2734, +0.1983, -0.3363, -0.0570, +0.0283, +0.4889,
+ +0.5389, -0.4052, -0.5635, +0.3627, -0.2224, -0.0141, -0.0919,
+ +0.2747, -0.1352, -0.0483, +0.2405, -0.1205, +0.1157, +0.1593,
+ -0.6906, +0.3747, +0.0316, -0.3510, -0.0224, -0.1504, +0.2385,
+ +0.2176, -0.6219, +0.0703, +0.6161, +0.1639, -0.3518, +0.0277, +0.5706
+ ],
+ [
+ +0.2870, -0.7338, -0.1045, -0.0942, +0.0845, +0.3805, +0.0079,
+ -0.7205, +0.0955, -0.4537, +0.0731, +0.1386, +0.2017, +0.2059,
+ -0.3269, -0.5290, -0.8150, -0.6405, +0.1613, -0.1068, +0.1682,
+ +0.0145, +0.0655, -0.0025, -0.2245, +0.4070, +0.1686, -0.8228,
+ +0.2429, -0.0431, +0.0035, +0.0513, -0.0154, +0.1894, +0.2753,
+ +0.2020, -0.0720, -0.1562, -0.2747, -0.1583, -0.9408, -0.8700,
+ -0.2165, +0.0506, -1.3863, -0.0658, -0.3209, -0.3702, -0.6101,
+ -0.0353, +0.1048, +0.1970, +0.2671, -0.3384, +0.1256, -0.2245,
+ -0.4526, -0.0493, -0.3827, +0.0560, +0.0338, -0.1525, -0.2141, -0.0425
+ ],
+ [
+ -0.1422, +0.1337, -0.9957, -0.5735, -0.2927, -0.4815, +0.4319,
+ +0.0342, +0.0668, +0.3405, -0.0740, -0.1619, +0.5172, -0.4340,
+ +0.1856, +0.2209, -0.4643, +0.6153, +0.4239, -0.9462, +0.2372,
+ +0.1935, +0.0449, +0.0913, +0.5925, +0.0728, -0.3116, +0.3045,
+ -0.1049, -0.3677, -0.2878, -0.2252, +0.1939, -1.5561, +0.0153,
+ -0.1803, -0.6259, -0.3834, -0.6172, -0.0133, -0.2826, -0.2731,
+ +0.3053, +0.0552, -0.0550, -0.5861, -0.2372, +0.1009, +0.2500,
+ -0.4699, +0.0561, -0.2214, +0.3366, +0.1667, -0.0716, -0.0938,
+ +0.0177, -0.9000, +0.1185, -0.3892, +0.1251, -0.1854, +0.1612, -0.2577
+ ],
+ [
+ +0.4538, -0.9701, +0.1504, +0.4843, -0.9331, +0.1328, -0.3539,
+ -0.5484, +0.2910, -0.1758, +0.1974, -0.1809, -0.3994, -1.0207,
+ +0.1626, -0.3537, +0.3522, +0.3263, -1.0539, +0.1426, -0.8538,
+ -0.0698, +0.1850, +0.7717, +0.4812, -0.0657, +0.8718, -0.6112,
+ +0.0877, -0.4540, +0.5209, +0.2496, -0.1358, -0.2268, +0.1259,
+ -0.3139, -0.2353, -1.0745, +0.4902, +0.3386, -0.7974, -1.2774,
+ +0.0222, -0.0120, +0.3418, +0.0277, -0.1518, +0.1329, -0.2840,
+ -0.6863, -0.1258, +0.0503, +0.6224, -0.9175, -0.4380, +0.0616,
+ -0.2948, -0.1367, -0.7437, -0.5496, -0.0115, -0.2441, -1.3192, +0.0898
+ ],
+ [
+ -0.8492, +0.2324, -1.0937, -0.0072, -0.5556, +0.1550, -0.0198,
+ +0.2518, -0.2527, -0.4283, +0.0591, -0.5192, +0.1214, -0.0950,
+ +0.0202, +0.4282, +0.2584, -0.7877, -0.8089, +0.0275, -0.5099,
+ +0.3571, +0.0930, +0.0660, -0.0577, -0.3545, +0.0622, +0.5885,
+ +0.3251, -0.6699, +0.4005, +0.1462, -0.1288, -0.8976, -0.5042,
+ +0.1200, +0.1997, -0.0740, +0.0969, +0.2668, -0.6573, -0.0003,
+ +0.3727, +0.0478, +0.1457, -0.9810, -0.1764, +0.1550, -0.2832,
+ +0.4197, -0.4164, -0.1324, +0.0982, +0.3429, +0.1463, +0.0178,
+ +0.2783, +0.1799, +0.4229, +0.0707, -1.0676, +0.0656, -0.2406, +0.1123
+ ],
+ [
+ -0.2739, +0.4278, +0.5050, +0.4886, +0.0866, -0.6754, -0.2957,
+ -0.7517, -0.1715, -0.0754, -0.0733, +0.0049, +0.4403, -0.5811,
+ +0.1439, -0.1410, -0.4331, +0.0514, -0.1729, +0.4406, +0.0236,
+ +0.1144, +0.3210, -0.0241, -0.1087, -0.7359, +0.4433, -0.1967,
+ +0.4850, -0.3577, -0.2777, -0.1381, +0.0488, +0.4510, +0.0785,
+ -0.1526, -0.0759, +0.3004, -0.0124, -0.3421, -0.3625, -0.2688,
+ -0.6088, +0.1834, -0.1742, -0.3992, -0.0729, -0.0954, +0.1403,
+ +0.2244, -1.0269, +0.0389, +0.0357, +0.2483, -0.0966, -0.1649,
+ +0.0946, +0.0789, -0.8485, +0.8510, -0.2052, +0.0063, +0.3289, -0.2707
+ ],
+ [
+ -0.0008, -0.1527, +0.1871, +0.0008, -0.5502, +0.1705, -0.0862,
+ -1.7449, -0.4099, -1.2881, -0.2889, -0.6813, -0.1696, -0.3554,
+ -0.0171, -0.1756, +0.0394, -0.0584, +0.0541, +0.2665, +0.2842,
+ +0.7106, -0.1510, +0.1608, -0.0213, +0.4420, -0.5489, -0.2275,
+ +0.2123, +0.2702, +0.1270, +0.1165, +0.0307, -0.9451, +0.5018,
+ -0.7310, +0.4341, -0.0568, -0.1530, +0.3782, -0.8706, -0.1489,
+ -0.3021, -0.3795, +0.0077, +0.3951, +0.0642, +0.0071, +0.0698,
+ -0.6238, -0.0427, +0.0675, +0.0150, -0.3453, -0.6300, +0.1152,
+ +0.0628, -0.1176, +0.1059, -0.3573, -0.0405, -0.4776, -0.3119, -0.1392
+ ],
+ [
+ -0.1531, +0.2170, +0.1452, +0.3291, -0.1676, +0.4282, +0.6817,
+ -1.1171, -0.0246, -0.1068, -0.1326, +0.0996, +0.5856, +0.0621,
+ -0.4004, -1.4584, +0.1328, +0.2980, +0.6669, +0.2422, -0.5000,
+ -0.0695, +0.0159, -0.5761, -0.2003, +0.1373, -0.1083, -0.7715,
+ -0.4855, +0.1736, +0.1171, +0.1248, -0.9882, -0.0027, +0.1430,
+ +0.2150, +0.0139, +0.3390, +0.2071, +0.0626, -0.3002, -0.4146,
+ -0.2301, +0.1151, -0.3078, -0.7258, -0.1942, +0.0928, +0.4019,
+ -0.5398, -0.1712, +0.3604, -0.0307, +0.5086, +0.1574, +0.1295,
+ -0.1964, +0.2544, -0.4195, -0.1106, +0.1878, -0.7051, -0.3494, -0.2784
+ ],
+ [
+ -0.1671, +0.2359, -0.3504, -0.0875, -0.0657, -0.0707, -0.2190,
+ +0.3783, +0.0052, +0.3745, -0.5688, +0.2605, -0.3190, +0.5080,
+ +0.4697, -0.0987, +0.2703, +0.1677, -0.6767, -0.3178, +0.4836,
+ +0.5635, -0.7103, -0.0746, +0.1034, +0.2430, -0.4251, -0.1090,
+ -0.5547, +0.2012, -0.3403, -0.3141, +0.1168, -0.2846, -0.3791,
+ -0.6774, -0.1252, -0.2180, -0.0656, +0.0353, -0.7226, +0.2728,
+ -0.1778, -0.3260, +0.3339, +0.0653, +0.3684, -0.1632, +0.2573,
+ -0.2883, +0.0009, +0.1928, -1.0397, -0.7210, -0.8038, -0.2165,
+ +0.1618, -0.0957, +0.2977, +0.2513, +0.0480, -0.4479, -0.0804, -0.1824
+ ],
+ [
+ +0.3119, +0.0566, +0.0424, -0.4121, +0.2908, -0.0512, +0.0101,
+ -0.2033, -0.0291, -0.4058, +0.1809, -0.3684, -0.1681, +0.3278,
+ -0.1494, +0.3727, -0.5309, +0.2718, +0.3946, -0.6974, -0.1518,
+ -1.1048, +0.0306, +0.2203, +0.1070, +0.4206, +0.2177, -0.0350,
+ -0.2504, -0.1273, +0.2011, -0.3807, -0.0330, -0.0830, +0.0246,
+ +0.2361, +0.2504, -0.0618, -0.4662, +0.1870, -0.0266, -0.7132,
+ -0.1990, +0.2201, +0.2257, +0.2032, +0.5247, +0.0135, -0.5164,
+ -0.4449, -0.1256, -0.2228, -0.3297, -0.0180, -0.4429, -1.1518,
+ -0.6446, +0.0484, -0.0231, -0.1286, +0.2235, +0.4159, -0.4084, +0.1132
+ ],
+ [
+ +0.2173, -0.4447, +0.0845, -0.0702, +0.1410, +0.0165, -0.2067,
+ -0.0764, +0.2809, +0.1371, -0.6168, +0.0406, -0.4437, -0.1373,
+ -0.0030, -0.3000, -0.3696, -0.3191, -0.1415, +0.2761, -0.0324,
+ +0.0190, -0.1383, +0.0778, -0.5184, +0.1510, -0.0283, -0.6965,
+ +0.3637, -0.2210, -0.0611, -0.0446, +0.1991, -0.0131, +0.3577,
+ -0.5313, +0.0258, -0.5449, -0.6727, -0.1732, +0.1289, -0.2922,
+ -0.2036, -0.2062, -0.5262, +0.2311, -0.5273, -0.3758, +0.0734,
+ +0.2520, +0.5800, +0.1337, -0.0203, +0.2392, +0.4818, +0.1183,
+ -0.2960, -1.3139, -0.3598, -0.4217, +0.5906, +0.3120, +0.0842, -0.0189
+ ],
+ [
+ -0.2034, -0.2470, +0.0815, +0.3712, -0.2452, -0.2641, -0.4384,
+ -0.0659, -0.1397, -0.0294, +0.5793, +0.4600, -0.6904, +0.1172,
+ -0.3046, +0.3242, +0.0302, -1.3304, +0.3182, -0.1053, +0.3679,
+ -0.3855, -0.2545, -0.2798, -0.2702, +0.0962, -0.3428, +0.1185,
+ +0.0799, -0.1985, -0.7122, -0.1967, -0.1748, +0.0686, +0.5070,
+ +0.2390, -0.3882, -0.1285, +0.1746, +0.0770, -0.7113, -0.3933,
+ +0.0402, -0.5497, +0.1689, -0.0035, -0.1905, -0.4365, +0.1926,
+ -0.0179, +0.2188, +0.1091, +0.2962, -0.0157, -0.1560, -0.1427,
+ -0.3535, +0.3942, -0.8826, -0.0166, +0.1164, -0.8110, +0.5112, -0.4452
+ ],
+ [
+ +0.1235, -0.1364, +0.0059, -0.1658, +0.1140, +0.2574, +0.0619,
+ -0.0737, +0.2568, -0.1101, -0.0517, +0.0775, +0.3710, -0.3755,
+ -0.5272, -0.1628, +0.0063, -0.2183, +0.3528, +0.3519, -0.0413,
+ -0.1653, -0.1039, +0.1532, -0.0121, +0.0628, +0.1186, -0.0342,
+ +0.6432, +0.2785, +0.1194, -0.1340, -0.0801, +0.5283, +0.0979,
+ +0.1328, -0.0234, +0.0730, -0.2662, +0.3805, +0.2164, -0.5923,
+ +0.2952, -0.1686, +0.0913, +0.4924, -0.6039, -0.2342, +0.0168,
+ -0.4053, -0.1432, +0.1093, -0.5354, -0.1532, -0.0843, -0.2759,
+ -0.5059, -0.5240, +0.2169, +0.1137, +0.1778, -0.8917, -0.0479, -0.4231
+ ],
+ [
+ -0.0225, +0.2392, +0.2313, +0.2092, -0.2090, +0.5269, -0.2119,
+ -0.6104, +0.2067, +0.1138, -0.0775, +0.2780, -0.3904, +0.2525,
+ -0.5334, -0.0438, +0.3420, -0.1981, +0.3290, -0.3555, -0.2135,
+ -0.1317, +0.2700, -0.0619, -0.6285, +0.2862, +0.3542, -0.6501,
+ +0.2822, +0.1852, +0.2532, -0.0958, +0.2226, +0.0876, +0.0229,
+ +0.0259, -0.1851, -0.2623, +0.0520, +0.1087, -0.1129, +0.4673,
+ +0.0371, -0.5383, -0.2881, -0.3649, -0.2050, +0.0659, -0.1629,
+ -0.2505, +0.2957, +0.1168, +0.1865, +0.3650, -0.2477, +0.2141,
+ +0.1328, -0.3441, -0.4943, -0.1007, +0.2719, -0.2334, -0.0244, +0.2138
+ ],
+ [
+ +0.0426, +0.2374, -0.6527, +0.2165, -0.0192, -0.2015, +0.1225,
+ +0.4667, -0.2282, -0.1058, +0.1764, +0.3174, +0.1419, -0.2757,
+ +0.1073, +0.0635, +0.0248, -0.3573, -0.4414, -0.0629, -0.3135,
+ -1.3118, +0.1522, -0.0582, +0.0370, +0.4431, +0.3450, -0.1012,
+ -0.5598, +0.1954, -0.0399, +0.1511, +0.3362, +0.0511, +0.0086,
+ +0.6763, -0.3848, +0.3133, -0.4143, +0.0054, -0.2434, -0.0314,
+ +0.4777, -0.2695, +0.1945, -0.4941, +0.2321, -0.2950, -0.2499,
+ -0.7564, +0.2191, +0.0811, -0.6030, +0.0595, +0.2227, +0.1896,
+ +0.1723, +0.0892, -0.2741, +0.4445, +0.3701, -0.4163, -0.3526, +0.0082
+ ],
+ [
+ +0.2931, -0.0836, +0.1128, -0.2699, -0.1293, -0.9413, -0.3849,
+ -0.0243, -0.1199, -0.0149, -0.1323, +0.1631, -0.3434, -0.7035,
+ -0.4271, -0.0106, +0.5124, +0.3303, -0.4026, +0.1950, -0.1408,
+ -0.3412, +0.0869, -0.3608, -0.4225, +0.1374, +0.1295, +0.2215,
+ +0.6199, +0.5064, -0.0815, +0.1034, -0.2661, +0.2258, -0.0738,
+ +0.1143, +0.2495, +0.2205, +0.1754, -0.4842, -0.1246, -0.2890,
+ +0.3604, -0.9065, -0.3236, -0.1017, +0.2657, +0.2487, +0.1089,
+ -0.1155, +0.3416, +0.0721, -0.0109, -0.0288, -0.1186, +0.2537,
+ +0.2910, -0.2570, -0.4873, -0.0378, +0.4349, +0.1140, -0.8302, +0.1782
+ ],
+ [
+ +0.1030, +0.1304, -0.0909, -0.2364, -0.2500, -0.3028, -0.0546,
+ -0.6416, -0.1898, -0.3917, -0.2705, -0.3312, +0.3570, -0.2017,
+ -0.0537, -0.6308, +0.0019, -0.1418, +0.2843, -0.0999, -0.5335,
+ +0.1763, -0.3687, +0.1857, +0.0332, +0.4558, +0.2883, -0.0218,
+ -0.2059, +0.4931, +0.4608, +0.0538, -0.5530, -0.1249, +0.1417,
+ -0.6702, -0.2335, -0.7719, +0.2778, +0.0543, -0.0728, +0.1623,
+ +0.4363, -0.3137, -1.1796, +0.3349, -0.1091, -0.1050, -1.2196,
+ +0.1470, -0.3972, +0.5019, +0.1066, +0.4256, -0.1710, -1.0880,
+ -0.0445, +0.2020, +0.0078, +0.2894, -0.1972, -0.4168, -0.5523, +0.0526
+ ],
+ [
+ -0.1724, -0.1460, -0.4037, +0.0507, +0.3517, -0.1470, +0.2463,
+ -0.9503, -0.5646, +0.2897, -0.3478, +0.0671, -0.0199, -0.2202,
+ -0.1675, -0.9212, +0.4622, +0.1569, -0.0368, +0.1945, -0.0634,
+ -0.9858, +0.0529, -0.0555, +0.1661, -0.0465, -0.0869, -0.0138,
+ +0.0404, -0.7938, +0.0083, +0.3436, -1.1259, +0.1878, -0.5468,
+ +0.0276, -0.1077, +0.5194, -0.1782, +0.1574, +0.3799, +0.0166,
+ +0.1506, -0.2308, -0.5062, -0.6700, +0.0766, -0.2727, -0.5081,
+ +0.0889, +0.0337, -0.0512, +0.2099, -0.3992, +0.2682, -0.1567,
+ +0.1432, +0.1219, -0.1049, +0.2016, -0.2421, +0.3822, -0.3316, -0.0221
+ ],
+ [
+ -0.0998, +0.3567, -0.9238, +0.2816, -0.0369, +0.3637, -0.1214,
+ -0.4277, -0.4980, -0.0801, +0.1680, -0.4083, -0.4140, -0.1989,
+ +0.1607, -0.4560, +0.1918, -0.2292, -0.0623, -0.3424, -0.1217,
+ -0.0239, +0.3148, +0.0673, +0.4032, +0.2976, -0.1841, +0.4275,
+ -0.3250, -0.3160, +0.0484, +0.3713, +0.3938, +0.0258, -0.2029,
+ -0.0053, -0.4931, +0.2625, -0.3302, -0.0181, -0.8182, -0.2774,
+ -0.1506, -1.1460, -0.4011, -0.2439, +0.0196, +0.2232, +0.8174,
+ -0.0484, +0.1209, -0.0140, -0.3340, +0.3268, +0.0327, -0.1059,
+ +0.1514, +0.3105, -0.0121, -0.3407, -0.1831, -0.1004, +0.3739, +0.1763
+ ],
+ [
+ +0.4708, -0.0521, +0.0590, -0.1178, +0.0997, +0.5031, -0.3283,
+ -0.4129, -0.0462, -0.9110, -0.1623, -0.7761, -0.0343, -0.1479,
+ -0.2679, -1.0075, +0.4896, -0.2684, +0.1089, -0.5597, -0.1109,
+ -0.1651, +0.4689, +0.6028, -0.6288, -0.0128, -0.3020, +0.0826,
+ -0.0618, +0.5606, +0.6067, -0.0180, +0.4340, -0.4646, +0.2367,
+ -0.1164, -0.5773, -0.0936, -1.4304, -0.2006, +0.2534, +0.1214,
+ +0.4082, +0.4421, -0.0296, +0.7033, +0.4593, +0.0166, -0.3860,
+ -0.4448, +0.0253, +0.3424, +0.1747, +0.4142, -0.5072, +0.0198,
+ -0.2323, +0.2584, -0.5340, -0.2674, +0.3111, +0.0950, -1.2430, -0.3871
+ ],
+ [
+ -0.3554, -0.4261, -0.3969, +0.1330, +0.3218, -0.1343, +0.3053,
+ -0.5123, -0.0876, -0.1438, +0.1724, +0.4915, +0.3161, -0.6318,
+ +0.0695, -0.0161, -0.0747, -0.1576, +0.2199, +0.0535, +0.3710,
+ -0.1703, +0.0093, -0.2971, -0.3412, +0.0165, +0.1949, -0.2908,
+ +0.1133, -0.0025, -0.0251, -0.3991, -0.5825, +0.1080, -0.5219,
+ +0.3805, -0.0868, -0.0036, -0.4767, +0.3711, -0.0467, -0.3188,
+ +0.3101, -0.4350, -0.5693, +0.0831, -0.0943, +0.0603, -0.3070,
+ +0.1510, -0.3361, -0.3525, -0.0654, -0.2628, +0.0655, -0.3440,
+ +0.0953, -0.0180, -0.3156, -0.1640, -0.2534, +0.2776, -0.5039, +0.4039
+ ],
+ [
+ +0.1528, -0.4957, -0.3149, -0.6788, +0.5233, +0.3255, +0.7413,
+ +0.1437, +0.7073, -0.1607, -0.0156, +0.8259, -0.4460, -0.4434,
+ -0.0353, +0.1706, +0.0603, -0.2323, +0.3872, -0.2852, +0.1093,
+ +0.5235, -0.4943, -0.0429, +0.0298, +0.3845, -0.4493, -0.5962,
+ +0.2980, +0.1263, +0.4735, +0.3274, +0.2746, -0.2191, +0.0693,
+ -0.1408, +0.3724, -0.1717, -0.4673, +0.0807, -0.3967, -0.4441,
+ +0.1146, +0.3469, +0.0416, +0.4874, +0.2353, -0.2750, -0.2053,
+ +0.3934, +0.3132, +0.5396, +0.7412, -0.6986, +0.2424, -0.2640,
+ -0.4363, -1.1939, -0.1710, +0.2154, -0.1753, +0.0985, +0.2595, +0.2793
+ ],
+ [
+ -0.0573, +0.0183, -0.8290, -0.3792, -0.4697, +0.1927, +0.2986,
+ +0.0933, +0.6088, -0.0466, +0.0604, +0.2636, -0.2967, +0.7121,
+ -0.3530, +0.4662, -0.1525, -1.1248, +0.1679, +0.1166, -0.1709,
+ -0.0463, +0.2697, -0.1441, +0.1371, -0.8555, -0.7195, -0.0514,
+ -0.1252, -0.2504, -0.1861, -0.2676, +0.3947, +0.2097, +0.1032,
+ -0.1152, -0.6395, +0.0102, -0.3397, +0.9433, -1.0032, +0.3374,
+ +0.3034, -0.5279, +0.2076, -0.2374, -0.2158, +0.6702, +0.3128,
+ -0.0549, +0.0874, -0.4102, +0.1829, -0.4387, -0.5966, +0.2051,
+ +0.4078, +0.1916, -0.1082, -0.0840, +0.0112, +0.2095, +0.4739, +0.0592
+ ],
+ [
+ +0.0712, -0.1285, -0.3152, -0.2810, +0.1589, -0.5851, +0.2913,
+ +0.4122, +0.3443, +0.1250, +0.3089, -0.6933, -0.1485, -0.2361,
+ +0.0330, -0.0679, +0.5881, +0.0105, -0.6269, -0.3111, -0.0086,
+ +0.3774, +0.1192, +0.3908, +0.2166, +0.0512, +0.0148, +0.1214,
+ +0.0431, +0.3745, +0.1041, +0.1479, +0.0928, +0.2105, -0.2576,
+ +0.1054, +0.1603, -0.0741, -0.9277, +0.0946, -0.4804, -0.8540,
+ +0.2943, -0.2224, -0.3795, -0.2643, -0.3990, +0.1907, -0.0094,
+ +0.2209, -0.3091, -0.3027, -0.2061, -0.0633, +0.1596, -0.0254,
+ +0.0329, +0.1977, -0.0670, -0.0397, -0.2621, +0.1125, -0.3700, +0.0390
+ ],
+ [
+ +0.3480, -0.7664, -0.4568, +0.1871, +0.5560, -0.1744, +0.3469,
+ -0.2509, +0.2379, -0.0506, +0.2119, +0.3410, +0.2622, -0.6715,
+ +0.1367, -0.4652, -1.4492, +0.2345, -0.0107, +0.3638, +0.1392,
+ +0.1721, +0.1263, -0.4381, -0.1557, -0.0970, +0.4355, -0.3398,
+ +0.3974, +0.1136, -0.1181, -0.0664, -0.0990, +0.2637, +0.0006,
+ +0.1281, +0.0642, +0.4717, -0.3359, +0.0537, -0.0195, -0.3825,
+ +0.1724, +0.3125, -0.4619, -0.2560, -0.1729, +0.0146, -0.9450,
+ -0.0293, -0.1295, -0.1973, +0.3303, -0.4519, +0.3595, +0.2745,
+ +0.0131, +0.0422, -0.5244, +0.0894, +0.1912, -0.3745, +0.1748, +0.0928
+ ],
+ [
+ -0.1506, +0.2073, +0.2138, -0.2598, -1.1459, +0.2474, +0.2124,
+ +0.2297, +0.0995, +0.4783, +0.1605, -0.6660, -0.4947, -0.1636,
+ -1.4091, +0.2500, -0.1069, +0.0376, -0.2405, +0.1701, +0.1519,
+ -0.4186, +0.4935, -0.8247, +0.1552, +0.1344, -0.1138, -0.3214,
+ +0.1920, -0.6936, -0.3714, -0.1434, +0.1774, +0.1123, +0.1861,
+ +0.7214, -0.0433, -0.1770, +0.2506, -0.5951, -0.0325, -0.2234,
+ -0.4408, -0.5731, +0.4697, -0.0485, -0.2623, +0.3801, -0.2302,
+ -0.4792, -0.0723, -0.8690, +0.4120, +0.0801, -0.5035, +0.6318,
+ -0.4286, -1.7760, -0.1839, +0.1031, +0.0964, +0.2205, +0.1453, +0.1327
+ ],
+ [
+ +0.0565, +0.1102, +0.0555, -0.3907, +0.3093, +0.6011, -0.1821,
+ -0.8135, -0.3734, -0.4417, +0.3651, -0.3520, -0.6925, +0.0480,
+ +0.4059, -0.0637, +0.1310, +0.1907, +0.1613, -0.2027, +0.1738,
+ -0.4830, +0.4008, -0.2709, +0.0293, +0.2790, -0.2094, -0.3615,
+ +0.1121, -0.3976, +0.2432, +0.1350, -0.3801, +0.0290, -0.3612,
+ -0.1686, -0.2163, -0.2304, -0.6177, +0.3902, -0.3066, +0.2993,
+ +0.0292, +0.3404, -0.0150, -0.1280, -0.2364, +0.1865, +0.0298,
+ -0.2680, -0.1932, -0.1310, -0.2946, -0.9964, -0.4285, -0.4160,
+ -0.1354, +0.2941, +0.0927, -0.1026, -0.1780, +0.1622, +0.0649, -0.8204
+ ],
+ [
+ +0.1894, -0.0970, -0.2627, -0.2888, -0.1052, -0.0090, +0.1697,
+ +0.1585, +0.0807, +0.2906, -0.1213, -0.4320, -0.3194, +0.4379,
+ -0.3009, +0.2913, -0.0138, -0.2332, -0.2100, -0.0920, +0.0030,
+ -0.1944, -0.1362, -0.0683, +0.1916, +0.2277, +0.0020, +0.0376,
+ -0.2581, +0.0203, +0.0945, -0.0273, -0.1834, -0.1477, +0.3891,
+ -0.8760, -0.7327, -0.3924, -0.7739, -0.2062, -0.9386, +0.0510,
+ +0.1158, -0.5032, +0.0522, +0.0838, -0.2942, +0.0945, -0.2562,
+ -0.2678, +0.0716, +0.1929, -0.2012, -0.6123, -0.3913, +0.0878,
+ +0.4618, +0.3128, +0.2354, -0.1198, +0.2178, +0.4765, -0.2785, -0.1888
+ ],
+ [
+ -0.2206, +0.3318, +0.2938, +0.4148, -0.0502, +0.6339, +0.1075,
+ +0.0466, -0.0205, -0.0399, +0.1343, -0.1876, +0.1697, -0.1137,
+ -0.3068, -1.2581, -0.4032, -0.2526, -0.0501, -0.4212, +0.2251,
+ -0.1790, -0.4869, +0.6200, -0.5371, -0.5877, +0.0569, -0.3732,
+ +0.1879, -0.5597, +0.3479, -0.6712, +0.2906, -0.3752, -0.3008,
+ -0.0225, -0.0610, -0.1636, +0.4039, +0.1432, +0.2402, -0.0871,
+ +0.1529, +0.0566, +0.1538, +0.1572, +0.1036, -0.0355, -0.7213,
+ +0.2796, +0.1821, +0.1483, +0.2256, -0.2517, +0.2175, -1.6318,
+ -0.3699, +0.0168, +0.1499, -0.2434, +0.4927, +0.3871, +0.4436, +0.3241
+ ],
+ [
+ -0.3785, +0.3710, +0.5153, -0.2213, +0.1006, +0.0343, -0.3430,
+ -1.3048, +0.2934, -1.1390, +0.0764, -0.4633, -0.3503, -0.1963,
+ -0.6778, +0.1066, +0.3581, -0.4359, +0.2323, -0.0946, +0.3556,
+ +0.0036, +0.1852, -0.4234, -0.7639, +0.1503, +0.5572, -0.0908,
+ -0.0304, +0.3589, +0.4023, +0.2161, -0.3031, -0.5656, +0.4415,
+ -0.2330, -0.2778, -0.1847, -0.4498, -0.1618, +0.0821, -0.0945,
+ -0.2184, -0.4628, +0.4103, +0.3438, -0.2311, -0.2477, +0.3549,
+ +0.3910, +0.1714, +0.2460, -0.5765, -0.3045, -0.0702, -0.1728,
+ -0.4134, -0.1338, -1.0295, +0.2805, -0.6990, +0.7314, +0.2259, -0.0369
+ ],
+ [
+ -0.7765, -0.8213, +0.0711, +0.2292, +0.2640, -0.1111, +0.0706,
+ -0.9447, -0.0118, +0.0427, +0.2097, -0.0662, -0.2773, -0.4894,
+ -0.7694, -0.3649, +0.1166, -0.3336, +0.3578, +0.0796, -0.1630,
+ -0.1352, -0.0720, +0.1224, -0.3877, +0.1955, -0.1440, -0.0612,
+ +0.1912, -0.1973, -0.0973, -0.0560, -0.7027, +0.2532, -0.3607,
+ -0.1223, +0.0162, -0.0028, +0.4377, -0.0581, -0.3754, -0.2387,
+ +0.0088, -0.0455, -0.1477, +0.4253, -0.0914, -0.7833, -0.1639,
+ -0.0433, +0.0863, +0.2265, -0.0409, +0.0313, +0.1362, +0.4949,
+ -0.0978, -0.5833, +0.0432, -0.4087, -0.1731, -0.0662, +0.4147, +0.1439
+ ],
+ [
+ +0.0350, +0.1548, +0.0131, +0.0115, -0.3387, +0.2374, +0.3363,
+ -0.5082, +0.5767, -1.2487, +0.1592, +0.1192, -0.9356, +0.0592,
+ +0.4122, -0.4330, -0.3213, -1.4197, +0.3280, -0.2136, -0.4984,
+ +0.2073, -0.0745, -0.2410, -0.2374, -0.0251, +0.2538, +0.2056,
+ +0.0789, -0.5060, +0.3261, +0.2714, -0.3186, -0.1567, -0.0758,
+ +0.2377, +0.1467, +0.5026, -0.3973, +0.9726, -0.0972, -0.0295,
+ +0.0114, -0.3803, +0.2799, -0.3394, +0.1301, +0.0501, -0.1194,
+ +0.3699, +0.0053, -0.4543, +0.2368, -0.1180, -0.0139, -0.3556,
+ -0.1657, +0.2425, +0.1212, +0.0460, -0.3302, +0.0835, +0.1524, +0.2809
+ ],
+ [
+ +0.5912, +0.3751, -0.7060, -0.6319, -0.0354, +0.0242, +0.0191,
+ +0.1079, -0.2649, +0.3621, +0.0965, -0.0276, -1.0230, -0.3146,
+ +0.2075, -0.6826, -0.3492, -0.0961, -0.5934, -0.6186, +0.0199,
+ +0.2130, -0.7184, +0.4223, +0.0614, +0.1626, +0.2471, +0.2255,
+ -0.2649, +0.1865, +0.2010, -0.0649, -0.7986, +0.3571, -0.7812,
+ +0.0793, -1.1885, -0.7985, -0.4967, -0.0632, +0.1954, -0.3144,
+ +0.1585, -0.2425, +0.0907, +0.0252, -0.9084, +0.3666, -0.5707,
+ -0.5022, +0.2995, +0.2105, +0.5991, +0.0387, +0.0628, +0.1833,
+ -0.1081, -0.6146, -1.9594, +0.3486, +0.4696, -0.0909, +0.2579, -0.8427
+ ],
+ [
+ +0.0336, -0.4557, -0.6614, +0.4449, +0.0964, +0.1173, -0.4679,
+ +0.3083, -0.3942, +0.2012, +0.0582, -1.3162, +0.0455, -0.5111,
+ -0.6087, +0.2155, -0.0063, -0.1217, -0.0372, +0.0719, +0.3264,
+ +0.4321, -0.5644, +0.4457, +0.6958, +0.3130, +0.1354, -0.0940,
+ +0.1247, -0.1034, -0.3069, -0.5462, -0.3833, -0.2013, +0.0727,
+ -0.2046, -0.6196, -0.2577, +0.1981, +0.0947, +0.2343, +0.2706,
+ -0.0317, -0.4985, +0.2393, +0.2797, -0.0232, -0.4649, +0.6968,
+ +0.1224, -0.0383, -0.5945, -0.5035, +0.0959, -0.3727, +0.7081,
+ -0.1661, +0.1211, -0.1007, -0.2776, +0.2769, +0.3188, -0.8125, -0.2640
+ ],
+ [
+ -0.2121, +0.1708, -0.0225, -0.0678, -0.0867, -0.0663, +0.2636,
+ +0.2387, +0.2040, -0.2074, -0.4069, -0.1904, -0.0885, -0.4112,
+ -0.5617, +0.3723, +0.4653, -0.2569, -0.3289, +0.4304, -0.0073,
+ +0.0809, -0.0856, -0.0631, -0.2508, -0.3386, -0.8901, +0.1858,
+ -0.1145, -0.0091, -0.0037, +0.3607, -0.0357, -0.7050, -0.2968,
+ +0.3616, +0.2470, +0.2633, -0.0279, +0.0722, -0.4222, -0.1375,
+ -0.4831, -0.2887, +0.0935, -0.0073, -0.4007, -0.1702, -0.2263,
+ +0.3825, +0.1574, +0.6085, -0.1626, -1.7196, +0.3131, +0.2672,
+ -0.1385, +0.3224, +0.3787, -0.0462, -0.3012, -0.5527, -0.4602, +0.1942
+ ],
+ [
+ -0.6093, -0.9537, +0.1757, -0.3976, -0.0383, +0.7251, +0.3466,
+ +0.4402, -0.0774, -0.4007, +0.0816, -0.0457, -0.1168, +0.2660,
+ +0.1250, -0.5599, +0.2008, +0.8158, -0.4430, +0.4986, -0.5222,
+ +0.3090, +0.0151, -0.1805, +0.1431, -0.1892, -0.6358, -0.2858,
+ -0.2296, -0.1724, -0.4177, +0.0810, +0.0851, -0.0888, +0.2480,
+ -0.2108, +0.2010, +0.0679, +0.0160, +0.1122, -0.5618, +0.0329,
+ -0.1360, -0.5033, -0.3957, -0.2492, +0.5305, -0.7473, -0.2721,
+ -0.0429, -0.0304, +0.0405, +0.6790, -0.1740, +0.3304, -0.0981,
+ -0.4455, -0.0456, -0.1221, +0.2468, -0.6452, +0.0697, +0.3481, -0.0379
+ ],
+ [
+ -0.1121, -0.5130, -0.5136, +0.3138, +0.2760, -0.3535, -0.3125,
+ +0.3587, -0.4589, -0.1302, -0.3529, +0.4531, +0.1770, +0.2400,
+ -0.0107, -0.2273, -0.0549, -0.1933, +0.0799, +0.0211, +0.0974,
+ -0.3228, -0.1341, -0.5369, +0.2466, -0.2529, -0.0108, -0.3154,
+ -0.0725, -0.1345, -0.2088, -0.0873, -0.3675, +0.0120, +0.0838,
+ -0.1347, +0.2473, +0.4509, +0.4634, +0.1623, +0.0152, +0.4995,
+ +0.4125, -0.0801, -0.9684, -1.0005, +0.1577, +0.3948, -0.1291,
+ +0.1197, -0.0382, +0.1272, -0.4528, -0.1108, -0.2218, -1.0994,
+ -0.0977, -0.3832, +0.1989, +0.3940, +0.2129, -0.1267, +0.2891, -0.4566
+ ],
+ [
+ +0.2013, -0.4966, +0.3134, +0.2968, +0.4050, +0.3077, -0.0970,
+ +0.0265, -0.6194, -0.4650, +0.2879, -0.5189, +0.0415, -0.0279,
+ -0.2265, +0.2703, -0.0049, -0.1062, +0.0758, +0.5811, -0.4047,
+ -0.4008, -0.5073, -0.1825, +0.3934, +0.1870, +0.0549, +0.2662,
+ -0.1832, +0.0716, -0.5844, +0.0985, +0.1388, -0.4097, +0.3492,
+ +0.3050, -0.3009, -0.3748, -0.0855, -0.2690, +0.0865, +0.0847,
+ -0.2502, +0.4930, -0.4957, -0.0679, +0.2032, -0.5270, -0.0298,
+ -0.6239, -0.3869, +0.1205, +0.2789, -0.4187, -0.4100, -1.3293,
+ +0.0339, -1.2127, -0.4629, -0.4488, -0.3622, +0.3658, -0.1273, -0.9988
+ ],
+ [
+ +0.0618, -0.6976, -0.2739, -0.4951, +0.3629, -0.0572, -0.0423,
+ -0.1126, -0.0084, +0.0039, -1.1347, +0.0766, +0.5972, -0.2661,
+ -0.1608, -0.1188, -0.5734, +0.2740, -0.1348, -0.0046, -0.2420,
+ +0.4932, -0.3493, +0.0077, -0.2928, +0.1936, -0.4306, +0.0672,
+ -0.2478, +0.2933, +0.4783, +0.1112, +0.0508, +0.5279, -0.0602,
+ -0.6082, +0.0254, -0.1455, +0.0860, -0.0137, +0.2181, +0.4595,
+ -0.1020, +0.2738, -0.3845, +0.1527, +0.0903, +0.2459, -0.1028,
+ -0.0204, +0.3592, -0.1899, +0.0156, -0.3667, +0.2428, -0.2370,
+ +0.4264, -0.1857, +0.1354, -0.1368, +0.1373, +0.3646, -0.1913, -0.2312
+ ],
+ [
+ -0.1679, -0.2973, +0.3421, +0.2689, -0.0877, +0.2735, -0.1347,
+ -0.2523, -0.0631, +0.1108, +0.2597, +0.4530, +0.1214, -0.1416,
+ -0.5936, -0.1322, -0.2734, -0.7423, +0.1697, +0.0126, -0.2423,
+ -0.0829, +0.4345, +0.2280, +0.1167, +0.0169, -0.1051, +0.4623,
+ +0.1274, +0.1364, -0.7264, +0.2868, +0.2049, +0.0837, -0.6358,
+ +0.0789, +0.1073, +0.5686, +0.3086, -0.5808, +0.7224, -0.5558,
+ -0.5012, -0.0334, +0.1128, -0.4420, +0.0341, -0.0761, -0.6116,
+ -0.1187, -0.0079, +0.1517, +0.1157, -0.0825, +0.0421, -0.4036,
+ +0.2306, -0.1724, +0.0817, +0.0796, +0.2520, -0.0839, -0.1000, +0.2560
+ ],
+ [
+ -0.1568, +0.1256, +0.2687, +0.5304, +0.0616, +0.2620, -0.1174,
+ -0.0828, +0.2457, -0.7009, -0.2341, +0.1980, -0.1387, +0.0767,
+ -0.1147, -0.3794, -0.0804, -0.9129, +0.4222, -0.0307, -0.4511,
+ +0.0235, +0.2063, -0.0281, -0.6208, -0.3369, -0.2876, -0.1240,
+ +0.0289, -0.1814, -0.0107, -0.6183, -0.0970, -0.1725, +0.0277,
+ -0.2143, +0.4770, -0.3520, +0.2918, -0.2149, +0.0670, +0.2961,
+ +0.0475, -0.2314, +0.4138, -0.6241, -0.5202, +0.6909, -0.1022,
+ -1.0779, +0.0202, +0.3129, -0.1340, +0.0622, -0.1117, -0.2848,
+ +0.1219, -0.2674, +0.2004, -0.4155, -0.0463, +0.1513, -0.0398, +0.3006
+ ],
+ [
+ -0.6542, +0.7595, -1.3221, +0.0988, -0.3465, +0.4240, -0.0449,
+ -0.8170, +0.0414, +0.1441, -0.6610, +0.0711, +0.1398, +0.6336,
+ +0.0080, -0.0566, -0.0857, +0.1501, -0.0995, +0.1385, +0.2677,
+ +0.0367, +0.1083, -0.0359, -0.1822, +0.1932, -0.1764, -0.4851,
+ -0.0244, -0.3504, -0.0213, -0.1195, -0.2686, -0.5418, -0.4927,
+ +0.3825, -0.0737, +0.0830, -0.2684, +0.2176, +0.1968, -0.2227,
+ -0.3244, -0.6385, +0.1551, -0.2165, -0.0925, +0.1828, +0.4494,
+ -0.1357, -0.0456, -0.0027, +0.1056, +0.3863, -0.1894, +0.0876,
+ -0.1854, +0.1973, +0.3061, +0.0674, +0.6454, -0.2473, +0.2778, +0.3394
+ ],
+ [
+ +0.1184, +0.0655, -0.4564, +0.1047, +0.0245, -0.3896, -0.4310,
+ +0.2791, -0.4074, -0.2665, -0.4304, +0.6561, -0.6748, +0.1907,
+ +0.5614, -1.5843, -0.0335, +0.1814, +0.3863, -0.3579, +0.0952,
+ -0.3241, +0.0511, +0.4439, +0.5712, -0.4604, +0.1338, +0.7400,
+ +0.2259, -0.5242, -0.5329, -0.4611, -0.1593, +0.0052, +0.1623,
+ -0.3202, -0.5784, +0.0174, -0.8842, -0.4272, +0.3299, -0.2110,
+ +0.0281, +0.4345, -0.0094, +0.4800, +0.0468, -0.1435, -0.1890,
+ +0.4818, +0.3842, +0.5413, +0.0015, -0.1571, -0.0965, -0.2082,
+ +0.3220, -0.4657, -0.2957, -0.4660, +0.1112, +0.0833, -1.0452, +0.2931
+ ],
+ [
+ -0.1050, -0.3930, -0.8470, -0.1539, +0.0283, +0.0506, -0.2962,
+ +0.1335, +0.1858, +0.2597, +0.1192, +0.0226, -1.1154, +0.4943,
+ -0.2086, +0.3223, -0.2796, -0.7304, -0.3808, -0.2430, +0.1130,
+ -1.4927, -0.0413, +0.1508, +0.2756, -0.1085, +0.0958, -0.0511,
+ -0.1654, -0.5590, +0.4892, +0.3117, -0.4354, -0.5566, -0.2910,
+ +0.1871, -0.3210, +0.0707, -1.4751, -0.0064, -0.3395, +0.1091,
+ -0.3423, -0.1070, +0.6077, -0.6818, +0.0364, +0.1810, -0.2418,
+ -0.4348, +0.2138, -0.4457, +0.1850, +0.1663, -0.4589, -0.0590,
+ +0.0140, -1.0031, +0.1671, +0.3095, -0.1959, -0.2354, +0.1129, -0.0914
+ ],
+ [
+ +0.1642, +0.1094, +0.3448, -0.0749, -0.0180, +0.2558, +0.4060,
+ +0.3335, +0.4197, -0.1441, -0.2556, +0.6254, -0.3226, -0.6062,
+ -0.2805, -0.1570, -0.3601, -0.3835, -0.2042, -0.0328, +0.1023,
+ +0.0759, +0.2519, -0.1706, -0.0075, -0.4085, -0.3140, -0.1070,
+ +0.0632, +0.0191, -0.4709, -0.2254, +0.0114, +0.3076, +0.2059,
+ +0.5133, -0.2243, +0.2795, +0.3773, +0.0803, -0.4325, -0.9119,
+ -0.1979, -0.6436, -0.2572, -0.3237, -0.4447, +0.5916, -0.3867,
+ +0.0101, +0.1406, -0.1133, +0.2802, -0.6540, -0.3323, +0.4628,
+ -0.0367, -0.2508, +0.2539, -0.3993, -0.5283, -0.2690, -0.3873, -0.3024
+ ],
+ [
+ -0.1436, -0.5517, -0.4431, +0.5327, -0.2588, +0.0900, -0.4125,
+ -0.2162, -0.1184, +0.2474, -0.1347, +0.1252, -0.0133, +0.0987,
+ -0.4174, +0.3728, -0.1239, -0.2282, +0.0385, -0.1100, +0.6123,
+ -0.4759, -0.3614, -0.0685, +0.3599, -0.0198, +0.1704, -0.0608,
+ -0.0503, +0.4438, -0.7307, +0.3350, +0.1720, +0.4469, -0.0751,
+ +0.0401, +0.3470, -0.0172, +0.0262, -0.0346, +0.1317, -0.1553,
+ +0.2946, -0.2742, +0.2364, -0.0640, +0.2536, -1.0183, +0.0773,
+ -0.2492, +0.0397, -0.3045, -0.3429, -0.3352, -0.5485, +0.3430,
+ +0.1481, -0.4997, +0.0928, -0.2616, -0.1770, +0.5925, +0.1034, +0.1339
+ ],
+ [
+ -0.2951, +0.0378, +0.0823, +0.0307, +0.0271, +0.3036, -0.0292,
+ -0.2978, +0.0779, +0.1428, -0.4928, +0.2944, +0.2024, +0.1920,
+ -1.0302, +0.3304, +0.0657, +0.0634, +0.3791, +0.0085, +0.0081,
+ +0.2927, -0.0241, -0.2411, -0.7849, -0.1806, -0.0433, +0.3816,
+ -0.0558, -0.1094, -0.0139, +0.1603, +0.4586, -0.7991, +0.1147,
+ -0.5045, +0.0183, -0.3893, -0.0443, -0.1665, +0.0342, -0.2120,
+ -0.1391, -0.4926, +0.1438, +0.1863, -0.7227, +0.3673, -0.1077,
+ -0.9778, +0.7210, +0.3733, +0.0778, -0.4336, -0.3407, -0.0074,
+ +0.0330, -0.4428, +0.1380, -0.8513, +0.0357, +0.4141, +0.1583, +0.2167
+ ],
+ [
+ +0.2654, +0.0174, +0.2618, +0.1341, -0.1338, -0.1338, -0.2252,
+ -0.1168, -0.0680, -0.1107, -0.7590, +0.0632, -0.0997, +0.2548,
+ -0.8639, -0.7354, +0.2814, -0.4214, +0.2266, +0.0072, +0.1706,
+ +0.3742, +0.2437, -0.5361, -0.2646, -0.3248, +0.1836, -1.9472,
+ -0.0832, -0.0410, +0.4056, -0.4654, -0.3995, -0.4292, -0.4182,
+ -0.4856, -0.8076, -0.7141, -0.2657, +0.0958, +0.0713, -0.2720,
+ -0.2588, -0.5835, +0.4793, -0.4319, -0.1098, -0.3144, +0.4965,
+ -0.4547, +0.3820, +0.4288, +0.0844, +0.5179, -0.0320, -0.8708,
+ -0.0751, +0.1578, +0.0879, -0.4416, +0.1729, -0.1362, -0.5350, -0.3401
+ ],
+ [
+ -0.2118, +0.3834, +0.3130, +0.3395, -0.3651, -0.0606, +0.4956,
+ +0.0693, -0.0051, -1.4244, +0.1108, +0.0637, +0.1052, -0.0301,
+ -0.0014, +0.0911, -0.8848, +0.1114, +0.0666, +0.3995, +0.4920,
+ -0.5034, -0.3851, +0.1373, -0.1200, +0.3886, +0.0684, -0.0183,
+ -0.4282, -0.0734, -0.1273, -0.4760, +0.1408, +0.5883, -0.0509,
+ -0.2998, -0.3337, +0.1388, -0.2568, -0.1320, +0.1283, -0.5020,
+ +0.1919, +0.1973, +0.3350, -0.0218, +0.7082, -0.2393, +0.0386,
+ -0.9842, -0.6694, -0.5423, +0.0867, -0.8208, -0.1974, +0.3153,
+ -0.2347, -0.7509, +0.1957, -0.2120, -0.1423, +0.0256, -0.5109, -0.5835
+ ],
+ [
+ -1.1792, -0.6405, -0.2588, -0.0688, -0.5575, +0.2734, -0.2927,
+ -0.9779, +0.3497, -0.7755, -0.3234, -0.2550, +0.3339, -0.4122,
+ -0.0858, +0.3816, +0.4377, -0.9395, -0.0228, +0.2162, -0.0766,
+ -0.2358, -1.2153, -0.0550, -0.0737, +0.2427, -0.2674, +0.1653,
+ -0.3603, +0.2592, -0.3009, +0.0850, -0.1091, -0.6973, -0.4073,
+ -0.6798, -0.0625, -0.3739, -0.0816, +0.0060, +0.1769, +0.5716,
+ -0.2536, -0.3430, +0.1475, +0.0754, -0.1260, +0.2230, +0.0758,
+ -0.1088, -0.0445, +0.2242, +0.1145, +0.4178, -0.6738, -0.2665,
+ -0.0909, -0.7142, -0.1012, -0.4404, +0.0002, -0.0546, -0.3006, -0.0512
+ ],
+ [
+ -0.9125, +0.3809, -0.2227, +0.1087, -0.3885, +0.2956, +0.2774,
+ -0.5007, -0.3132, +0.0619, -0.1097, +0.1279, -0.0931, +0.1050,
+ -0.3562, -1.4404, -0.4041, -0.1452, +0.2098, -0.3736, +0.4604,
+ +0.3447, +0.3285, -0.4358, -0.0095, -1.4794, +0.1615, -0.3714,
+ -0.1101, +0.2171, -0.2488, -0.5689, -0.0069, -0.3341, +0.4860,
+ +0.1670, -0.5619, -0.2339, -0.4304, -0.1604, -0.1719, -0.1354,
+ -0.1688, +0.5730, +0.0874, +0.9201, +0.4451, -0.1082, +0.5830,
+ -0.5734, +0.8476, +0.1526, -0.0611, +0.0482, +0.4043, +0.1631,
+ +0.0934, +0.5185, -0.4728, -0.7169, +0.2903, -0.1128, +0.1467, +0.0853
+ ],
+ [
+ +0.2255, -0.1422, +0.6191, -0.5573, -0.4242, +0.6153, -0.0805,
+ -0.6878, +0.0707, +0.1314, -1.1376, -0.4014, +0.0828, -0.1102,
+ +0.4117, +0.1082, -0.1197, -0.0014, +0.2616, -0.4504, -0.1758,
+ -0.5121, +0.4080, -0.7097, -1.0162, -0.0971, -0.1583, -0.4393,
+ +0.2060, -0.2875, -0.0826, +0.0484, +0.1807, -1.0531, +0.1788,
+ -0.2329, -1.2088, -1.2534, -0.3840, -0.3139, +0.1190, -0.4243,
+ -0.3891, -0.1715, +0.2351, -0.0939, -0.1855, -0.4761, +0.4378,
+ +0.1383, -0.0800, +0.1091, -0.3985, +0.0516, -0.1441, +0.0286,
+ -1.0542, +0.4448, -0.8192, +0.4307, -0.2630, -0.6092, -0.0993, -0.1385
+ ],
+ [
+ +0.1763, -0.3222, +0.2001, -0.5100, -0.0191, +0.3838, -0.2628,
+ +0.4131, -0.3282, +0.5341, +0.1770, -0.3993, -0.4334, +0.3543,
+ +0.4917, -0.3028, -0.5898, +0.2188, +0.4483, -0.4407, -0.1927,
+ +0.0154, +0.1614, -0.7020, +0.3948, +0.1950, +0.0146, +0.4208,
+ +0.3840, -0.2642, +0.7406, -0.1180, -0.0369, -0.8693, +0.2694,
+ -0.0968, +0.0402, -0.1230, -0.2885, +0.0380, -0.4557, +0.2529,
+ -0.1008, -0.1731, -0.8810, -0.2787, +0.4076, +0.1796, +0.4104,
+ +0.3133, -0.5395, +0.0393, -0.2067, +0.7584, -0.3746, +0.0869,
+ +0.6750, +0.3594, -0.3354, +0.2386, -0.1971, +0.0392, -0.0169, -0.1902
+ ],
+ [
+ +0.2144, -0.3314, +0.2725, -0.0827, -0.0906, +0.0674, +0.1273,
+ -0.4302, +0.2808, -0.8198, -0.0832, +0.3300, +0.4027, +0.0423,
+ +0.2126, +0.1215, +0.1076, -0.3192, -0.0130, +0.2427, -0.1374,
+ +0.1292, +0.1993, -0.5142, -0.1865, +0.0820, +0.0993, +0.1877,
+ -0.3977, +0.0706, -0.7814, +0.2711, +0.4268, -0.1433, +0.4873,
+ +0.5543, +0.0717, +0.2401, -0.0935, -0.2784, +0.2711, +0.2732,
+ -0.8383, -0.2575, -0.0303, +0.0535, +0.1117, -0.3160, +0.2767,
+ +0.1754, +0.0219, -0.0515, +0.0079, -0.7837, +0.1359, +0.0749,
+ -0.2690, +0.1145, -0.1394, +0.2234, -0.8230, +0.2444, -0.5010, -0.0515
+ ],
+ [
+ -0.7577, -0.1246, -0.6416, -0.1292, +0.1269, -0.1601, -0.7096,
+ +0.5698, +0.1452, +0.2287, -0.1673, +0.1212, -0.0779, -0.3946,
+ -0.6451, -1.1095, -0.7062, -0.0777, +0.1132, -0.2283, +0.0272,
+ -0.0535, -0.0579, +0.3027, +0.3611, -0.0492, +0.0490, +0.1978,
+ -0.1055, +0.1079, +0.2022, +0.1964, -0.3552, +0.0624, -0.2604,
+ -0.3808, +0.0454, +0.3496, +0.1034, -0.1317, +0.2831, -0.8189,
+ +0.2068, -0.0665, -0.2932, -0.3625, +0.1067, -0.3037, +0.3838,
+ +0.0383, +0.1815, +0.2562, -0.0403, -0.0175, -0.1908, -0.7806,
+ +0.1274, +0.1829, -0.1783, +0.2590, -0.4242, -0.0020, +0.2163, -0.7718
+ ],
+ [
+ -0.1172, -0.2910, +0.1343, +0.1023, +0.2716, +0.2049, -0.6185,
+ +0.2182, -0.1194, -0.0311, -0.4619, +0.2636, +0.2120, -0.2086,
+ +0.0149, +0.0339, +0.2969, -0.3070, -0.2462, -0.1908, -0.2441,
+ +0.3313, +0.6891, +0.1639, -1.0531, -0.1253, -0.2737, +0.2814,
+ +0.1508, +0.1255, +0.4555, -0.0806, -0.0359, +0.0192, -0.0501,
+ +0.3172, +0.0013, -0.8248, -0.1446, -0.1389, +0.3792, +0.3625,
+ -0.2145, +0.0517, +0.2897, +0.0143, +0.0080, +0.1945, -0.4495,
+ -0.0941, +0.5322, +0.2886, -0.0868, -1.5349, +0.0948, -0.7860,
+ +0.5374, -0.5335, -0.0638, -0.1858, +0.0161, -0.2840, -0.3180, +0.3528
+ ],
+ [
+ -0.3348, +0.2055, -0.9754, -0.4012, +0.4188, -0.2831, +0.1521,
+ +0.1827, +0.1194, +0.0318, -0.0500, -0.4176, -0.3061, +0.0976,
+ -0.0334, -0.0595, -1.2187, -0.2892, -0.0487, -0.3854, -0.0304,
+ +0.1867, -0.0166, +0.2530, +0.2887, -0.2363, -0.1904, +0.2580,
+ +0.0583, +0.3023, -0.0038, -0.3527, +0.3573, -0.0487, -0.0710,
+ -0.4197, +0.1109, +0.1214, -0.5087, +0.3008, -1.3029, -0.4291,
+ -0.0687, +0.1112, +0.1664, +0.4177, +0.0462, +0.0217, +0.3115,
+ +0.2880, +0.1207, -0.1077, +0.1978, +0.0262, +0.2084, -0.4996,
+ +0.0478, +0.3084, -0.0012, -0.2354, -0.5644, +0.1193, +0.0854, -0.5877
+ ],
+ [
+ -0.3103, -0.3814, +0.1322, -0.1447, -0.2558, +0.0371, +0.0856,
+ +0.1248, +0.2103, -0.2475, -0.2205, +0.3099, +0.3163, -0.1651,
+ +0.2838, +0.2346, -0.3855, -0.2486, -0.3396, -0.0437, +0.3671,
+ -0.0069, +0.4828, -0.6932, -0.7277, +0.3441, -0.8020, +0.4863,
+ +0.1061, -0.2418, -0.2396, -0.0053, -0.1668, -0.2948, -0.0782,
+ -0.0149, +0.3159, +0.2116, +0.2267, -0.2058, +0.1034, -0.0827,
+ +0.0529, +0.0069, +0.1822, +0.0000, +0.0525, +0.2258, -0.2335,
+ -0.0016, -0.1231, +0.8993, -0.6615, -0.8643, -0.1698, -0.1447,
+ +0.0801, -1.4432, -0.2538, +0.1848, +0.1005, +0.3882, +0.0458, +0.0405
+ ],
+ [
+ +0.3984, +0.1613, +0.5291, +0.1697, -0.2074, -0.4148, -0.3233,
+ -0.3691, -0.1697, -0.0608, -1.2200, +0.2840, -0.7305, -0.2600,
+ +0.2990, +0.0959, -0.0343, +0.2958, +0.1014, -0.2986, -0.6878,
+ +0.1185, -0.4202, -0.5000, -0.2732, +0.0477, +0.0419, -0.4453,
+ -0.3634, -0.2955, +0.1807, +0.2088, -0.1500, -0.1789, -0.2411,
+ -0.3513, -0.2156, +0.1619, -0.7682, -0.2928, +0.2605, +0.4007,
+ +0.1044, -0.7360, +0.1440, -0.4713, -0.2737, -0.5854, +0.0717,
+ +0.5728, +0.3894, +0.1652, -0.5978, +0.2093, +0.2174, -0.3677,
+ -0.2305, -0.1676, -1.2163, -0.3159, -0.5652, -0.1905, -0.1668, +0.2184
+ ],
+ [
+ -0.0008, -1.0383, +1.1172, -0.3757, +0.1185, +0.2778, +0.1407,
+ -0.1279, -0.5174, -0.4343, +0.0887, -0.0483, -0.0541, -0.3713,
+ -0.3302, +0.4045, +0.4483, -0.6313, +0.0040, +0.1367, +0.2285,
+ -0.2697, -1.1601, +0.0076, +0.1744, +0.1132, -0.1431, -0.3811,
+ -0.6136, +0.2844, -0.1848, -0.5152, -1.0414, -0.4109, -0.7278,
+ -0.0349, +0.1370, -0.1978, +0.5068, +0.1623, -0.2598, -0.5556,
+ +0.2846, -0.1811, -1.5462, -0.2162, +0.5351, -0.2391, -0.1035,
+ -0.2865, -0.1122, +0.4251, -0.2923, -0.8803, +0.1712, +0.1824,
+ +0.2363, -0.6512, +0.2178, -0.4485, -0.3429, -0.1578, +0.1009, -0.1692
+ ],
+ [
+ +0.0041, +0.4229, +0.0388, +0.5734, +0.1830, -0.5990, +0.0260,
+ -0.4107, -0.1851, -0.2277, -0.0275, -0.2505, +0.4437, +0.3490,
+ +0.2597, -0.1346, -0.5125, -0.1878, -0.4422, +0.0793, +0.0946,
+ +0.1463, +0.3695, +0.4150, +0.2463, -0.4557, +0.4123, +0.2879,
+ +0.6034, -0.5302, -0.7214, -0.2835, -0.0240, +0.2951, +0.3102,
+ -0.2566, -0.0515, -0.1121, -0.5604, -0.3810, +0.4285, +0.9055,
+ -0.2602, +0.2380, -0.3954, -0.0396, +0.6154, +0.0981, +0.4571,
+ +0.0322, +0.2965, +0.1396, -0.0881, -0.0175, +0.3386, -0.0699,
+ +0.1114, +0.3103, +0.0885, -0.2483, +0.3396, -0.5895, -0.4524, +0.4458
+ ],
+ [
+ -0.7421, -0.1838, +0.0929, +0.1654, -0.1778, +0.1589, +0.1777,
+ +0.1539, +0.6931, -0.0002, +0.0366, -0.2482, +0.3404, -0.6776,
+ -0.0599, -0.9906, -0.1703, -0.2741, -0.2623, +0.2435, +0.1282,
+ -0.2218, -0.4463, -0.0515, -0.1126, +0.5793, -0.4053, +0.3077,
+ -0.2113, -0.1654, -0.4019, +0.3054, -0.2755, -0.0359, -1.3564,
+ +0.7528, +0.0788, +0.2060, +0.1633, -0.4355, +0.2035, -0.2194,
+ -0.0381, -0.1512, -0.7473, +0.2736, -0.0204, -0.4578, -0.4144,
+ +0.0076, -0.6070, +0.0851, +0.4764, -0.3511, -0.1171, -0.8141,
+ +0.1976, +0.2906, +0.0918, +0.2261, +0.2769, +0.1746, +0.5881, -0.8917
+ ],
+ [
+ -0.3276, -0.1296, +0.3245, -0.0630, +0.1080, -0.0923, -0.0555,
+ -0.4351, -0.4805, +0.1625, -0.7317, +0.0232, -0.0290, -1.2621,
+ +0.0074, +0.6063, -0.0992, +0.2137, -0.0525, -0.1596, +0.2326,
+ +0.7151, -0.2879, -0.9427, +0.0728, +0.3451, -1.3029, -0.1453,
+ -0.0766, -0.1260, +0.2174, +0.2524, -0.0272, -0.9901, -0.2757,
+ -0.0532, +0.0768, -0.6334, +0.2368, +0.1227, -0.6449, -0.0662,
+ +0.3466, -0.1741, +0.1209, +0.4601, +0.1192, -0.0727, -0.3973,
+ -0.2250, +0.1601, +0.1562, -0.2805, -0.0830, -0.0274, -0.4325,
+ +0.0951, -0.1183, +0.1025, +0.0261, -0.6047, -0.0146, -0.1957, +0.0218
+ ],
+ [
+ +0.1081, +0.3138, +0.3278, -0.7791, +0.1543, -0.1908, +0.3635,
+ +0.0070, +0.3577, -0.0404, -0.8582, -0.4834, +0.3016, -0.6306,
+ -0.4563, +0.1801, -0.2791, -0.6206, +0.0517, +0.5410, +0.1347,
+ +0.4778, +0.0558, -0.0759, -0.0772, +0.1917, -0.7159, -0.0643,
+ -0.1721, -0.5170, -0.3511, -0.3017, +0.1299, -0.7527, -0.1136,
+ -0.3605, -0.3682, -0.0709, +0.0723, -0.2196, -0.9063, -0.3520,
+ -0.3413, +0.2594, +0.1649, -0.5071, -0.1584, +0.1231, +0.0057,
+ -0.4875, +0.2410, -0.2405, +0.3705, -1.0071, +0.3241, +0.0207,
+ -0.4803, -0.4314, +0.1130, -0.0724, +0.2252, -0.2790, +0.0415, +0.0660
+ ],
+ [
+ -1.0239, +0.0612, -0.1775, +0.0616, +0.3968, +0.1192, -0.0637,
+ -1.3325, +0.0141, -0.3692, -0.2163, +0.1634, +0.1818, +0.1767,
+ -0.3110, -0.5755, -0.2020, -0.1910, +0.4489, -0.0309, +0.2252,
+ +0.0045, +0.0525, -0.9357, +0.0912, -0.2257, +0.2897, +0.4927,
+ +0.0509, -0.3725, +0.2843, -0.8260, -0.1409, -1.0330, -0.1377,
+ +0.2625, +0.0637, -0.5822, -1.0901, +0.2305, -0.0809, -0.4811,
+ -0.2776, +0.1618, -0.6189, +0.1608, +0.2586, -0.4005, -0.0048,
+ -0.4438, -0.0799, +0.1356, +0.0141, -0.1191, +0.3150, -0.4819,
+ -0.2142, +0.1938, +0.2875, -0.5401, +0.0929, -0.3865, -0.0821, -0.5999
+ ],
+ [
+ +0.4043, -0.0639, -0.3917, +0.0908, +0.0894, -0.4655, -0.2022,
+ +0.3332, -0.2707, +0.0466, +0.1355, +0.1318, -0.3180, -0.3957,
+ -0.0124, -0.7214, -0.2792, +0.3177, -0.5455, -0.5225, -0.2927,
+ -0.2688, +0.0192, +0.3940, +0.0514, +0.2258, -0.3504, -0.0024,
+ +0.0145, -0.2194, -0.0040, +0.2842, -0.0667, -0.4815, +0.2162,
+ +0.1778, -0.7473, +0.4520, +0.1720, -0.5224, -0.0490, -0.5519,
+ -0.3571, +0.4386, -0.1868, -0.2627, -0.3350, -0.7849, -0.1009,
+ +0.1432, -0.2389, +0.1923, -0.4800, +0.0100, -0.0507, +0.0151,
+ +0.3257, +0.0299, +0.0118, +0.2283, -0.2633, +0.2229, -0.7595, +0.1507
+ ],
+ [
+ +0.2797, -0.2386, -0.0121, +0.2439, -0.0317, -0.0390, +0.0581,
+ -0.8813, -0.5392, -0.2527, -0.4720, +0.4787, +0.3710, +0.0434,
+ +0.0702, -1.0678, -0.0195, -0.6846, -0.7418, +0.0543, -0.3187,
+ -0.1510, -0.3590, -0.0902, +0.2195, +0.0943, -0.0384, -0.7203,
+ +0.0316, -0.0647, +0.1894, +0.2490, -1.3374, +0.3883, +0.1207,
+ +0.4036, +0.3255, +0.3757, +0.2444, +0.2612, -1.5274, +0.1092,
+ +0.5718, -0.1929, -0.1531, -0.2330, +0.0539, +0.2055, -0.8240,
+ +0.1292, -0.4835, +0.5281, +0.1944, -0.3389, -0.3689, +0.4941,
+ +0.0330, +0.0938, +0.4999, -0.2465, -0.2547, +0.3286, -0.2172, +0.4791
+ ],
+ [
+ +0.4580, +0.6728, +0.1603, -0.5751, -0.8616, +0.0422, -0.3104,
+ -0.2042, +0.4133, +0.3150, -0.8036, -0.5332, +0.5432, +0.2999,
+ +0.1480, -0.2845, -0.9013, -0.0924, -0.6048, -0.1631, -0.1127,
+ -0.3833, -0.5830, -1.1764, -1.2800, -0.0174, -0.2561, +0.1081,
+ +0.3352, +0.1175, +0.3419, +0.7590, +0.4220, -0.8411, +0.0312,
+ +0.3287, +0.2295, -0.0867, -0.6239, +0.0633, +0.3005, -0.0838,
+ -0.4589, -0.2385, +0.2734, -0.2946, -0.2759, -0.4446, +0.0052,
+ -0.3499, -0.3503, +0.1211, -0.1839, -0.2803, +0.0158, +0.2441,
+ +0.4413, -0.4929, +0.3714, +0.5445, -0.0731, -0.3297, -0.5428, +0.4811
+ ],
+ [
+ -0.3528, +0.2554, +0.1195, +0.2853, -0.0731, -0.0237, -0.0755,
+ +0.3719, -0.5900, +0.3071, +0.1961, -0.3822, -0.3113, +0.3011,
+ +0.1113, -0.1598, -0.0299, +0.6281, +0.1811, +0.1312, +0.1971,
+ -0.4736, +0.7463, -0.0154, +0.4255, -0.3671, +0.3200, -0.1815,
+ -0.4259, +0.1115, +0.4232, -0.3993, +0.0706, -0.1901, +0.1188,
+ -0.6964, -0.5131, -0.5996, -0.0103, +0.1504, +0.0713, -0.0430,
+ -0.8008, +0.1890, -0.2637, +0.1984, +0.0119, +0.1025, -0.9490,
+ -0.0255, +0.2795, +0.2354, -0.1830, +0.1894, -0.1928, -0.8840,
+ +0.3929, +0.1748, +0.1588, +0.4326, -0.0759, +0.1664, +0.2102, -0.3707
+ ],
+ [
+ +0.0479, -0.0155, -0.3830, +0.0390, -0.0793, -0.1159, -0.0263,
+ -0.3720, -0.9581, +0.2546, -0.4353, +0.2756, -0.0628, +0.0360,
+ +0.1591, -0.7122, +0.1463, -0.1078, -0.5880, +0.1476, -0.0437,
+ -0.6911, -0.0355, +0.2766, -0.3426, +0.2286, -0.2323, -0.2819,
+ -0.0887, +0.5000, -0.0338, -0.1563, -0.0168, +0.0500, -0.1077,
+ +0.4968, -1.1365, +0.1814, -0.1388, -0.1080, +0.0761, -0.4107,
+ +0.3764, +0.3308, +0.0905, -0.2821, -0.2366, -0.2618, +0.2762,
+ -0.2521, +0.1400, -0.1133, +0.0411, -0.0475, -0.4804, +0.4348,
+ -0.1652, +0.0103, +0.2100, -0.3716, +0.1860, -0.3946, -0.1734, +0.2052
+ ],
+ [
+ -0.0266, -0.2590, -0.1527, +0.2632, -0.1506, -0.0040, -0.3828,
+ -0.7623, -0.1620, -0.1641, +0.0927, +0.1030, -0.1890, +0.2110,
+ +0.1634, -1.4356, +0.1170, -0.7333, -0.3429, -0.3402, +0.5740,
+ +0.2288, +0.0264, -0.0770, +0.0611, +0.2538, +0.5611, -0.0635,
+ -0.0885, -0.0698, +0.2153, +0.0752, -0.2368, +0.2113, -0.8473,
+ -0.7176, -0.3615, -0.2906, +0.0310, +0.0041, -0.3076, +0.1850,
+ +0.0959, -0.1510, +0.1042, +0.0781, +0.1000, -0.0701, -0.0252,
+ +0.6513, +0.1680, +0.3624, -0.5958, -0.6897, +0.1336, -0.0600,
+ +0.0437, -0.2525, +0.1216, -0.2053, +0.0452, +0.8903, -0.0487, -0.0072
+ ]])
-weights_final_w = np.array([
-[ -0.0133, +0.0628, -0.6441, +0.2383, +0.4270, +0.1927, -0.3628, +0.3698],
-[ -0.0089, +0.0614, +0.0522, -0.3912, -0.1872, -0.7369, +0.0852, -0.1505],
-[ +0.2779, +0.7024, -0.3493, -0.2124, -0.0220, +0.0741, +0.0670, -0.1029],
-[ -0.0519, +0.2775, -0.3879, -0.0335, +0.1150, +0.0789, -0.1963, +0.1992],
-[ +0.0241, +0.2946, +0.2777, -0.2040, +0.4150, +0.0810, -0.0170, -0.0202],
-[ -0.2781, +0.0243, -0.0485, +0.1249, -0.0354, -0.0327, +0.2284, -0.3674],
-[ -0.1843, +0.1452, -0.0728, +0.2894, +0.1892, +0.0013, +0.1527, -0.3815],
-[ +0.4556, -0.1760, +0.0188, -0.2475, -0.3291, -0.3527, -0.6556, -0.5543],
-[ +0.0309, +0.3396, +0.0626, -0.0045, +0.2597, -0.2234, +0.3634, -0.1476],
-[ -0.3221, +0.4484, +0.0538, +0.2543, -0.3213, +0.4323, -0.2503, +0.0654],
-[ +0.5351, -0.2229, -0.1097, +0.1062, -0.5535, +0.4454, +0.1802, +0.1971],
-[ +0.1813, +0.0778, +0.1647, -0.1118, +0.4696, -0.3322, -0.2033, -0.0201],
-[ +0.1423, +0.2278, +0.0263, +0.1439, +0.0134, -0.5282, +0.1236, -0.0416],
-[ +0.1217, +0.1197, -0.5194, +0.4029, -0.1307, -0.4352, -0.0514, -0.2256],
-[ +0.1484, +0.0685, +0.4156, +0.1887, -0.7306, +0.1027, -0.4018, +0.0134],
-[ +0.2326, +0.0218, +0.0390, +0.0010, -0.5719, +0.0264, -0.4600, -0.3220],
-[ -0.0586, -0.3066, +0.2050, +0.1253, +0.4542, +0.1711, -0.6051, +0.0061],
-[ +0.0108, -0.5588, -0.3976, +0.3375, +0.3065, +0.2118, -0.4879, +0.1444],
-[ -0.1443, -0.2895, -0.3992, +0.0409, +0.3109, -0.0295, -0.2016, -0.3679],
-[ -0.2630, +0.2348, +0.2592, +0.1778, -0.1501, -0.2856, +0.3477, +0.1416],
-[ -0.3078, -0.3138, +0.2040, -0.3254, +0.2891, +0.0228, -0.3580, +0.2438],
-[ -0.0035, -0.1374, +0.9035, +0.1420, +0.1437, -0.1159, -0.1822, +0.2037],
-[ +0.2533, -0.0089, -0.1549, +0.1085, -0.5376, -0.0639, +0.3232, +0.0673],
-[ -0.1033, +0.2733, +0.1426, +0.4075, -0.1140, +0.1152, +0.2189, +0.7337],
-[ +0.0682, -0.1010, +0.2224, +0.4526, +0.0599, +0.1290, -0.5523, +0.0333],
-[ +0.1089, -0.1139, -0.0310, -0.2661, +0.0781, -0.1955, -0.2610, +0.1017],
-[ +0.0011, +0.4399, -0.2365, -0.1523, -0.1508, +0.2314, +0.1414, +0.1116],
-[ +0.0014, -0.0973, +0.6542, -0.0039, -0.2656, -0.1597, +0.0158, -0.0201],
-[ -0.1700, +0.0102, +0.1321, -0.1934, -0.2208, +0.0057, +0.1504, +0.3798],
-[ +0.1586, +0.0557, +0.1042, -0.4201, +0.0613, -0.0152, -0.3855, +0.1035],
-[ -0.0969, -0.0936, +0.1289, -0.4031, +0.1148, +0.3258, +0.2017, -0.2499],
-[ +0.5422, -0.3985, -0.0758, -0.0241, +0.1124, +0.0043, -0.0495, -0.1127],
-[ +0.1679, -0.1337, -0.2102, -0.0678, +0.0768, -0.5881, +0.0327, -0.1429],
-[ +0.2756, -0.1772, -0.3729, -0.0931, +0.6402, -0.0739, -0.1221, +0.5423],
-[ -0.2310, -0.6409, -0.0729, -0.2143, +0.0735, -0.3279, -0.1317, -0.2060],
-[ -0.0864, +0.0344, -0.5635, +0.3137, -0.0566, -0.3874, -0.0119, +0.0187],
-[ +0.4066, +0.1192, +0.2065, +0.0546, +0.2182, +0.6743, +0.2802, -0.0638],
-[ +0.2526, +0.6688, -0.0943, -0.2531, +0.1259, +0.1115, +0.0581, -0.0340],
-[ +0.1820, +0.2927, -0.2457, +0.0310, -0.3335, -0.5889, +0.0088, +0.3045],
-[ +0.0072, -0.0702, +0.1246, +0.0875, +0.0488, +0.2379, -0.1760, -0.5422],
-[ +0.1416, +0.1796, -0.7311, +0.0016, -0.4996, +0.0724, -0.4854, +0.2310],
-[ -0.5525, +0.1246, +0.8667, +0.3521, -0.7227, +0.4473, +0.0805, -0.1707],
-[ -0.3557, +0.0798, +0.5322, -0.0827, +0.1836, +0.2784, -0.1676, -0.1012],
-[ -0.6738, +0.5545, -0.3111, +0.2171, -0.3377, -0.2039, -0.1205, +0.1212],
-[ -0.2249, -0.1037, -0.4715, -0.3616, +0.2250, +0.0999, +0.4772, -0.0679],
-[ -0.4895, -0.2557, +0.0892, -0.0000, -0.4443, +0.2913, -0.0450, -0.3303],
-[ -0.2729, +0.0973, +0.2516, -0.4313, -0.1743, -0.2386, -0.1142, -0.0440],
-[ -0.6820, +0.2449, -0.1079, +0.3047, +0.0325, -0.0980, +0.1868, -0.1600],
-[ -0.2085, -0.2897, -0.4539, -0.0506, +0.1225, +0.1976, -0.2360, +0.6553],
-[ +0.5299, +0.2876, +0.2354, -0.0884, -0.1821, +0.3841, -0.0701, +0.0278],
-[ -0.1594, -0.4837, +0.1483, -0.1280, +0.0962, -0.1932, +0.1730, +0.0544],
-[ +0.2879, -0.1846, +0.1474, -0.3383, +0.1483, +0.1159, +0.3761, +0.2326],
-[ -0.0960, -0.0727, -0.3099, +0.0548, +0.2339, -0.2232, +0.6066, +0.3826],
-[ -0.0171, +0.1490, -0.3324, -0.0231, +0.0700, -0.6364, -0.1944, +0.3094],
-[ +0.0804, -0.0278, +0.0182, -0.3807, -0.3628, -0.3564, +0.2279, -0.0226],
-[ +0.4219, +0.0741, +0.1299, +0.4700, +0.1927, +0.0849, -0.1574, +0.5607],
-[ +0.0810, -0.0815, +0.1356, +0.2048, -0.1404, -0.0222, -0.2464, +0.4991],
-[ +0.3000, +0.0862, -0.3917, +0.4117, +0.0306, +0.0788, -0.0403, -0.6423],
-[ -0.2445, +0.4847, +0.0478, -0.2170, -0.3700, +0.0189, +0.0001, -0.0335],
-[ +0.3710, -0.0115, -0.4207, -0.4245, +0.2041, -0.0875, -0.2369, -0.6424],
-[ -0.3608, +0.0539, -0.3928, -0.0352, +0.2832, +0.1003, -0.0082, +0.3201],
-[ +0.2221, -0.0399, +0.2092, -0.1670, -0.5146, +0.2273, +0.3011, -0.2879],
-[ +0.1500, +0.3236, +0.1295, -0.0763, -0.2708, +0.6542, +0.1379, -0.0646],
-[ +0.1291, +0.0417, +0.1386, +0.0166, +0.1373, +0.1956, +0.4986, +0.5690]
+weights_dense2_b = np.array([
+ +0.2226, +0.0124, +0.0027, +0.2335, +0.0952, +0.0250, +0.1087, +0.1225,
+ +0.0476, +0.1535, +0.0940, +0.0421, +0.0967, +0.0431, -0.2867, -0.1520,
+ -0.0796, +0.0041, +0.0599, +0.0139, -0.0608, -0.0695, +0.0222, +0.0420,
+ -0.0988, +0.0851, +0.2547, +0.0361, +0.0341, +0.0986, +0.1827, -0.1344,
+ +0.1575, +0.0374, +0.0497, -0.1436, +0.1622, +0.2187, +0.0257, +0.0680,
+ -0.0228, +0.0215, +0.1596, -0.0594, -0.0886, -0.0006, -0.0940, +0.1568,
+ +0.0610, +0.1915, +0.1162, +0.0765, -0.1731, -0.0258, +0.0896, -0.2285,
+ +0.0948, +0.0286, +0.1174, +0.0382, +0.2536, +0.3435, +0.0281, +0.2328
])
-weights_final_b = np.array([ -0.0680, +0.1401, -0.0628, -0.1317, +0.1489, +0.1844, -0.1147, +0.0137])
+weights_final_w = np.array(
+ [[-0.0133, +0.0628, -0.6441, +0.2383, +0.4270, +0.1927, -0.3628, +0.3698],
+ [-0.0089, +0.0614, +0.0522, -0.3912, -0.1872, -0.7369, +0.0852, -0.1505],
+ [+0.2779, +0.7024, -0.3493, -0.2124, -0.0220, +0.0741, +0.0670, -0.1029],
+ [-0.0519, +0.2775, -0.3879, -0.0335, +0.1150, +0.0789, -0.1963, +0.1992],
+ [+0.0241, +0.2946, +0.2777, -0.2040, +0.4150, +0.0810, -0.0170, -0.0202],
+ [-0.2781, +0.0243, -0.0485, +0.1249, -0.0354, -0.0327, +0.2284, -0.3674],
+ [-0.1843, +0.1452, -0.0728, +0.2894, +0.1892, +0.0013, +0.1527, -0.3815],
+ [+0.4556, -0.1760, +0.0188, -0.2475, -0.3291, -0.3527, -0.6556, -0.5543],
+ [+0.0309, +0.3396, +0.0626, -0.0045, +0.2597, -0.2234, +0.3634, -0.1476],
+ [-0.3221, +0.4484, +0.0538, +0.2543, -0.3213, +0.4323, -0.2503, +0.0654],
+ [+0.5351, -0.2229, -0.1097, +0.1062, -0.5535, +0.4454, +0.1802, +0.1971],
+ [+0.1813, +0.0778, +0.1647, -0.1118, +0.4696, -0.3322, -0.2033, -0.0201],
+ [+0.1423, +0.2278, +0.0263, +0.1439, +0.0134, -0.5282, +0.1236, -0.0416],
+ [+0.1217, +0.1197, -0.5194, +0.4029, -0.1307, -0.4352, -0.0514, -0.2256],
+ [+0.1484, +0.0685, +0.4156, +0.1887, -0.7306, +0.1027, -0.4018, +0.0134],
+ [+0.2326, +0.0218, +0.0390, +0.0010, -0.5719, +0.0264, -0.4600, -0.3220],
+ [-0.0586, -0.3066, +0.2050, +0.1253, +0.4542, +0.1711, -0.6051, +0.0061],
+ [+0.0108, -0.5588, -0.3976, +0.3375, +0.3065, +0.2118, -0.4879, +0.1444],
+ [-0.1443, -0.2895, -0.3992, +0.0409, +0.3109, -0.0295, -0.2016, -0.3679],
+ [-0.2630, +0.2348, +0.2592, +0.1778, -0.1501, -0.2856, +0.3477, +0.1416],
+ [-0.3078, -0.3138, +0.2040, -0.3254, +0.2891, +0.0228, -0.3580, +0.2438],
+ [-0.0035, -0.1374, +0.9035, +0.1420, +0.1437, -0.1159, -0.1822, +0.2037],
+ [+0.2533, -0.0089, -0.1549, +0.1085, -0.5376, -0.0639, +0.3232, +0.0673],
+ [-0.1033, +0.2733, +0.1426, +0.4075, -0.1140, +0.1152, +0.2189, +0.7337],
+ [+0.0682, -0.1010, +0.2224, +0.4526, +0.0599, +0.1290, -0.5523, +0.0333],
+ [+0.1089, -0.1139, -0.0310, -0.2661, +0.0781, -0.1955, -0.2610, +0.1017],
+ [+0.0011, +0.4399, -0.2365, -0.1523, -0.1508, +0.2314, +0.1414, +0.1116],
+ [+0.0014, -0.0973, +0.6542, -0.0039, -0.2656, -0.1597, +0.0158, -0.0201],
+ [-0.1700, +0.0102, +0.1321, -0.1934, -0.2208, +0.0057, +0.1504, +0.3798],
+ [+0.1586, +0.0557, +0.1042, -0.4201, +0.0613, -0.0152, -0.3855, +0.1035],
+ [-0.0969, -0.0936, +0.1289, -0.4031, +0.1148, +0.3258, +0.2017, -0.2499],
+ [+0.5422, -0.3985, -0.0758, -0.0241, +0.1124, +0.0043, -0.0495, -0.1127],
+ [+0.1679, -0.1337, -0.2102, -0.0678, +0.0768, -0.5881, +0.0327, -0.1429],
+ [+0.2756, -0.1772, -0.3729, -0.0931, +0.6402, -0.0739, -0.1221, +0.5423],
+ [-0.2310, -0.6409, -0.0729, -0.2143, +0.0735, -0.3279, -0.1317, -0.2060],
+ [-0.0864, +0.0344, -0.5635, +0.3137, -0.0566, -0.3874, -0.0119, +0.0187],
+ [+0.4066, +0.1192, +0.2065, +0.0546, +0.2182, +0.6743, +0.2802, -0.0638],
+ [+0.2526, +0.6688, -0.0943, -0.2531, +0.1259, +0.1115, +0.0581, -0.0340],
+ [+0.1820, +0.2927, -0.2457, +0.0310, -0.3335, -0.5889, +0.0088, +0.3045],
+ [+0.0072, -0.0702, +0.1246, +0.0875, +0.0488, +0.2379, -0.1760, -0.5422],
+ [+0.1416, +0.1796, -0.7311, +0.0016, -0.4996, +0.0724, -0.4854, +0.2310],
+ [-0.5525, +0.1246, +0.8667, +0.3521, -0.7227, +0.4473, +0.0805, -0.1707],
+ [-0.3557, +0.0798, +0.5322, -0.0827, +0.1836, +0.2784, -0.1676, -0.1012],
+ [-0.6738, +0.5545, -0.3111, +0.2171, -0.3377, -0.2039, -0.1205, +0.1212],
+ [-0.2249, -0.1037, -0.4715, -0.3616, +0.2250, +0.0999, +0.4772, -0.0679],
+ [-0.4895, -0.2557, +0.0892, -0.0000, -0.4443, +0.2913, -0.0450, -0.3303],
+ [-0.2729, +0.0973, +0.2516, -0.4313, -0.1743, -0.2386, -0.1142, -0.0440],
+ [-0.6820, +0.2449, -0.1079, +0.3047, +0.0325, -0.0980, +0.1868, -0.1600],
+ [-0.2085, -0.2897, -0.4539, -0.0506, +0.1225, +0.1976, -0.2360, +0.6553],
+ [+0.5299, +0.2876, +0.2354, -0.0884, -0.1821, +0.3841, -0.0701, +0.0278],
+ [-0.1594, -0.4837, +0.1483, -0.1280, +0.0962, -0.1932, +0.1730, +0.0544],
+ [+0.2879, -0.1846, +0.1474, -0.3383, +0.1483, +0.1159, +0.3761, +0.2326],
+ [-0.0960, -0.0727, -0.3099, +0.0548, +0.2339, -0.2232, +0.6066, +0.3826],
+ [-0.0171, +0.1490, -0.3324, -0.0231, +0.0700, -0.6364, -0.1944, +0.3094],
+ [+0.0804, -0.0278, +0.0182, -0.3807, -0.3628, -0.3564, +0.2279, -0.0226],
+ [+0.4219, +0.0741, +0.1299, +0.4700, +0.1927, +0.0849, -0.1574, +0.5607],
+ [+0.0810, -0.0815, +0.1356, +0.2048, -0.1404, -0.0222, -0.2464, +0.4991],
+ [+0.3000, +0.0862, -0.3917, +0.4117, +0.0306, +0.0788, -0.0403, -0.6423],
+ [-0.2445, +0.4847, +0.0478, -0.2170, -0.3700, +0.0189, +0.0001, -0.0335],
+ [+0.3710, -0.0115, -0.4207, -0.4245, +0.2041, -0.0875, -0.2369, -0.6424],
+ [-0.3608, +0.0539, -0.3928, -0.0352, +0.2832, +0.1003, -0.0082, +0.3201],
+ [+0.2221, -0.0399, +0.2092, -0.1670, -0.5146, +0.2273, +0.3011, -0.2879],
+ [+0.1500, +0.3236, +0.1295, -0.0763, -0.2708, +0.6542, +0.1379, -0.0646],
+ [+0.1291, +0.0417, +0.1386, +0.0166, +0.1373, +0.1956, +0.4986, +0.5690]])
+
+weights_final_b = np.array(
+ [-0.0680, +0.1401, -0.0628, -0.1317, +0.1489, +0.1844, -0.1147, +0.0137])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py
index 1b68afd6f..50eacc552 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HalfCheetahBulletEnv_v0_2017may.py
@@ -2,293 +2,2120 @@
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], 128)
- assert weights_dense2_w.shape == (128, 64)
- assert weights_final_w.shape == (64, 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], 128)
+ assert weights_dense2_w.shape == (128, 64)
+ assert weights_final_w.shape == (64, 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("HalfCheetahBulletEnv-v0")
- env.render(mode="human")
+ env = gym.make("HalfCheetahBulletEnv-v0")
+ env.render(mode="human")
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
- #disable rendering during reset, makes loading much faster
- env.reset()
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ #disable rendering during reset, makes loading much faster
+ env.reset()
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ obs = env.reset()
while 1:
- frame = 0
- score = 0
- restart_delay = 0
- obs = env.reset()
- while 1:
- time.sleep(1./60.)
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- score += r
- frame += 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
+ 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.4105, +0.5540, +0.2791, +0.4953, -0.0309, +0.8480, +0.1630, +0.0630, +0.7107, +0.0597, +0.2675, -0.1931, -0.2436, +0.2909, +0.3563, +0.4564, -0.0445, -0.2228, +0.7005, +0.8368, +0.3631, +0.7365, +0.2453, +0.4687, +0.4819, +0.4940, +0.5096, +0.5929, +0.5504, +0.2265, +0.4118, +0.5993, +0.2402, -0.5087, -0.0756, +0.7520, -0.0086, -0.0648, +0.0564, -0.0812, -0.0093, +0.8482, +0.7333, +0.4401, -0.1273, -0.2974, +0.1284, -0.4948, +0.1120, +0.7938, +0.1297, +1.0807, +0.2480, +0.2444, +0.4258, +0.1515, -0.0126, +0.3098, -0.2786, +0.4913, +0.3065, +0.3356, +0.6884, +0.3117, +0.3163, +0.4234, +0.1172, +0.8810, +0.3574, -0.3993, -0.5597, +0.2233, +0.8058, +0.3391, -0.1113, +0.1884, +0.1324, +0.0503, +0.1807, +0.0441, -0.2065, +0.1978, +0.0852, -0.3531, +0.2180, +0.7946, -0.0318, +0.0650, -0.3174, -0.1715, -0.0486, +0.2131, -0.3901, +0.1995, +0.8593, +0.1786, +0.3595, +0.7852, +0.3491, -0.4206, +0.6117, -0.1991, +0.1876, -0.3114, -0.2007, -0.2738, -0.0388, +0.0465, +0.2726, -0.5321, +0.4720, -0.0555, +0.3415, +0.1447, -0.1132, -0.2958, -0.6729, -0.5003, -0.4960, -0.2600, -0.4158, -0.4476, -0.8244, -0.0574, +0.2194, +0.0541, -0.3526, -0.1131],
-[ -0.2662, +0.1763, +0.0520, +0.3624, +0.0564, +0.2756, +0.0743, +0.0155, +0.1861, -0.5311, +0.2181, -0.3643, +0.1433, +0.1801, -0.1781, -0.3576, -0.2487, +0.0588, +0.3906, -0.3994, +0.1343, +0.2701, +0.1613, +0.1962, -0.0277, +0.0303, +0.0845, -0.1033, -0.1092, -0.1026, -0.2261, +0.3324, +0.1881, -0.2780, -0.0865, -0.2131, -0.1238, -0.1727, +0.1086, +0.1383, +0.1794, +0.0677, -0.0582, -0.0758, +0.0834, +0.0847, +0.0945, +0.1888, -0.0696, +0.0111, -0.0028, +0.0439, -0.3847, -0.1564, -0.2226, +0.0002, +0.0926, -0.2819, -0.0868, +0.2233, +0.0738, +0.1671, -0.0326, +0.3784, -0.0117, +0.0836, +0.0285, +0.0376, +0.0157, +0.1297, +0.0556, -0.0533, -0.0103, +0.0740, -0.1825, -0.2399, -0.0609, -0.0030, +0.1811, -0.2784, -0.2249, +0.3637, +0.1895, +0.3102, -0.0767, +0.1143, -0.0840, +0.2981, -0.3040, +0.0135, +0.2495, +0.0036, -0.1493, -0.1144, -0.0006, +0.1195, +0.0961, -0.4227, -0.3022, +0.2102, +0.2024, -0.2111, +0.1507, +0.2948, -0.1822, +0.2263, -0.3213, +0.0380, -0.1188, +0.1237, +0.0731, +0.0044, -0.1637, -0.3173, +0.0895, -0.0130, +0.0703, -0.2186, +0.1401, +0.1191, +0.0225, -0.3208, -0.0578, -0.3113, +0.1041, -0.1957, -0.3054, -0.0797],
-[ +0.3485, -0.3161, -0.4092, +0.1190, -0.5706, -0.3627, +0.0576, -0.1068, +0.1367, +0.1686, +0.0284, -0.1694, -0.0496, -0.1647, +0.0111, -0.1897, -0.4613, -0.5996, -0.0601, -0.1417, -0.0236, -0.0898, +0.1239, -0.2693, -0.1709, +0.3592, -0.1284, -0.0376, -0.1308, -0.1832, -0.0538, -0.0467, -0.1181, -0.0994, -0.3281, +0.0527, -0.4579, -0.1062, -0.1058, -0.4459, -0.0901, -0.0246, -0.1125, +0.1228, -0.3428, -0.3385, +0.0366, -0.0988, +0.1345, +0.0299, +0.2921, -0.1347, +0.1688, -0.1350, -0.0888, +0.0734, -0.0936, -0.2695, +0.0154, +0.0237, -0.1334, -0.3247, -0.1856, -0.0449, -0.0772, +0.0176, -0.0856, -0.1746, -0.1575, -0.2365, -0.0741, -0.1638, +0.0864, -0.0243, -0.0472, +0.0423, -0.2962, -0.2523, -0.1430, +0.1470, -0.1122, -0.1843, -0.1437, -0.1895, +0.1110, -0.2572, -0.3307, -0.2597, -0.4706, -0.2441, -0.2988, -0.5409, -0.1696, +0.0810, -0.2336, -0.0925, +0.4226, +0.1162, -0.3211, -0.2118, -0.3100, -0.1384, +0.1625, +0.0005, -0.1936, +0.2836, +0.1660, -0.2154, +0.1341, -0.2413, -0.1203, -0.3427, +0.0863, +0.1393, -0.3580, +0.1443, -0.2158, -0.4703, -0.2687, -0.0573, +0.1099, -0.2551, -0.0506, -0.3351, -0.2325, -0.0119, -0.0907, -0.0628],
-[ +0.0565, +0.2158, +0.1461, +0.1045, -0.3548, -0.2816, -0.0124, -0.0931, +0.1249, +0.0093, -0.3325, -0.1646, +0.3022, -0.0509, -0.1403, +0.3703, +0.2642, +0.0835, +0.1347, +0.1734, -0.0112, +0.3162, -0.0076, +0.1258, -0.2059, +0.2387, +0.0775, -0.1653, -0.3899, -0.1205, -0.2263, +0.2800, -0.1979, +0.1708, +0.0505, -0.0998, +0.1838, -0.1314, -0.1932, -0.1897, -0.3157, -0.0113, -0.3488, +0.1534, -0.3546, -0.1098, +0.0652, -0.1327, -0.0131, +0.3698, -0.0927, +0.1735, -0.4869, +0.1768, -0.0187, -0.1069, -0.2118, -0.2557, -0.1380, -0.0579, -0.2147, +0.3389, -0.1801, +0.1954, -0.2856, +0.0825, +0.1846, -0.2102, +0.4063, -0.0422, +0.1645, -0.2313, -0.2017, -0.2554, +0.1597, -0.1198, +0.4493, +0.1135, +0.1556, -0.0380, +0.0527, -0.0505, -0.5094, -0.4410, +0.2543, +0.2891, -0.0031, -0.0863, +0.2982, +0.1069, -0.4814, +0.0295, -0.0547, +0.0518, -0.4326, -0.0295, -0.3795, +0.0399, +0.0363, +0.1623, +0.4509, +0.2852, -0.4404, +0.0109, -0.0394, +0.0092, -0.1684, +0.4728, -0.1317, +0.0575, -0.3862, -0.1313, +0.0676, +0.1321, -0.2816, -0.0500, -0.0027, +0.0906, +0.0297, -0.1476, +0.0337, +0.0911, -0.1591, +0.2816, -0.0435, -0.3437, -0.0732, -0.4545],
-[ -0.2090, -0.1890, -0.4459, +0.0942, +0.2823, -0.0085, -0.1576, -0.5515, +0.1211, -0.0689, +0.2807, +0.1457, +0.2009, -0.2739, +0.0296, -0.0511, -0.1048, -0.1275, +0.2358, +0.3103, +0.2239, +0.2028, -0.0858, +0.0520, -0.1453, +0.2013, -0.2131, -0.0596, -0.0469, -0.0934, -0.2082, +0.2071, -0.5051, +0.1719, -0.1380, -0.2781, -0.0598, -0.1636, +0.2784, -0.0144, +0.0655, -0.1932, +0.1421, -0.0840, -0.0277, -0.2310, -0.0509, +0.0870, +0.0721, -0.1785, +0.1514, -0.1485, -0.1158, +0.1124, -0.1155, -0.4105, -0.1765, +0.0103, -0.1695, +0.0521, -0.1132, -0.1209, -0.1313, -0.0419, +0.1828, -0.1026, +0.0564, +0.0095, -0.0414, +0.1264, +0.1588, -0.2200, +0.1928, -0.2098, +0.4256, -0.3453, -0.3882, -0.2238, -0.1347, +0.2160, +0.4278, -0.2666, -0.1046, +0.2501, +0.0238, +0.2802, -0.3955, +0.1452, +0.1773, -0.0727, -0.3603, -0.2480, -0.0412, +0.2462, +0.2148, -0.2819, +0.0982, -0.0102, +0.0310, +0.0147, +0.0597, +0.0514, -0.0032, +0.1320, -0.0606, -0.0637, +0.0398, +0.1367, +0.0646, -0.0435, +0.0527, +0.1258, -0.2075, -0.1816, -0.2129, -0.1253, +0.2394, -0.2325, -0.1115, -0.4115, -0.1196, -0.2855, +0.3805, -0.2741, -0.0278, -0.3461, +0.0139, -0.0499],
-[ -0.6025, +0.2692, +0.5276, +0.3615, -0.3196, +0.3828, +0.1312, -1.1323, -0.0073, -0.1227, -0.0831, +0.0605, -1.0515, -0.1917, -0.2510, +0.2964, -1.1074, -0.1708, -0.4475, -0.1189, +0.3345, +0.5101, +0.4628, +1.1872, +0.5829, +0.0234, +0.0306, +0.0021, -0.1827, -0.0257, -0.2993, +0.0083, -0.9032, -0.0311, +0.0045, +0.6173, +0.3095, -0.1490, -0.2561, +0.2011, -0.1550, -0.1936, +0.0729, +0.7613, -0.9194, +0.1954, +0.0306, +0.2292, +0.1529, -0.1161, -0.0182, -0.2625, -0.3142, -0.9182, +0.2761, +0.3656, +0.3537, +1.0318, -0.4273, +0.1703, -0.2378, -0.4640, +0.6184, +0.3686, -0.3043, -0.4850, -0.2155, -0.6656, +0.1921, -0.2552, -0.8096, +0.8593, -0.3583, -0.0332, -0.5619, +0.2977, -0.3425, -0.7839, -0.4299, -0.2358, +0.0526, -0.0752, -0.6535, +0.0501, -0.4043, +0.8261, -0.4269, -0.1165, +0.3480, -0.2337, -0.3269, -0.2775, +0.7307, +0.5863, -0.1005, -0.3421, +0.1591, +0.4530, -0.1228, -1.0896, +0.6218, -0.0610, -0.1239, -1.5883, -0.1711, -0.4331, -0.3553, +0.0773, +0.3669, -0.5690, +0.7117, -0.2021, -0.1426, -0.1125, +0.0364, +0.2397, -0.1739, -0.3131, -0.9135, -0.7713, -0.0638, -0.3219, +0.0353, +0.3407, -0.0035, -0.1492, -0.1118, -0.4841],
-[ -0.0175, -0.3710, +0.0894, +0.2056, -0.2250, +0.0982, +0.0039, -0.2128, -0.0479, +0.3049, +0.2228, -0.1747, -0.0936, +0.1146, +0.1377, +0.0127, +0.0014, +0.1374, +0.1557, -0.1890, -0.2396, +0.2248, +0.1710, -0.2916, +0.4568, -0.0645, -0.0760, -0.2067, -0.3900, +0.0276, -0.3171, -0.0148, +0.2019, -0.1335, -0.0731, -0.3224, +0.0859, +0.2299, +0.0602, +0.0499, -0.2686, +0.1028, +0.1204, +0.0321, +0.0636, -0.1350, -0.1789, -0.0529, -0.2255, +0.1867, +0.1258, +0.1392, -0.2657, +0.1478, +0.1961, -0.0687, +0.1878, +0.2016, -0.2413, +0.0050, -0.0666, -0.0226, -0.0185, +0.4750, -0.1661, +0.0637, -0.2668, +0.1875, +0.0032, +0.1176, +0.1844, -0.1665, -0.1806, -0.3208, +0.0606, -0.0122, +0.2792, +0.1867, +0.1424, +0.2775, +0.1074, -0.2996, +0.0562, -0.1864, +0.1985, +0.1356, -0.3013, -0.0824, -0.1534, -0.0795, -0.0086, -0.0490, -0.0861, -0.0986, +0.3499, -0.0630, +0.0028, -0.1540, +0.0377, -0.1057, +0.1303, +0.1379, -0.1257, -0.2578, -0.0744, -0.1304, +0.0411, -0.1635, +0.0535, +0.0271, +0.1674, +0.1309, -0.0397, -0.1127, -0.2217, +0.0548, -0.5178, +0.1170, +0.4857, +0.1134, +0.0598, +0.1467, +0.1405, -0.1152, +0.1825, -0.0382, +0.1325, +0.2708],
-[ -0.1185, -1.2480, -0.6130, -0.9105, +0.1073, -0.7702, -1.2908, +0.6513, -0.3928, -0.7365, -0.2977, +0.7845, +0.3186, +0.2207, -1.1391, -0.9353, +1.1582, -0.7291, +0.2077, +0.2808, -0.5894, +0.4805, -0.2316, -0.8861, -0.4102, -1.1704, +0.9183, -0.0637, -0.1935, -0.2971, -0.6144, +0.6113, +0.1596, -0.2931, +0.3199, -0.2938, -0.2098, +0.3615, -0.3433, +0.0334, +0.2148, -1.9070, -0.0655, -0.5875, +0.5659, +0.0436, +0.5074, +0.5399, -0.2164, -0.7224, -0.1556, -1.3397, +0.5629, +0.1272, -0.1749, -1.2117, +0.9305, -0.9436, -0.9450, -0.4745, -0.9840, -0.5153, -0.1703, -0.5252, -0.0291, +0.3351, +1.0137, -1.4468, +0.1594, +0.4054, +0.9667, -0.3279, -1.2628, -0.6361, -0.1322, -0.4219, -0.8181, +0.1316, +0.3924, +0.4478, +0.5855, -0.0547, -1.4541, +0.1199, -0.2794, -0.9176, +0.8841, +0.2706, -0.1612, +0.7667, -0.3909, -1.6514, +0.1562, -0.3166, -0.2654, +1.0692, -0.1898, -1.3619, +0.0357, +0.6267, -0.0957, -0.5473, -0.9002, +0.4248, +0.7671, +0.6034, +0.1176, +0.4126, -0.4076, +0.5846, -0.4275, +0.0146, +0.5074, +0.4825, +0.3414, -0.0289, +0.5663, +0.9628, +0.9791, -0.1043, +1.2530, +1.3600, +1.6041, +0.4200, -0.2415, -0.4470, +0.6965, +0.2395],
-[ +1.2479, -0.0619, -0.4174, -0.2800, +0.2902, +0.2310, +0.0858, -0.0805, +0.2556, +0.8018, -0.1018, +0.9876, +0.2342, +0.3219, +0.3031, -0.1343, +0.0737, +0.2219, -0.6479, -0.4475, +0.3711, +0.4780, -0.8735, +0.6208, -0.3031, +0.1480, +0.4935, +0.9053, +0.0797, -0.3932, +0.0853, -0.4709, -0.6192, +1.1604, -0.0924, -0.2548, +0.5836, +0.0325, -0.2435, -0.1506, -0.1754, -0.2248, -0.8059, -0.1997, +0.7772, +0.1456, -0.1463, -0.0360, -0.0240, -0.1852, -0.1289, +0.9165, -0.2434, +0.7580, +0.3838, -0.0338, +0.1199, -0.1700, -0.4038, -0.1863, +0.0925, -0.2396, +0.4659, +0.1810, +0.6990, +0.2880, +0.0641, -0.3991, +0.6049, -0.5948, -0.1894, -0.7874, -0.6910, +0.0824, +0.5111, -0.2513, +0.4632, +0.7014, -0.6793, +0.0562, -0.0800, +0.2665, -0.0270, +0.1830, +0.8184, +0.5293, -0.3352, +0.1144, +0.7672, -0.0924, +0.2099, -0.0854, -0.1534, +0.2607, -0.1140, -0.1163, +0.0403, +0.2623, +0.4065, +0.9303, +0.4008, -0.1773, +0.0368, +0.4014, -0.6941, +0.0333, +0.3245, +0.0262, +0.7663, +0.3834, +0.4088, +0.0289, -0.6102, +0.5717, -0.0787, +0.2367, +0.2061, -0.3039, -0.0797, +0.0814, +1.2009, +0.4369, +0.0788, +0.2358, +0.9926, +0.5428, -0.5656, -0.2758],
-[ +0.3487, +0.2086, -0.0813, +0.4360, -0.2904, +0.4395, +0.1773, +0.0481, +0.4503, +0.4991, +0.3741, +0.1866, -0.2241, -0.3511, +0.2302, +0.5140, +0.5208, +0.5968, +0.5189, +0.2814, +0.3372, +0.3461, +0.0298, +0.0069, -0.1004, +0.5782, -0.2609, +0.1167, -0.5090, -0.3220, +0.0509, +0.4076, -0.1667, +0.2021, -0.0495, +0.2189, -0.0504, -0.3792, -0.4321, +0.0364, -0.0175, -0.0359, +0.0965, +0.3641, -0.2778, -0.1170, +0.7745, -0.2177, +0.1121, +0.0240, +0.6502, +0.1845, -0.0903, +0.3065, +0.0884, +0.4046, -0.2021, -0.3310, +0.0056, -0.2555, +0.0209, +0.5952, -0.1765, +0.0503, -0.0449, +0.2059, +0.2699, -0.2488, -0.6611, +0.2942, -0.4384, +0.3329, +0.4411, -0.1499, -0.0820, +0.5042, +0.2737, -0.3949, +0.4931, +0.0065, -0.8717, -0.4590, +0.1508, +0.3686, +0.1564, -0.2887, -0.3002, -0.0485, +0.0003, -0.4201, -0.0104, +0.2674, +0.1690, +0.1299, -0.0258, -0.0109, +0.6633, +0.3255, -0.0330, +0.4770, +0.3560, +0.1506, +0.3608, +0.4205, +0.0090, -0.3770, +0.2320, -0.2200, +0.0256, -0.2081, -0.1292, +0.0661, -0.3286, +0.1211, +0.1542, +0.5790, +0.0675, -0.1831, -0.0903, +0.0403, +0.1506, -0.2725, +0.1505, -0.3582, -0.2939, -0.3307, -0.2906, -0.1859],
-[ +0.6120, +0.3881, -0.2144, +0.0539, +0.2717, +0.0574, -0.6547, -1.1043, -0.4978, +1.0026, -0.2662, -0.3964, -0.4590, +0.5876, +0.3651, +0.2121, -0.3029, +0.4225, -0.2654, -0.0867, -0.0286, +0.4754, +0.5950, -0.0923, +0.5628, -0.1033, -0.1225, -0.5554, -0.9027, -0.3767, -0.7881, -0.0124, -0.6633, -0.7063, +0.4806, -1.2205, -0.1279, +0.0321, +0.3928, +0.0134, +0.3143, -0.5378, +0.0553, +0.1611, +0.0254, -0.4512, +0.7660, +0.4550, +0.6917, +0.0186, +0.1970, -0.4484, +0.4214, +0.5640, +0.7182, -0.6329, +0.3644, -0.5340, -0.0268, -0.3028, +0.4847, -0.1190, -0.3030, +0.4755, +0.1916, -0.1579, -0.1899, -0.1830, +0.2239, -0.8405, -0.0194, -0.4524, -0.6924, +1.0233, -0.1682, -1.0005, -0.1989, +0.0655, -0.5738, +0.3489, -0.2032, -0.5767, +0.2677, -0.2104, +0.9164, -0.6995, +0.3138, +0.2631, +0.4646, -0.7949, -0.4088, +0.0390, +0.5322, +0.8076, +0.3327, -0.8003, -0.4473, +0.2003, -0.0771, +0.9627, -0.5091, +0.5703, -0.3930, +0.3132, +0.9709, +0.2298, +0.2046, -0.4682, -0.4135, +0.8331, -0.0837, -0.2126, -0.2461, -0.6451, -0.3118, +0.1340, +0.3047, -0.3990, +0.8511, -0.0305, +0.7664, +0.2561, +0.5513, +0.2083, -0.7912, -0.5125, -0.5167, -0.5089],
-[ +0.2836, +0.6191, -0.2299, +0.4317, +0.1775, -0.6181, +0.0461, +0.0362, +0.0559, +0.7882, -0.1351, -0.3722, +0.1090, +0.0281, +0.1148, +0.7799, -0.2107, -0.3900, -0.2063, -0.3643, +0.7287, -0.2938, +0.1283, -0.1046, +0.0992, -0.1031, +0.6297, -0.8027, -0.0918, +0.2503, +0.5527, +0.3296, -0.0083, -0.1686, +0.0065, +0.2643, +0.1768, -0.4890, +0.0692, +0.5517, +0.6225, -0.0423, -1.0015, -0.5841, -0.2217, -0.6242, -0.1942, -0.3841, +0.7571, +0.4939, -0.2331, +0.1612, +0.0843, +1.2429, -0.2966, -0.5344, +1.0299, -0.7019, -0.1317, -0.0856, +0.2293, -0.0003, -0.0487, -0.5326, +0.0300, +0.5683, +0.2054, -0.3269, +0.6114, -0.5650, -0.1812, -0.8703, +0.0364, +0.6392, -0.7844, +0.0227, +0.6228, +0.5272, -0.8685, -0.4089, -0.3416, -0.1562, +0.1535, -0.0063, +0.6183, -0.5915, -0.1640, -0.2188, +0.4079, -0.3470, +0.5118, +0.4866, -0.9074, -0.0650, +0.3942, -0.1759, -0.3695, +0.1913, +0.9200, +0.2702, -0.2663, +0.1217, -0.1575, -0.2490, +0.1515, -0.7135, +0.4985, +0.1606, -0.1133, -0.2688, -0.4154, -0.5524, -0.0633, -0.0389, +0.4926, -0.0719, -0.3427, -0.6053, -0.1829, -0.5910, +0.1137, +0.0312, +0.4532, +0.1142, +0.3834, -0.0407, -0.5945, -0.6180],
-[ +0.0362, -0.5185, -0.3235, +0.0613, +0.3283, +0.6853, -0.3136, +0.4028, +0.2535, +0.0223, +0.1985, -0.9784, +0.8819, -0.4328, -0.1815, +0.2478, -0.1824, -0.0182, +0.3654, -0.2296, +0.3019, -0.1017, +0.5535, +0.2589, -0.4000, +0.0137, -0.4569, +0.4085, +0.3198, +0.1833, -0.2268, +0.1447, +0.3493, +0.4606, -0.2277, -0.0773, -0.6224, +0.8234, +0.0221, +0.5623, -0.1428, -0.5706, +0.5371, +0.8732, -0.5540, -0.0395, +0.8031, +0.3599, +0.5903, +0.0713, -0.1844, +0.5461, +0.1745, +0.1545, -0.2652, -0.0803, +0.2160, -0.4186, -0.3271, +1.0229, -0.0675, +0.0257, +0.3415, +0.1843, -0.4467, +0.0753, +0.3914, -0.0426, +0.2589, -0.2688, -0.2011, -0.0360, -0.2472, -0.4691, +0.1115, -0.3416, +0.1560, -0.1638, -0.3131, -0.3056, +0.1102, +0.0386, -0.0213, +0.0334, +0.5400, +0.3385, +0.0520, +0.2917, +0.0586, +0.3761, -0.2422, -0.4576, -0.0317, +0.2312, +0.7176, +0.2603, -0.1864, -0.3297, -0.3581, +0.3024, +0.4191, +0.1382, -0.4671, -0.1097, +0.3002, +0.1556, +0.3214, +0.0859, +0.2674, -0.0762, +0.1793, +0.8109, +0.5113, +0.0960, +0.2222, +0.2567, -0.0165, +0.8895, -0.0689, -0.1649, +0.5046, +0.1555, +0.2201, -0.2468, -0.5657, -0.5523, -0.7054, -0.2129],
-[ +0.0779, -0.1795, -0.3084, +0.0991, +0.0959, -0.0223, +0.3783, +0.3527, -0.2872, +0.3394, +0.0425, -0.0484, -0.2041, +0.9751, -0.2537, +0.0812, +0.2257, +0.4729, +0.4647, +0.4171, +0.0146, -0.1489, +0.5499, +0.4513, -0.2661, -0.8428, +0.3146, -0.1790, +0.0097, -0.1133, +0.0693, +0.3234, +0.0583, -0.6285, -0.7520, -0.2485, -0.5776, +0.6696, -0.2599, -0.0951, -0.2328, -0.5490, +0.5175, +0.0767, -0.3109, -0.2104, +0.1518, -0.5617, +0.0181, +0.2775, +0.0589, +0.3021, -0.8439, -0.0653, -0.4131, -0.4757, +0.6912, -0.0174, -0.3354, +0.5238, -0.2113, +0.0943, -0.1804, +0.0211, +0.5478, +0.5479, +0.3961, +0.0754, +0.0795, -0.2051, -0.1059, -0.2414, +0.0145, +0.6187, +0.1991, +0.1538, -0.5956, -0.0687, -0.1066, +0.5816, +0.3722, -0.3560, +0.4422, +0.4901, +0.5202, -0.1284, +0.6292, +0.8110, +0.5204, -0.2698, -0.1241, -0.0359, -0.0064, -0.3268, +0.7780, -0.3028, +0.1004, -0.0382, -0.4620, +0.2837, -0.8406, -0.2417, +0.2056, +0.0777, -0.2286, +0.0642, +0.5493, -0.8877, -0.1941, +0.3304, +0.4645, -0.4799, -0.2487, +0.2221, +0.7077, +0.2539, -0.1791, +0.2926, +0.1322, +0.0905, +0.1544, -0.2086, +0.3299, -0.0308, -0.0567, +0.1242, -0.0968, +0.4553],
-[ -0.2603, -0.4800, +0.0541, -0.8000, -0.6535, -0.8949, -0.3607, -0.0667, -0.7336, -0.3965, +0.3150, +0.1505, -0.3550, -0.1260, +0.3011, -0.0821, -0.3796, -0.1918, -0.3090, +0.0550, +0.1061, -0.3667, -0.8571, -0.4193, -0.4680, -0.3205, +0.2565, -0.3090, -0.2638, +0.1026, -0.1909, -0.5068, +0.0748, -0.4648, +0.0748, -0.2874, +0.2573, -0.1646, -0.1574, +0.1782, -0.2502, +0.1568, -0.1522, -0.5577, +0.5309, +0.1850, -0.1607, +0.2624, +0.0171, +0.2342, -0.8137, +0.2716, -0.1085, -0.4303, -0.5537, -0.0020, -0.0393, -0.3333, +0.2081, -0.0905, -0.6573, +0.1222, -0.4209, -0.3416, -0.2223, +0.5376, -0.0664, +0.2956, +0.4846, +0.5470, +0.3633, -0.2415, -0.6977, -0.4417, -0.1011, -0.4229, -0.1614, -0.0722, -0.4239, -0.2685, +0.4363, +0.1485, -0.0346, -0.1507, +0.0344, -0.0586, -0.1486, +0.1647, -0.0353, +0.3965, +0.1495, -0.1808, -0.3812, -0.3466, -0.6642, -0.1044, -0.6627, -0.3414, -0.3478, -0.0244, -0.0663, -0.2007, -0.3840, -0.6573, -0.4302, +0.0623, +0.0473, -0.1558, -0.5837, +0.1068, -0.1332, -0.0385, -0.0638, -0.7497, -0.1423, -0.3235, -0.2541, -0.2405, +0.3238, -0.1456, +0.2076, +0.1714, +0.0112, +0.3124, +0.0782, +0.1887, +0.3277, +0.1156],
-[ -1.0948, -0.2236, +0.1540, -0.6062, -0.2097, -0.2825, -0.4756, +0.3731, -0.5436, -0.3209, -0.3609, -0.1703, -0.6188, +0.0140, -0.0252, +0.5627, +0.0186, +0.1253, -0.0046, +0.0767, -0.2195, +0.3782, -0.1052, -0.1369, +0.3583, -0.5566, +0.6542, -0.3200, +0.2563, -0.1301, +0.0185, -0.8119, +0.5848, +0.4946, -0.0112, +0.1033, +0.1308, -0.1700, +0.1149, +0.3101, -0.3001, +0.2433, +0.2101, +0.1298, -0.1548, +0.1310, -0.2388, +0.3923, +0.9332, +0.5030, -1.0263, -0.1072, +0.1241, -0.0134, -0.0806, -0.3525, +0.5211, -0.0752, +0.0334, +0.2871, -0.4669, -0.2720, -0.0067, +0.1326, -0.4609, -0.0674, -0.6579, -0.2538, +0.2333, +0.4456, +0.5642, -0.1694, -0.3706, +0.5684, -0.7867, -0.4995, +0.3289, -0.6711, -0.1191, -0.8581, +0.3775, +0.8927, +0.5052, -0.0896, +0.0121, +0.6358, +0.1183, +0.5200, +0.7512, +0.0846, -0.1086, -0.0426, -0.0155, +0.6603, +0.0812, +0.4987, +0.0256, +0.0992, +0.2730, -0.0697, +0.2773, -0.7570, -0.7726, -0.3871, -0.3158, -0.3692, -0.7297, -0.0744, -0.5920, +0.6132, -0.0072, +0.1400, -0.1782, -0.0227, +0.1123, -0.6036, -0.6343, +0.5520, +0.3165, -0.4080, -0.0338, -0.1839, -0.0071, +0.3603, -0.3050, +0.4097, -0.5939, -0.1245],
-[ -0.3346, -0.2795, +0.2751, +0.2150, +0.4031, +0.5422, +0.3587, +0.5206, -0.6544, +0.1672, -1.0438, -0.3010, +0.6246, +1.1339, -0.6914, -0.1198, +0.0050, -0.8139, -0.1150, +0.9000, -1.1849, +1.0507, -0.2149, -0.3482, -0.7118, +0.3377, +0.2528, +0.2764, +0.2596, -0.4997, -0.8768, +0.4370, -0.0810, +0.1831, -0.0584, +0.0562, +0.4426, -0.4548, -0.6110, -0.3985, -0.0168, -0.5126, +0.5279, -0.4445, +0.0281, +0.3755, -0.0337, -0.7288, -0.4249, +0.6200, -0.1673, -0.4617, +0.0127, -0.1385, +0.6653, -0.1985, +0.4186, -0.5372, -0.5204, +0.8371, +0.2907, -0.7418, +0.0020, +0.4483, +0.1869, +0.6499, +0.1529, +0.4740, +0.6753, +0.6005, +0.7086, -0.3005, +0.5440, +0.3387, +0.2046, +0.4181, -0.8759, -0.7487, -0.1262, -0.0293, +0.8712, +0.0119, -0.7947, -1.2465, -0.0061, -0.0503, -0.2992, +0.5275, -0.3151, +0.1889, -1.5430, +0.5531, +0.2559, -0.2591, -0.2807, -0.1324, -0.7027, -0.4375, +0.1984, -0.3944, -0.0467, -0.3111, -0.6493, -0.2939, -0.0617, +0.2605, -0.9876, -0.0857, -0.6928, +0.7228, -1.2047, +0.3026, -0.7448, +0.4988, -0.3507, -0.7106, -0.7583, +0.3245, +0.2599, -1.4422, +0.4198, -0.6388, -1.3088, +0.9680, -0.0616, -0.4120, -0.3508, +0.1672],
-[ -0.5261, +0.4924, +0.1685, -0.2603, +0.3052, +0.3751, -0.8492, -0.1073, +0.1541, +0.1367, +0.1658, +0.0405, -0.0968, -0.0074, -0.3535, -0.4133, +0.0255, -0.6547, -0.0838, +0.2996, +0.1273, -0.1657, +0.0394, +0.4691, +0.0353, -0.2699, +0.1696, +0.5037, +0.0277, -0.1267, -0.3741, +0.2501, +0.1612, -0.3687, -0.0763, -0.2902, +0.3456, +0.1048, +0.0277, +0.1918, -0.6208, +0.1135, -0.1049, -0.0283, +0.0202, +0.0171, +0.0822, -0.2369, +0.1969, +0.5290, -0.0731, +0.4711, -0.2303, -0.0833, -0.3602, -0.1438, -0.0070, -0.5158, -0.3721, +0.0134, +0.4545, -0.0207, +0.2113, -0.0665, -0.2343, +0.2490, -0.2058, +0.1182, +0.0765, +0.3709, +0.3816, -0.1490, -0.1526, -0.0174, +0.6291, +0.4946, -0.3356, -0.0425, -0.0716, -0.6482, +0.4502, +0.0332, -0.2189, -0.6447, +0.1329, +0.4471, -0.0323, -0.0798, -0.1390, +0.1446, -0.2377, +0.4462, -0.2870, -0.2893, -0.0998, +0.1104, -0.1755, +0.2786, +0.3976, -0.6894, -0.4004, -0.3018, -0.2645, +0.0620, +0.0661, +0.1230, -0.3739, +0.0862, -0.2077, -0.1822, +0.0729, +0.0871, -0.2029, +0.0181, +0.3299, -0.5234, +0.0010, +0.1996, +0.0403, -0.6255, +0.1214, +0.0402, -0.3186, +0.1235, +0.0944, +0.2717, +0.1232, -0.3457],
-[ -0.1970, -0.3969, -0.2225, +0.1993, +0.1553, -0.0254, -0.1890, -0.3057, +0.4549, -0.0170, -0.5648, -0.4915, -0.0502, -0.2149, +0.2144, -0.5744, -0.1044, -0.4353, +0.0233, -0.0785, -0.3143, -0.3626, +0.0585, -0.3341, -0.0893, -0.4231, -0.0378, +0.0274, -0.4611, +0.0728, -0.1463, -0.2042, +0.0172, -0.4561, -0.0206, -0.1719, -0.0000, -0.4023, +0.0364, -0.1958, -0.5589, -0.0532, +0.0099, -0.0872, +0.0206, -0.0009, -0.3550, -0.3123, -0.0938, -0.2254, -0.1686, -0.2615, -0.2844, +0.0994, +0.0554, +0.1692, -0.2632, -0.1443, -0.1879, -0.1459, -0.6597, -0.3367, -0.1862, -0.3134, +0.1299, -0.0695, +0.2293, +0.0609, +0.2819, -0.1567, -0.2090, -0.1359, +0.3011, -0.2784, -0.2469, +0.0022, -0.1715, -0.1446, -0.2693, -0.3637, -0.1232, -0.2147, -0.2098, +0.0446, +0.1409, -0.0058, +0.0383, -0.1855, -0.1377, +0.0460, -0.2215, +0.3805, -0.2653, -0.1465, -0.4812, -0.0015, +0.0714, +0.0472, -0.2914, -0.2133, -0.1082, -0.8207, +0.1838, -0.1654, -0.6285, -0.5248, +0.0549, -0.1583, -0.5096, +0.1266, -0.5755, -0.3374, +0.0946, -0.3824, -0.4274, +0.1813, -0.3312, +0.1190, -0.2241, +0.0402, +0.2119, +0.1831, -0.0826, -0.1367, -0.2986, -0.4726, -0.5516, -0.0995],
-[ -0.5413, +0.2330, +0.8049, -0.1323, +0.1069, +0.8225, +0.5138, +0.5381, +0.4208, +0.0392, -0.8431, +0.4248, -0.0927, +0.0971, -0.1803, -0.9058, +0.8480, -0.3816, -0.6984, -0.3827, -0.2599, +0.2374, -0.1889, -0.3184, -0.3037, +0.2556, -0.3310, -0.0797, -0.0166, -0.8056, +0.5743, +0.3340, -0.3261, -1.1856, -0.1586, -0.2816, -0.4614, -0.8387, -0.8821, -0.2603, -0.3087, -0.4192, +0.0168, -0.2696, +0.2092, -0.2967, -0.3088, +0.1593, -0.3350, +0.7112, +0.6204, +0.1440, -0.1400, +0.4595, +0.6284, -0.4182, +0.4677, +0.4245, -0.2426, +0.4360, +0.5265, +0.4846, +1.0185, -0.5593, +0.9728, +0.4769, +0.7221, +0.6885, -0.0294, +0.2469, +0.0124, +0.5220, -0.4949, -0.1693, +0.6676, +0.7299, -0.0920, +0.5961, -0.4980, -0.3700, +0.4610, -0.0052, -1.1549, -0.2259, -0.7090, +0.0568, +0.5237, -0.4150, +0.3867, -0.0865, -0.0347, +0.2796, -0.3372, +0.4407, +0.4653, +0.4029, +0.0542, -0.4820, +0.5448, +0.0841, +0.3830, -0.5634, +0.3101, -0.3656, +0.5915, +0.5094, +0.0265, +0.3061, -0.1867, +0.4472, +0.0831, -1.4864, +0.6205, -0.7317, +0.0345, +0.0241, -0.4189, +0.2699, -0.0454, +0.1761, +0.1418, +1.0411, -0.1500, -0.5850, +0.4274, -0.2819, -0.0049, -0.0539],
-[ +0.3625, +0.0194, -0.3223, -0.1543, -0.3422, +0.1361, -0.1979, +0.1716, +0.1964, +0.1080, -0.2562, +0.5515, -0.6231, +0.0645, -0.2820, -0.4138, -0.3513, -0.1298, +0.1236, -0.1571, +0.0996, -0.4628, -0.0855, +0.6111, +0.2735, +0.1079, +0.0759, -0.8790, +0.2145, -0.6007, -0.0575, +0.4727, -0.0139, -0.2520, -0.1913, -0.1010, +0.0459, +0.2930, -0.5473, -0.6486, +0.0525, -0.9643, +0.0756, -0.0343, -0.3489, +0.2362, +0.5423, -0.2968, -0.0831, -0.4753, -0.2939, +0.1316, -0.6055, +0.3439, -0.4793, -0.9334, -0.0404, -0.0067, -0.1639, -0.2048, +0.2024, +0.0257, -0.7722, +0.3862, +0.3280, -1.2964, +0.3508, -0.4320, -0.0618, +0.0669, -0.1487, +0.0590, -0.0657, -0.5083, -0.3131, -0.3795, -0.3027, -0.7377, -0.2656, -0.1819, +0.0315, -0.1914, -0.3061, -0.0285, +0.1491, -0.3607, -0.6081, +0.3564, +0.2935, -0.1484, +0.1152, -0.5023, +0.1752, -1.5863, +0.1823, -0.3487, +0.3613, +0.0175, -0.2217, -0.1352, -0.5851, +0.1753, -0.0871, +0.5474, +0.3244, -0.8566, -0.3348, -0.0279, +0.5935, +0.2750, +0.0797, +0.1091, -0.8979, +0.7681, +0.3679, +0.3083, +0.2425, +0.1221, +0.3024, +0.4512, +0.0880, -0.0056, -0.1940, +0.3921, +0.4914, -0.7178, -0.2134, +0.1143],
-[ +0.0679, -0.0794, -0.3814, +0.2536, -0.1512, +0.1385, -0.1787, -0.1347, -0.1905, +0.0860, +0.1867, -0.0860, +0.0923, +0.1577, +0.1129, +0.2066, +0.2144, +0.0983, +0.1848, +0.3214, -0.3866, +0.1045, -0.0303, -0.2351, -0.1582, -0.0153, -0.1058, +0.0740, -0.0575, -0.1356, +0.0975, +0.2816, +0.0862, -0.2179, -0.4657, -0.2575, -0.1307, -0.1683, -0.0066, +0.0145, +0.2131, -0.0987, +0.2698, +0.1188, +0.0539, +0.3335, -0.0699, -0.1512, -0.0397, +0.0569, +0.0859, +0.2909, +0.0149, -0.0338, +0.3416, +0.0462, -0.0262, +0.3987, -0.1117, +0.0869, +0.2025, +0.0820, +0.0110, -0.0663, -0.0989, +0.0121, +0.2080, +0.2500, -0.2012, -0.0425, -0.3801, +0.2980, -0.1070, -0.2112, -0.2358, -0.0148, +0.0342, +0.1877, -0.0190, -0.3003, -0.0384, +0.3230, +0.0058, +0.1883, +0.1429, -0.0525, -0.0369, +0.1965, +0.4171, -0.2498, +0.3534, +0.1377, -0.1843, -0.0786, -0.0334, -0.2252, -0.2525, -0.4377, +0.0970, -0.0632, -0.1115, +0.1151, -0.2193, +0.4269, +0.0589, +0.2567, -0.0083, -0.1317, -0.0140, -0.2162, +0.1460, +0.2144, -0.2364, +0.2052, +0.1361, +0.3009, -0.0415, +0.0753, +0.1605, -0.0008, +0.1161, -0.0075, +0.1132, -0.1271, +0.5005, +0.0962, +0.0963, +0.2632],
-[ -0.0499, -0.1868, +0.0577, +0.1447, +0.1636, -0.3556, -0.1492, +0.0388, -0.1583, -0.0774, +0.0437, +0.0230, -0.1318, +0.0701, +0.3213, -0.0902, -0.1691, +0.0205, +0.0912, -0.0380, +0.0704, -0.0709, -0.0177, -0.1689, -0.3108, +0.0728, -0.2808, -0.0876, -0.0702, -0.4691, +0.3010, +0.2589, -0.1658, -0.3264, +0.1423, +0.0444, -0.0579, +0.0883, -0.1900, -0.3669, +0.0899, +0.0842, +0.1387, +0.0023, +0.0807, -0.1238, +0.1961, +0.0881, -0.0594, -0.1222, -0.2213, +0.2254, +0.0348, -0.1841, -0.1994, -0.4183, +0.0770, -0.2080, -0.0388, +0.0821, +0.0289, +0.0999, -0.0389, +0.0711, -0.2250, -0.0025, -0.2014, +0.2883, +0.3065, -0.1356, -0.0597, -0.1037, -0.0451, -0.1849, +0.0913, -0.0457, +0.0217, -0.0981, +0.0654, -0.1176, +0.1646, +0.2142, -0.3388, -0.5200, -0.2313, -0.1905, +0.0708, -0.0961, -0.1217, -0.1662, -0.1982, +0.1837, -0.0128, +0.0935, +0.0200, +0.1873, -0.2688, +0.2296, +0.2719, -0.2736, +0.2598, +0.1866, +0.1070, -0.0368, -0.0790, +0.3079, -0.1966, +0.0417, -0.2708, +0.0273, +0.3073, +0.2085, -0.1423, -0.1677, -0.2092, -0.3405, +0.1060, -0.3134, -0.1067, +0.0272, +0.1868, -0.2262, +0.2388, -0.4858, -0.0006, +0.3641, -0.0149, +0.1635],
-[ -0.0293, -0.6816, +0.0207, -0.3203, +0.5807, +0.2284, +0.0608, -0.0782, -0.7455, +0.0780, +0.1824, +0.2558, +0.6335, +0.3215, -0.1083, -0.4061, +0.2560, -0.2431, -0.9005, -0.7526, +0.0429, +0.0809, +0.3405, -0.1655, +0.1869, -0.4230, +0.1290, -0.0598, -0.8880, -1.3204, -0.6279, +0.1188, -0.1528, +0.1304, +0.3002, -0.2851, -0.4151, +0.1325, +0.0967, -1.1975, -1.4119, -0.1437, +0.1030, +0.1688, +0.1357, +0.5681, +0.1686, -0.6273, -0.0961, -0.1940, -0.4501, -0.3292, -0.4322, -0.0958, -0.1608, +0.0745, -0.2823, +0.1386, -0.3401, -0.0044, +0.1450, -0.9192, +0.1943, -1.0786, -0.3468, -0.2210, -0.8898, +0.2841, -0.1573, +0.0027, +0.5140, +0.2573, -0.2886, -0.1363, +0.0590, -0.0752, -0.5069, +0.4482, -0.2980, -0.0193, +0.0242, -0.1357, +0.3524, -0.0679, -0.4083, -0.1631, -0.0261, +0.0079, +0.4069, +0.0506, +0.0312, +0.1185, +0.3524, -0.1431, -1.3855, +0.2428, -0.4439, +0.2224, -0.6006, +0.1477, -0.1597, -0.4273, -0.1280, +0.4005, +0.2949, +0.1104, -0.0679, +0.3744, +0.6098, -0.5700, +0.1008, +0.2341, -0.4750, -0.3084, -0.2798, -0.7803, +0.6083, -0.0650, +0.0205, -0.1667, +0.0401, -0.1926, +0.4924, +0.1119, -0.8171, +0.2006, +0.3861, -1.1334],
-[ +0.3379, -0.0630, -0.3660, +0.3327, +0.0593, -0.1086, +0.5011, +0.1324, -0.2487, -0.0698, +0.1031, -0.1188, +0.2941, +0.0543, -0.0504, -0.1540, -0.0798, +0.2290, +0.2369, -0.0698, +0.1134, +0.4617, +0.1530, -0.3301, -0.2881, -0.2488, +0.0245, -0.0285, -0.2306, -0.1149, -0.0003, -0.0923, -0.1315, +0.0210, -0.1870, +0.0622, -0.0506, -0.0135, -0.1995, -0.0287, +0.0711, -0.0130, +0.3577, -0.1441, -0.1204, -0.3320, -0.2458, -0.0879, +0.0139, +0.2201, -0.3011, +0.0393, +0.2918, -0.0472, -0.1514, -0.1190, -0.0056, +0.2567, -0.3284, -0.5337, -0.0050, -0.1086, -0.1834, -0.3311, -0.1851, +0.1848, -0.0175, -0.1277, -0.1361, +0.1587, +0.0424, +0.0936, +0.1683, -0.0294, +0.1407, -0.0313, -0.0279, +0.2524, +0.1912, +0.1002, +0.1337, +0.0550, +0.1725, +0.0323, +0.1961, +0.2280, +0.4421, +0.1152, +0.0211, +0.1519, -0.0487, -0.0903, +0.1088, -0.1067, -0.1932, +0.0741, -0.1907, -0.1498, +0.3873, -0.1806, -0.1683, +0.1372, +0.0304, +0.0863, -0.1042, -0.0114, +0.1071, +0.1654, +0.2195, -0.1274, -0.2964, +0.1572, +0.1514, +0.0736, +0.1129, +0.1630, -0.0438, +0.2270, -0.0895, +0.2149, +0.2307, +0.0664, +0.0300, +0.3303, +0.0999, +0.3439, +0.0904, +0.1683],
-[ +0.0340, -0.0989, -0.0451, +0.2294, +0.2241, +0.2625, -0.1814, +0.0073, -0.3025, +0.3027, -0.3313, -0.0211, +0.0333, +0.1126, -0.0768, -0.1360, -0.3812, +0.2599, -0.2655, -0.0163, +0.2248, -0.1354, +0.1735, -0.1578, -0.0827, +0.1191, +0.1209, -0.2733, +0.2359, -0.2004, -0.0624, +0.2381, -0.0092, -0.0115, +0.0134, -0.2366, +0.2267, -0.3574, -0.0541, -0.3561, -0.0686, -0.0024, -0.0964, -0.0168, +0.0758, +0.1287, +0.0970, +0.2117, +0.4078, +0.2125, -0.1938, +0.0866, -0.2325, -0.0116, -0.2797, -0.2403, +0.1878, -0.2757, -0.2458, +0.2984, -0.0047, +0.1370, -0.3392, -0.1224, +0.2413, +0.1075, +0.3686, +0.2316, -0.0368, +0.0658, +0.0282, +0.2231, -0.1776, +0.0984, +0.2372, +0.2452, +0.0692, -0.0771, +0.2522, +0.2017, +0.1455, +0.2602, +0.1297, -0.0145, -0.1484, +0.0469, -0.0616, +0.2906, +0.1185, +0.2783, +0.0614, +0.0493, -0.2796, +0.1048, -0.2029, +0.1820, -0.2846, +0.0042, +0.0699, +0.2208, +0.1126, -0.0028, -0.0612, -0.0730, -0.0883, +0.1355, -0.2635, -0.4806, +0.1522, -0.5489, -0.1904, -0.2650, +0.1945, -0.0204, -0.0391, +0.2104, +0.2261, +0.2982, -0.5277, +0.0563, -0.0652, -0.0232, +0.0058, +0.0107, +0.1389, -0.1388, +0.3945, +0.1338]
-])
-weights_dense1_b = np.array([ +0.0484, -0.2398, -0.1357, +0.0298, -0.3778, -0.2392, -0.0211, -0.1728, +0.0154, -0.1052, -0.0235, -0.0825, -0.0137, -0.1951, +0.1408, -0.2835, -0.4597, -0.2002, -0.1659, -0.2736, -0.0233, -0.2472, -0.0697, -0.1892, -0.1340, -0.0051, -0.1712, -0.1986, -0.1902, -0.1213, -0.1363, -0.2731, -0.0609, +0.0803, -0.1623, +0.0661, -0.0660, -0.1206, -0.2835, -0.1281, -0.1008, -0.2377, -0.1436, -0.1027, -0.1816, -0.1699, -0.2476, -0.0886, -0.1582, -0.1714, -0.1558, -0.2484, -0.1255, -0.1657, -0.0830, -0.0800, -0.1293, -0.0594, +0.0174, +0.1097, -0.1769, -0.1648, -0.1995, -0.1082, -0.1761, +0.0342, -0.1445, -0.0106, -0.2021, -0.1352, -0.2769, -0.1503, +0.1171, -0.2275, -0.1514, -0.1064, -0.1877, +0.0308, -0.1081, -0.0229, -0.1273, -0.0516, -0.0789, -0.1148, -0.0308, -0.1946, -0.3185, -0.1215, -0.0605, -0.1876, -0.1192, -0.1545, -0.0148, -0.0218, -0.3640, -0.2230, +0.1549, +0.0196, -0.2555, -0.1814, -0.3217, -0.1741, +0.0117, -0.1752, -0.2445, -0.0863, +0.0041, +0.0058, -0.0948, -0.1010, -0.0595, +0.0182, -0.0761, -0.0141, -0.1886, -0.0474, +0.0057, -0.1247, -0.3390, +0.0672, -0.0612, -0.1059, +0.0219, -0.1802, -0.1265, -0.1287, +0.0565, -0.0502])
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ -0.4105, +0.5540, +0.2791, +0.4953, -0.0309, +0.8480, +0.1630, +0.0630,
+ +0.7107, +0.0597, +0.2675, -0.1931, -0.2436, +0.2909, +0.3563, +0.4564,
+ -0.0445, -0.2228, +0.7005, +0.8368, +0.3631, +0.7365, +0.2453, +0.4687,
+ +0.4819, +0.4940, +0.5096, +0.5929, +0.5504, +0.2265, +0.4118, +0.5993,
+ +0.2402, -0.5087, -0.0756, +0.7520, -0.0086, -0.0648, +0.0564, -0.0812,
+ -0.0093, +0.8482, +0.7333, +0.4401, -0.1273, -0.2974, +0.1284, -0.4948,
+ +0.1120, +0.7938, +0.1297, +1.0807, +0.2480, +0.2444, +0.4258, +0.1515,
+ -0.0126, +0.3098, -0.2786, +0.4913, +0.3065, +0.3356, +0.6884, +0.3117,
+ +0.3163, +0.4234, +0.1172, +0.8810, +0.3574, -0.3993, -0.5597, +0.2233,
+ +0.8058, +0.3391, -0.1113, +0.1884, +0.1324, +0.0503, +0.1807, +0.0441,
+ -0.2065, +0.1978, +0.0852, -0.3531, +0.2180, +0.7946, -0.0318, +0.0650,
+ -0.3174, -0.1715, -0.0486, +0.2131, -0.3901, +0.1995, +0.8593, +0.1786,
+ +0.3595, +0.7852, +0.3491, -0.4206, +0.6117, -0.1991, +0.1876, -0.3114,
+ -0.2007, -0.2738, -0.0388, +0.0465, +0.2726, -0.5321, +0.4720, -0.0555,
+ +0.3415, +0.1447, -0.1132, -0.2958, -0.6729, -0.5003, -0.4960, -0.2600,
+ -0.4158, -0.4476, -0.8244, -0.0574, +0.2194, +0.0541, -0.3526, -0.1131
+ ],
+ [
+ -0.2662, +0.1763, +0.0520, +0.3624, +0.0564, +0.2756, +0.0743,
+ +0.0155, +0.1861, -0.5311, +0.2181, -0.3643, +0.1433, +0.1801,
+ -0.1781, -0.3576, -0.2487, +0.0588, +0.3906, -0.3994, +0.1343,
+ +0.2701, +0.1613, +0.1962, -0.0277, +0.0303, +0.0845, -0.1033,
+ -0.1092, -0.1026, -0.2261, +0.3324, +0.1881, -0.2780, -0.0865,
+ -0.2131, -0.1238, -0.1727, +0.1086, +0.1383, +0.1794, +0.0677,
+ -0.0582, -0.0758, +0.0834, +0.0847, +0.0945, +0.1888, -0.0696,
+ +0.0111, -0.0028, +0.0439, -0.3847, -0.1564, -0.2226, +0.0002,
+ +0.0926, -0.2819, -0.0868, +0.2233, +0.0738, +0.1671, -0.0326,
+ +0.3784, -0.0117, +0.0836, +0.0285, +0.0376, +0.0157, +0.1297,
+ +0.0556, -0.0533, -0.0103, +0.0740, -0.1825, -0.2399, -0.0609,
+ -0.0030, +0.1811, -0.2784, -0.2249, +0.3637, +0.1895, +0.3102,
+ -0.0767, +0.1143, -0.0840, +0.2981, -0.3040, +0.0135, +0.2495,
+ +0.0036, -0.1493, -0.1144, -0.0006, +0.1195, +0.0961, -0.4227,
+ -0.3022, +0.2102, +0.2024, -0.2111, +0.1507, +0.2948, -0.1822,
+ +0.2263, -0.3213, +0.0380, -0.1188, +0.1237, +0.0731, +0.0044,
+ -0.1637, -0.3173, +0.0895, -0.0130, +0.0703, -0.2186, +0.1401,
+ +0.1191, +0.0225, -0.3208, -0.0578, -0.3113, +0.1041, -0.1957,
+ -0.3054, -0.0797
+ ],
+ [
+ +0.3485, -0.3161, -0.4092, +0.1190, -0.5706, -0.3627, +0.0576,
+ -0.1068, +0.1367, +0.1686, +0.0284, -0.1694, -0.0496, -0.1647,
+ +0.0111, -0.1897, -0.4613, -0.5996, -0.0601, -0.1417, -0.0236,
+ -0.0898, +0.1239, -0.2693, -0.1709, +0.3592, -0.1284, -0.0376,
+ -0.1308, -0.1832, -0.0538, -0.0467, -0.1181, -0.0994, -0.3281,
+ +0.0527, -0.4579, -0.1062, -0.1058, -0.4459, -0.0901, -0.0246,
+ -0.1125, +0.1228, -0.3428, -0.3385, +0.0366, -0.0988, +0.1345,
+ +0.0299, +0.2921, -0.1347, +0.1688, -0.1350, -0.0888, +0.0734,
+ -0.0936, -0.2695, +0.0154, +0.0237, -0.1334, -0.3247, -0.1856,
+ -0.0449, -0.0772, +0.0176, -0.0856, -0.1746, -0.1575, -0.2365,
+ -0.0741, -0.1638, +0.0864, -0.0243, -0.0472, +0.0423, -0.2962,
+ -0.2523, -0.1430, +0.1470, -0.1122, -0.1843, -0.1437, -0.1895,
+ +0.1110, -0.2572, -0.3307, -0.2597, -0.4706, -0.2441, -0.2988,
+ -0.5409, -0.1696, +0.0810, -0.2336, -0.0925, +0.4226, +0.1162,
+ -0.3211, -0.2118, -0.3100, -0.1384, +0.1625, +0.0005, -0.1936,
+ +0.2836, +0.1660, -0.2154, +0.1341, -0.2413, -0.1203, -0.3427,
+ +0.0863, +0.1393, -0.3580, +0.1443, -0.2158, -0.4703, -0.2687,
+ -0.0573, +0.1099, -0.2551, -0.0506, -0.3351, -0.2325, -0.0119,
+ -0.0907, -0.0628
+ ],
+ [
+ +0.0565, +0.2158, +0.1461, +0.1045, -0.3548, -0.2816, -0.0124,
+ -0.0931, +0.1249, +0.0093, -0.3325, -0.1646, +0.3022, -0.0509,
+ -0.1403, +0.3703, +0.2642, +0.0835, +0.1347, +0.1734, -0.0112,
+ +0.3162, -0.0076, +0.1258, -0.2059, +0.2387, +0.0775, -0.1653,
+ -0.3899, -0.1205, -0.2263, +0.2800, -0.1979, +0.1708, +0.0505,
+ -0.0998, +0.1838, -0.1314, -0.1932, -0.1897, -0.3157, -0.0113,
+ -0.3488, +0.1534, -0.3546, -0.1098, +0.0652, -0.1327, -0.0131,
+ +0.3698, -0.0927, +0.1735, -0.4869, +0.1768, -0.0187, -0.1069,
+ -0.2118, -0.2557, -0.1380, -0.0579, -0.2147, +0.3389, -0.1801,
+ +0.1954, -0.2856, +0.0825, +0.1846, -0.2102, +0.4063, -0.0422,
+ +0.1645, -0.2313, -0.2017, -0.2554, +0.1597, -0.1198, +0.4493,
+ +0.1135, +0.1556, -0.0380, +0.0527, -0.0505, -0.5094, -0.4410,
+ +0.2543, +0.2891, -0.0031, -0.0863, +0.2982, +0.1069, -0.4814,
+ +0.0295, -0.0547, +0.0518, -0.4326, -0.0295, -0.3795, +0.0399,
+ +0.0363, +0.1623, +0.4509, +0.2852, -0.4404, +0.0109, -0.0394,
+ +0.0092, -0.1684, +0.4728, -0.1317, +0.0575, -0.3862, -0.1313,
+ +0.0676, +0.1321, -0.2816, -0.0500, -0.0027, +0.0906, +0.0297,
+ -0.1476, +0.0337, +0.0911, -0.1591, +0.2816, -0.0435, -0.3437,
+ -0.0732, -0.4545
+ ],
+ [
+ -0.2090, -0.1890, -0.4459, +0.0942, +0.2823, -0.0085, -0.1576,
+ -0.5515, +0.1211, -0.0689, +0.2807, +0.1457, +0.2009, -0.2739,
+ +0.0296, -0.0511, -0.1048, -0.1275, +0.2358, +0.3103, +0.2239,
+ +0.2028, -0.0858, +0.0520, -0.1453, +0.2013, -0.2131, -0.0596,
+ -0.0469, -0.0934, -0.2082, +0.2071, -0.5051, +0.1719, -0.1380,
+ -0.2781, -0.0598, -0.1636, +0.2784, -0.0144, +0.0655, -0.1932,
+ +0.1421, -0.0840, -0.0277, -0.2310, -0.0509, +0.0870, +0.0721,
+ -0.1785, +0.1514, -0.1485, -0.1158, +0.1124, -0.1155, -0.4105,
+ -0.1765, +0.0103, -0.1695, +0.0521, -0.1132, -0.1209, -0.1313,
+ -0.0419, +0.1828, -0.1026, +0.0564, +0.0095, -0.0414, +0.1264,
+ +0.1588, -0.2200, +0.1928, -0.2098, +0.4256, -0.3453, -0.3882,
+ -0.2238, -0.1347, +0.2160, +0.4278, -0.2666, -0.1046, +0.2501,
+ +0.0238, +0.2802, -0.3955, +0.1452, +0.1773, -0.0727, -0.3603,
+ -0.2480, -0.0412, +0.2462, +0.2148, -0.2819, +0.0982, -0.0102,
+ +0.0310, +0.0147, +0.0597, +0.0514, -0.0032, +0.1320, -0.0606,
+ -0.0637, +0.0398, +0.1367, +0.0646, -0.0435, +0.0527, +0.1258,
+ -0.2075, -0.1816, -0.2129, -0.1253, +0.2394, -0.2325, -0.1115,
+ -0.4115, -0.1196, -0.2855, +0.3805, -0.2741, -0.0278, -0.3461,
+ +0.0139, -0.0499
+ ],
+ [
+ -0.6025, +0.2692, +0.5276, +0.3615, -0.3196, +0.3828, +0.1312,
+ -1.1323, -0.0073, -0.1227, -0.0831, +0.0605, -1.0515, -0.1917,
+ -0.2510, +0.2964, -1.1074, -0.1708, -0.4475, -0.1189, +0.3345,
+ +0.5101, +0.4628, +1.1872, +0.5829, +0.0234, +0.0306, +0.0021,
+ -0.1827, -0.0257, -0.2993, +0.0083, -0.9032, -0.0311, +0.0045,
+ +0.6173, +0.3095, -0.1490, -0.2561, +0.2011, -0.1550, -0.1936,
+ +0.0729, +0.7613, -0.9194, +0.1954, +0.0306, +0.2292, +0.1529,
+ -0.1161, -0.0182, -0.2625, -0.3142, -0.9182, +0.2761, +0.3656,
+ +0.3537, +1.0318, -0.4273, +0.1703, -0.2378, -0.4640, +0.6184,
+ +0.3686, -0.3043, -0.4850, -0.2155, -0.6656, +0.1921, -0.2552,
+ -0.8096, +0.8593, -0.3583, -0.0332, -0.5619, +0.2977, -0.3425,
+ -0.7839, -0.4299, -0.2358, +0.0526, -0.0752, -0.6535, +0.0501,
+ -0.4043, +0.8261, -0.4269, -0.1165, +0.3480, -0.2337, -0.3269,
+ -0.2775, +0.7307, +0.5863, -0.1005, -0.3421, +0.1591, +0.4530,
+ -0.1228, -1.0896, +0.6218, -0.0610, -0.1239, -1.5883, -0.1711,
+ -0.4331, -0.3553, +0.0773, +0.3669, -0.5690, +0.7117, -0.2021,
+ -0.1426, -0.1125, +0.0364, +0.2397, -0.1739, -0.3131, -0.9135,
+ -0.7713, -0.0638, -0.3219, +0.0353, +0.3407, -0.0035, -0.1492,
+ -0.1118, -0.4841
+ ],
+ [
+ -0.0175, -0.3710, +0.0894, +0.2056, -0.2250, +0.0982, +0.0039,
+ -0.2128, -0.0479, +0.3049, +0.2228, -0.1747, -0.0936, +0.1146,
+ +0.1377, +0.0127, +0.0014, +0.1374, +0.1557, -0.1890, -0.2396,
+ +0.2248, +0.1710, -0.2916, +0.4568, -0.0645, -0.0760, -0.2067,
+ -0.3900, +0.0276, -0.3171, -0.0148, +0.2019, -0.1335, -0.0731,
+ -0.3224, +0.0859, +0.2299, +0.0602, +0.0499, -0.2686, +0.1028,
+ +0.1204, +0.0321, +0.0636, -0.1350, -0.1789, -0.0529, -0.2255,
+ +0.1867, +0.1258, +0.1392, -0.2657, +0.1478, +0.1961, -0.0687,
+ +0.1878, +0.2016, -0.2413, +0.0050, -0.0666, -0.0226, -0.0185,
+ +0.4750, -0.1661, +0.0637, -0.2668, +0.1875, +0.0032, +0.1176,
+ +0.1844, -0.1665, -0.1806, -0.3208, +0.0606, -0.0122, +0.2792,
+ +0.1867, +0.1424, +0.2775, +0.1074, -0.2996, +0.0562, -0.1864,
+ +0.1985, +0.1356, -0.3013, -0.0824, -0.1534, -0.0795, -0.0086,
+ -0.0490, -0.0861, -0.0986, +0.3499, -0.0630, +0.0028, -0.1540,
+ +0.0377, -0.1057, +0.1303, +0.1379, -0.1257, -0.2578, -0.0744,
+ -0.1304, +0.0411, -0.1635, +0.0535, +0.0271, +0.1674, +0.1309,
+ -0.0397, -0.1127, -0.2217, +0.0548, -0.5178, +0.1170, +0.4857,
+ +0.1134, +0.0598, +0.1467, +0.1405, -0.1152, +0.1825, -0.0382,
+ +0.1325, +0.2708
+ ],
+ [
+ -0.1185, -1.2480, -0.6130, -0.9105, +0.1073, -0.7702, -1.2908,
+ +0.6513, -0.3928, -0.7365, -0.2977, +0.7845, +0.3186, +0.2207,
+ -1.1391, -0.9353, +1.1582, -0.7291, +0.2077, +0.2808, -0.5894,
+ +0.4805, -0.2316, -0.8861, -0.4102, -1.1704, +0.9183, -0.0637,
+ -0.1935, -0.2971, -0.6144, +0.6113, +0.1596, -0.2931, +0.3199,
+ -0.2938, -0.2098, +0.3615, -0.3433, +0.0334, +0.2148, -1.9070,
+ -0.0655, -0.5875, +0.5659, +0.0436, +0.5074, +0.5399, -0.2164,
+ -0.7224, -0.1556, -1.3397, +0.5629, +0.1272, -0.1749, -1.2117,
+ +0.9305, -0.9436, -0.9450, -0.4745, -0.9840, -0.5153, -0.1703,
+ -0.5252, -0.0291, +0.3351, +1.0137, -1.4468, +0.1594, +0.4054,
+ +0.9667, -0.3279, -1.2628, -0.6361, -0.1322, -0.4219, -0.8181,
+ +0.1316, +0.3924, +0.4478, +0.5855, -0.0547, -1.4541, +0.1199,
+ -0.2794, -0.9176, +0.8841, +0.2706, -0.1612, +0.7667, -0.3909,
+ -1.6514, +0.1562, -0.3166, -0.2654, +1.0692, -0.1898, -1.3619,
+ +0.0357, +0.6267, -0.0957, -0.5473, -0.9002, +0.4248, +0.7671,
+ +0.6034, +0.1176, +0.4126, -0.4076, +0.5846, -0.4275, +0.0146,
+ +0.5074, +0.4825, +0.3414, -0.0289, +0.5663, +0.9628, +0.9791,
+ -0.1043, +1.2530, +1.3600, +1.6041, +0.4200, -0.2415, -0.4470,
+ +0.6965, +0.2395
+ ],
+ [
+ +1.2479, -0.0619, -0.4174, -0.2800, +0.2902, +0.2310, +0.0858,
+ -0.0805, +0.2556, +0.8018, -0.1018, +0.9876, +0.2342, +0.3219,
+ +0.3031, -0.1343, +0.0737, +0.2219, -0.6479, -0.4475, +0.3711,
+ +0.4780, -0.8735, +0.6208, -0.3031, +0.1480, +0.4935, +0.9053,
+ +0.0797, -0.3932, +0.0853, -0.4709, -0.6192, +1.1604, -0.0924,
+ -0.2548, +0.5836, +0.0325, -0.2435, -0.1506, -0.1754, -0.2248,
+ -0.8059, -0.1997, +0.7772, +0.1456, -0.1463, -0.0360, -0.0240,
+ -0.1852, -0.1289, +0.9165, -0.2434, +0.7580, +0.3838, -0.0338,
+ +0.1199, -0.1700, -0.4038, -0.1863, +0.0925, -0.2396, +0.4659,
+ +0.1810, +0.6990, +0.2880, +0.0641, -0.3991, +0.6049, -0.5948,
+ -0.1894, -0.7874, -0.6910, +0.0824, +0.5111, -0.2513, +0.4632,
+ +0.7014, -0.6793, +0.0562, -0.0800, +0.2665, -0.0270, +0.1830,
+ +0.8184, +0.5293, -0.3352, +0.1144, +0.7672, -0.0924, +0.2099,
+ -0.0854, -0.1534, +0.2607, -0.1140, -0.1163, +0.0403, +0.2623,
+ +0.4065, +0.9303, +0.4008, -0.1773, +0.0368, +0.4014, -0.6941,
+ +0.0333, +0.3245, +0.0262, +0.7663, +0.3834, +0.4088, +0.0289,
+ -0.6102, +0.5717, -0.0787, +0.2367, +0.2061, -0.3039, -0.0797,
+ +0.0814, +1.2009, +0.4369, +0.0788, +0.2358, +0.9926, +0.5428,
+ -0.5656, -0.2758
+ ],
+ [
+ +0.3487, +0.2086, -0.0813, +0.4360, -0.2904, +0.4395, +0.1773,
+ +0.0481, +0.4503, +0.4991, +0.3741, +0.1866, -0.2241, -0.3511,
+ +0.2302, +0.5140, +0.5208, +0.5968, +0.5189, +0.2814, +0.3372,
+ +0.3461, +0.0298, +0.0069, -0.1004, +0.5782, -0.2609, +0.1167,
+ -0.5090, -0.3220, +0.0509, +0.4076, -0.1667, +0.2021, -0.0495,
+ +0.2189, -0.0504, -0.3792, -0.4321, +0.0364, -0.0175, -0.0359,
+ +0.0965, +0.3641, -0.2778, -0.1170, +0.7745, -0.2177, +0.1121,
+ +0.0240, +0.6502, +0.1845, -0.0903, +0.3065, +0.0884, +0.4046,
+ -0.2021, -0.3310, +0.0056, -0.2555, +0.0209, +0.5952, -0.1765,
+ +0.0503, -0.0449, +0.2059, +0.2699, -0.2488, -0.6611, +0.2942,
+ -0.4384, +0.3329, +0.4411, -0.1499, -0.0820, +0.5042, +0.2737,
+ -0.3949, +0.4931, +0.0065, -0.8717, -0.4590, +0.1508, +0.3686,
+ +0.1564, -0.2887, -0.3002, -0.0485, +0.0003, -0.4201, -0.0104,
+ +0.2674, +0.1690, +0.1299, -0.0258, -0.0109, +0.6633, +0.3255,
+ -0.0330, +0.4770, +0.3560, +0.1506, +0.3608, +0.4205, +0.0090,
+ -0.3770, +0.2320, -0.2200, +0.0256, -0.2081, -0.1292, +0.0661,
+ -0.3286, +0.1211, +0.1542, +0.5790, +0.0675, -0.1831, -0.0903,
+ +0.0403, +0.1506, -0.2725, +0.1505, -0.3582, -0.2939, -0.3307,
+ -0.2906, -0.1859
+ ],
+ [
+ +0.6120, +0.3881, -0.2144, +0.0539, +0.2717, +0.0574, -0.6547,
+ -1.1043, -0.4978, +1.0026, -0.2662, -0.3964, -0.4590, +0.5876,
+ +0.3651, +0.2121, -0.3029, +0.4225, -0.2654, -0.0867, -0.0286,
+ +0.4754, +0.5950, -0.0923, +0.5628, -0.1033, -0.1225, -0.5554,
+ -0.9027, -0.3767, -0.7881, -0.0124, -0.6633, -0.7063, +0.4806,
+ -1.2205, -0.1279, +0.0321, +0.3928, +0.0134, +0.3143, -0.5378,
+ +0.0553, +0.1611, +0.0254, -0.4512, +0.7660, +0.4550, +0.6917,
+ +0.0186, +0.1970, -0.4484, +0.4214, +0.5640, +0.7182, -0.6329,
+ +0.3644, -0.5340, -0.0268, -0.3028, +0.4847, -0.1190, -0.3030,
+ +0.4755, +0.1916, -0.1579, -0.1899, -0.1830, +0.2239, -0.8405,
+ -0.0194, -0.4524, -0.6924, +1.0233, -0.1682, -1.0005, -0.1989,
+ +0.0655, -0.5738, +0.3489, -0.2032, -0.5767, +0.2677, -0.2104,
+ +0.9164, -0.6995, +0.3138, +0.2631, +0.4646, -0.7949, -0.4088,
+ +0.0390, +0.5322, +0.8076, +0.3327, -0.8003, -0.4473, +0.2003,
+ -0.0771, +0.9627, -0.5091, +0.5703, -0.3930, +0.3132, +0.9709,
+ +0.2298, +0.2046, -0.4682, -0.4135, +0.8331, -0.0837, -0.2126,
+ -0.2461, -0.6451, -0.3118, +0.1340, +0.3047, -0.3990, +0.8511,
+ -0.0305, +0.7664, +0.2561, +0.5513, +0.2083, -0.7912, -0.5125,
+ -0.5167, -0.5089
+ ],
+ [
+ +0.2836, +0.6191, -0.2299, +0.4317, +0.1775, -0.6181, +0.0461,
+ +0.0362, +0.0559, +0.7882, -0.1351, -0.3722, +0.1090, +0.0281,
+ +0.1148, +0.7799, -0.2107, -0.3900, -0.2063, -0.3643, +0.7287,
+ -0.2938, +0.1283, -0.1046, +0.0992, -0.1031, +0.6297, -0.8027,
+ -0.0918, +0.2503, +0.5527, +0.3296, -0.0083, -0.1686, +0.0065,
+ +0.2643, +0.1768, -0.4890, +0.0692, +0.5517, +0.6225, -0.0423,
+ -1.0015, -0.5841, -0.2217, -0.6242, -0.1942, -0.3841, +0.7571,
+ +0.4939, -0.2331, +0.1612, +0.0843, +1.2429, -0.2966, -0.5344,
+ +1.0299, -0.7019, -0.1317, -0.0856, +0.2293, -0.0003, -0.0487,
+ -0.5326, +0.0300, +0.5683, +0.2054, -0.3269, +0.6114, -0.5650,
+ -0.1812, -0.8703, +0.0364, +0.6392, -0.7844, +0.0227, +0.6228,
+ +0.5272, -0.8685, -0.4089, -0.3416, -0.1562, +0.1535, -0.0063,
+ +0.6183, -0.5915, -0.1640, -0.2188, +0.4079, -0.3470, +0.5118,
+ +0.4866, -0.9074, -0.0650, +0.3942, -0.1759, -0.3695, +0.1913,
+ +0.9200, +0.2702, -0.2663, +0.1217, -0.1575, -0.2490, +0.1515,
+ -0.7135, +0.4985, +0.1606, -0.1133, -0.2688, -0.4154, -0.5524,
+ -0.0633, -0.0389, +0.4926, -0.0719, -0.3427, -0.6053, -0.1829,
+ -0.5910, +0.1137, +0.0312, +0.4532, +0.1142, +0.3834, -0.0407,
+ -0.5945, -0.6180
+ ],
+ [
+ +0.0362, -0.5185, -0.3235, +0.0613, +0.3283, +0.6853, -0.3136,
+ +0.4028, +0.2535, +0.0223, +0.1985, -0.9784, +0.8819, -0.4328,
+ -0.1815, +0.2478, -0.1824, -0.0182, +0.3654, -0.2296, +0.3019,
+ -0.1017, +0.5535, +0.2589, -0.4000, +0.0137, -0.4569, +0.4085,
+ +0.3198, +0.1833, -0.2268, +0.1447, +0.3493, +0.4606, -0.2277,
+ -0.0773, -0.6224, +0.8234, +0.0221, +0.5623, -0.1428, -0.5706,
+ +0.5371, +0.8732, -0.5540, -0.0395, +0.8031, +0.3599, +0.5903,
+ +0.0713, -0.1844, +0.5461, +0.1745, +0.1545, -0.2652, -0.0803,
+ +0.2160, -0.4186, -0.3271, +1.0229, -0.0675, +0.0257, +0.3415,
+ +0.1843, -0.4467, +0.0753, +0.3914, -0.0426, +0.2589, -0.2688,
+ -0.2011, -0.0360, -0.2472, -0.4691, +0.1115, -0.3416, +0.1560,
+ -0.1638, -0.3131, -0.3056, +0.1102, +0.0386, -0.0213, +0.0334,
+ +0.5400, +0.3385, +0.0520, +0.2917, +0.0586, +0.3761, -0.2422,
+ -0.4576, -0.0317, +0.2312, +0.7176, +0.2603, -0.1864, -0.3297,
+ -0.3581, +0.3024, +0.4191, +0.1382, -0.4671, -0.1097, +0.3002,
+ +0.1556, +0.3214, +0.0859, +0.2674, -0.0762, +0.1793, +0.8109,
+ +0.5113, +0.0960, +0.2222, +0.2567, -0.0165, +0.8895, -0.0689,
+ -0.1649, +0.5046, +0.1555, +0.2201, -0.2468, -0.5657, -0.5523,
+ -0.7054, -0.2129
+ ],
+ [
+ +0.0779, -0.1795, -0.3084, +0.0991, +0.0959, -0.0223, +0.3783,
+ +0.3527, -0.2872, +0.3394, +0.0425, -0.0484, -0.2041, +0.9751,
+ -0.2537, +0.0812, +0.2257, +0.4729, +0.4647, +0.4171, +0.0146,
+ -0.1489, +0.5499, +0.4513, -0.2661, -0.8428, +0.3146, -0.1790,
+ +0.0097, -0.1133, +0.0693, +0.3234, +0.0583, -0.6285, -0.7520,
+ -0.2485, -0.5776, +0.6696, -0.2599, -0.0951, -0.2328, -0.5490,
+ +0.5175, +0.0767, -0.3109, -0.2104, +0.1518, -0.5617, +0.0181,
+ +0.2775, +0.0589, +0.3021, -0.8439, -0.0653, -0.4131, -0.4757,
+ +0.6912, -0.0174, -0.3354, +0.5238, -0.2113, +0.0943, -0.1804,
+ +0.0211, +0.5478, +0.5479, +0.3961, +0.0754, +0.0795, -0.2051,
+ -0.1059, -0.2414, +0.0145, +0.6187, +0.1991, +0.1538, -0.5956,
+ -0.0687, -0.1066, +0.5816, +0.3722, -0.3560, +0.4422, +0.4901,
+ +0.5202, -0.1284, +0.6292, +0.8110, +0.5204, -0.2698, -0.1241,
+ -0.0359, -0.0064, -0.3268, +0.7780, -0.3028, +0.1004, -0.0382,
+ -0.4620, +0.2837, -0.8406, -0.2417, +0.2056, +0.0777, -0.2286,
+ +0.0642, +0.5493, -0.8877, -0.1941, +0.3304, +0.4645, -0.4799,
+ -0.2487, +0.2221, +0.7077, +0.2539, -0.1791, +0.2926, +0.1322,
+ +0.0905, +0.1544, -0.2086, +0.3299, -0.0308, -0.0567, +0.1242,
+ -0.0968, +0.4553
+ ],
+ [
+ -0.2603, -0.4800, +0.0541, -0.8000, -0.6535, -0.8949, -0.3607,
+ -0.0667, -0.7336, -0.3965, +0.3150, +0.1505, -0.3550, -0.1260,
+ +0.3011, -0.0821, -0.3796, -0.1918, -0.3090, +0.0550, +0.1061,
+ -0.3667, -0.8571, -0.4193, -0.4680, -0.3205, +0.2565, -0.3090,
+ -0.2638, +0.1026, -0.1909, -0.5068, +0.0748, -0.4648, +0.0748,
+ -0.2874, +0.2573, -0.1646, -0.1574, +0.1782, -0.2502, +0.1568,
+ -0.1522, -0.5577, +0.5309, +0.1850, -0.1607, +0.2624, +0.0171,
+ +0.2342, -0.8137, +0.2716, -0.1085, -0.4303, -0.5537, -0.0020,
+ -0.0393, -0.3333, +0.2081, -0.0905, -0.6573, +0.1222, -0.4209,
+ -0.3416, -0.2223, +0.5376, -0.0664, +0.2956, +0.4846, +0.5470,
+ +0.3633, -0.2415, -0.6977, -0.4417, -0.1011, -0.4229, -0.1614,
+ -0.0722, -0.4239, -0.2685, +0.4363, +0.1485, -0.0346, -0.1507,
+ +0.0344, -0.0586, -0.1486, +0.1647, -0.0353, +0.3965, +0.1495,
+ -0.1808, -0.3812, -0.3466, -0.6642, -0.1044, -0.6627, -0.3414,
+ -0.3478, -0.0244, -0.0663, -0.2007, -0.3840, -0.6573, -0.4302,
+ +0.0623, +0.0473, -0.1558, -0.5837, +0.1068, -0.1332, -0.0385,
+ -0.0638, -0.7497, -0.1423, -0.3235, -0.2541, -0.2405, +0.3238,
+ -0.1456, +0.2076, +0.1714, +0.0112, +0.3124, +0.0782, +0.1887,
+ +0.3277, +0.1156
+ ],
+ [
+ -1.0948, -0.2236, +0.1540, -0.6062, -0.2097, -0.2825, -0.4756,
+ +0.3731, -0.5436, -0.3209, -0.3609, -0.1703, -0.6188, +0.0140,
+ -0.0252, +0.5627, +0.0186, +0.1253, -0.0046, +0.0767, -0.2195,
+ +0.3782, -0.1052, -0.1369, +0.3583, -0.5566, +0.6542, -0.3200,
+ +0.2563, -0.1301, +0.0185, -0.8119, +0.5848, +0.4946, -0.0112,
+ +0.1033, +0.1308, -0.1700, +0.1149, +0.3101, -0.3001, +0.2433,
+ +0.2101, +0.1298, -0.1548, +0.1310, -0.2388, +0.3923, +0.9332,
+ +0.5030, -1.0263, -0.1072, +0.1241, -0.0134, -0.0806, -0.3525,
+ +0.5211, -0.0752, +0.0334, +0.2871, -0.4669, -0.2720, -0.0067,
+ +0.1326, -0.4609, -0.0674, -0.6579, -0.2538, +0.2333, +0.4456,
+ +0.5642, -0.1694, -0.3706, +0.5684, -0.7867, -0.4995, +0.3289,
+ -0.6711, -0.1191, -0.8581, +0.3775, +0.8927, +0.5052, -0.0896,
+ +0.0121, +0.6358, +0.1183, +0.5200, +0.7512, +0.0846, -0.1086,
+ -0.0426, -0.0155, +0.6603, +0.0812, +0.4987, +0.0256, +0.0992,
+ +0.2730, -0.0697, +0.2773, -0.7570, -0.7726, -0.3871, -0.3158,
+ -0.3692, -0.7297, -0.0744, -0.5920, +0.6132, -0.0072, +0.1400,
+ -0.1782, -0.0227, +0.1123, -0.6036, -0.6343, +0.5520, +0.3165,
+ -0.4080, -0.0338, -0.1839, -0.0071, +0.3603, -0.3050, +0.4097,
+ -0.5939, -0.1245
+ ],
+ [
+ -0.3346, -0.2795, +0.2751, +0.2150, +0.4031, +0.5422, +0.3587,
+ +0.5206, -0.6544, +0.1672, -1.0438, -0.3010, +0.6246, +1.1339,
+ -0.6914, -0.1198, +0.0050, -0.8139, -0.1150, +0.9000, -1.1849,
+ +1.0507, -0.2149, -0.3482, -0.7118, +0.3377, +0.2528, +0.2764,
+ +0.2596, -0.4997, -0.8768, +0.4370, -0.0810, +0.1831, -0.0584,
+ +0.0562, +0.4426, -0.4548, -0.6110, -0.3985, -0.0168, -0.5126,
+ +0.5279, -0.4445, +0.0281, +0.3755, -0.0337, -0.7288, -0.4249,
+ +0.6200, -0.1673, -0.4617, +0.0127, -0.1385, +0.6653, -0.1985,
+ +0.4186, -0.5372, -0.5204, +0.8371, +0.2907, -0.7418, +0.0020,
+ +0.4483, +0.1869, +0.6499, +0.1529, +0.4740, +0.6753, +0.6005,
+ +0.7086, -0.3005, +0.5440, +0.3387, +0.2046, +0.4181, -0.8759,
+ -0.7487, -0.1262, -0.0293, +0.8712, +0.0119, -0.7947, -1.2465,
+ -0.0061, -0.0503, -0.2992, +0.5275, -0.3151, +0.1889, -1.5430,
+ +0.5531, +0.2559, -0.2591, -0.2807, -0.1324, -0.7027, -0.4375,
+ +0.1984, -0.3944, -0.0467, -0.3111, -0.6493, -0.2939, -0.0617,
+ +0.2605, -0.9876, -0.0857, -0.6928, +0.7228, -1.2047, +0.3026,
+ -0.7448, +0.4988, -0.3507, -0.7106, -0.7583, +0.3245, +0.2599,
+ -1.4422, +0.4198, -0.6388, -1.3088, +0.9680, -0.0616, -0.4120,
+ -0.3508, +0.1672
+ ],
+ [
+ -0.5261, +0.4924, +0.1685, -0.2603, +0.3052, +0.3751, -0.8492,
+ -0.1073, +0.1541, +0.1367, +0.1658, +0.0405, -0.0968, -0.0074,
+ -0.3535, -0.4133, +0.0255, -0.6547, -0.0838, +0.2996, +0.1273,
+ -0.1657, +0.0394, +0.4691, +0.0353, -0.2699, +0.1696, +0.5037,
+ +0.0277, -0.1267, -0.3741, +0.2501, +0.1612, -0.3687, -0.0763,
+ -0.2902, +0.3456, +0.1048, +0.0277, +0.1918, -0.6208, +0.1135,
+ -0.1049, -0.0283, +0.0202, +0.0171, +0.0822, -0.2369, +0.1969,
+ +0.5290, -0.0731, +0.4711, -0.2303, -0.0833, -0.3602, -0.1438,
+ -0.0070, -0.5158, -0.3721, +0.0134, +0.4545, -0.0207, +0.2113,
+ -0.0665, -0.2343, +0.2490, -0.2058, +0.1182, +0.0765, +0.3709,
+ +0.3816, -0.1490, -0.1526, -0.0174, +0.6291, +0.4946, -0.3356,
+ -0.0425, -0.0716, -0.6482, +0.4502, +0.0332, -0.2189, -0.6447,
+ +0.1329, +0.4471, -0.0323, -0.0798, -0.1390, +0.1446, -0.2377,
+ +0.4462, -0.2870, -0.2893, -0.0998, +0.1104, -0.1755, +0.2786,
+ +0.3976, -0.6894, -0.4004, -0.3018, -0.2645, +0.0620, +0.0661,
+ +0.1230, -0.3739, +0.0862, -0.2077, -0.1822, +0.0729, +0.0871,
+ -0.2029, +0.0181, +0.3299, -0.5234, +0.0010, +0.1996, +0.0403,
+ -0.6255, +0.1214, +0.0402, -0.3186, +0.1235, +0.0944, +0.2717,
+ +0.1232, -0.3457
+ ],
+ [
+ -0.1970, -0.3969, -0.2225, +0.1993, +0.1553, -0.0254, -0.1890,
+ -0.3057, +0.4549, -0.0170, -0.5648, -0.4915, -0.0502, -0.2149,
+ +0.2144, -0.5744, -0.1044, -0.4353, +0.0233, -0.0785, -0.3143,
+ -0.3626, +0.0585, -0.3341, -0.0893, -0.4231, -0.0378, +0.0274,
+ -0.4611, +0.0728, -0.1463, -0.2042, +0.0172, -0.4561, -0.0206,
+ -0.1719, -0.0000, -0.4023, +0.0364, -0.1958, -0.5589, -0.0532,
+ +0.0099, -0.0872, +0.0206, -0.0009, -0.3550, -0.3123, -0.0938,
+ -0.2254, -0.1686, -0.2615, -0.2844, +0.0994, +0.0554, +0.1692,
+ -0.2632, -0.1443, -0.1879, -0.1459, -0.6597, -0.3367, -0.1862,
+ -0.3134, +0.1299, -0.0695, +0.2293, +0.0609, +0.2819, -0.1567,
+ -0.2090, -0.1359, +0.3011, -0.2784, -0.2469, +0.0022, -0.1715,
+ -0.1446, -0.2693, -0.3637, -0.1232, -0.2147, -0.2098, +0.0446,
+ +0.1409, -0.0058, +0.0383, -0.1855, -0.1377, +0.0460, -0.2215,
+ +0.3805, -0.2653, -0.1465, -0.4812, -0.0015, +0.0714, +0.0472,
+ -0.2914, -0.2133, -0.1082, -0.8207, +0.1838, -0.1654, -0.6285,
+ -0.5248, +0.0549, -0.1583, -0.5096, +0.1266, -0.5755, -0.3374,
+ +0.0946, -0.3824, -0.4274, +0.1813, -0.3312, +0.1190, -0.2241,
+ +0.0402, +0.2119, +0.1831, -0.0826, -0.1367, -0.2986, -0.4726,
+ -0.5516, -0.0995
+ ],
+ [
+ -0.5413, +0.2330, +0.8049, -0.1323, +0.1069, +0.8225, +0.5138,
+ +0.5381, +0.4208, +0.0392, -0.8431, +0.4248, -0.0927, +0.0971,
+ -0.1803, -0.9058, +0.8480, -0.3816, -0.6984, -0.3827, -0.2599,
+ +0.2374, -0.1889, -0.3184, -0.3037, +0.2556, -0.3310, -0.0797,
+ -0.0166, -0.8056, +0.5743, +0.3340, -0.3261, -1.1856, -0.1586,
+ -0.2816, -0.4614, -0.8387, -0.8821, -0.2603, -0.3087, -0.4192,
+ +0.0168, -0.2696, +0.2092, -0.2967, -0.3088, +0.1593, -0.3350,
+ +0.7112, +0.6204, +0.1440, -0.1400, +0.4595, +0.6284, -0.4182,
+ +0.4677, +0.4245, -0.2426, +0.4360, +0.5265, +0.4846, +1.0185,
+ -0.5593, +0.9728, +0.4769, +0.7221, +0.6885, -0.0294, +0.2469,
+ +0.0124, +0.5220, -0.4949, -0.1693, +0.6676, +0.7299, -0.0920,
+ +0.5961, -0.4980, -0.3700, +0.4610, -0.0052, -1.1549, -0.2259,
+ -0.7090, +0.0568, +0.5237, -0.4150, +0.3867, -0.0865, -0.0347,
+ +0.2796, -0.3372, +0.4407, +0.4653, +0.4029, +0.0542, -0.4820,
+ +0.5448, +0.0841, +0.3830, -0.5634, +0.3101, -0.3656, +0.5915,
+ +0.5094, +0.0265, +0.3061, -0.1867, +0.4472, +0.0831, -1.4864,
+ +0.6205, -0.7317, +0.0345, +0.0241, -0.4189, +0.2699, -0.0454,
+ +0.1761, +0.1418, +1.0411, -0.1500, -0.5850, +0.4274, -0.2819,
+ -0.0049, -0.0539
+ ],
+ [
+ +0.3625, +0.0194, -0.3223, -0.1543, -0.3422, +0.1361, -0.1979,
+ +0.1716, +0.1964, +0.1080, -0.2562, +0.5515, -0.6231, +0.0645,
+ -0.2820, -0.4138, -0.3513, -0.1298, +0.1236, -0.1571, +0.0996,
+ -0.4628, -0.0855, +0.6111, +0.2735, +0.1079, +0.0759, -0.8790,
+ +0.2145, -0.6007, -0.0575, +0.4727, -0.0139, -0.2520, -0.1913,
+ -0.1010, +0.0459, +0.2930, -0.5473, -0.6486, +0.0525, -0.9643,
+ +0.0756, -0.0343, -0.3489, +0.2362, +0.5423, -0.2968, -0.0831,
+ -0.4753, -0.2939, +0.1316, -0.6055, +0.3439, -0.4793, -0.9334,
+ -0.0404, -0.0067, -0.1639, -0.2048, +0.2024, +0.0257, -0.7722,
+ +0.3862, +0.3280, -1.2964, +0.3508, -0.4320, -0.0618, +0.0669,
+ -0.1487, +0.0590, -0.0657, -0.5083, -0.3131, -0.3795, -0.3027,
+ -0.7377, -0.2656, -0.1819, +0.0315, -0.1914, -0.3061, -0.0285,
+ +0.1491, -0.3607, -0.6081, +0.3564, +0.2935, -0.1484, +0.1152,
+ -0.5023, +0.1752, -1.5863, +0.1823, -0.3487, +0.3613, +0.0175,
+ -0.2217, -0.1352, -0.5851, +0.1753, -0.0871, +0.5474, +0.3244,
+ -0.8566, -0.3348, -0.0279, +0.5935, +0.2750, +0.0797, +0.1091,
+ -0.8979, +0.7681, +0.3679, +0.3083, +0.2425, +0.1221, +0.3024,
+ +0.4512, +0.0880, -0.0056, -0.1940, +0.3921, +0.4914, -0.7178,
+ -0.2134, +0.1143
+ ],
+ [
+ +0.0679, -0.0794, -0.3814, +0.2536, -0.1512, +0.1385, -0.1787,
+ -0.1347, -0.1905, +0.0860, +0.1867, -0.0860, +0.0923, +0.1577,
+ +0.1129, +0.2066, +0.2144, +0.0983, +0.1848, +0.3214, -0.3866,
+ +0.1045, -0.0303, -0.2351, -0.1582, -0.0153, -0.1058, +0.0740,
+ -0.0575, -0.1356, +0.0975, +0.2816, +0.0862, -0.2179, -0.4657,
+ -0.2575, -0.1307, -0.1683, -0.0066, +0.0145, +0.2131, -0.0987,
+ +0.2698, +0.1188, +0.0539, +0.3335, -0.0699, -0.1512, -0.0397,
+ +0.0569, +0.0859, +0.2909, +0.0149, -0.0338, +0.3416, +0.0462,
+ -0.0262, +0.3987, -0.1117, +0.0869, +0.2025, +0.0820, +0.0110,
+ -0.0663, -0.0989, +0.0121, +0.2080, +0.2500, -0.2012, -0.0425,
+ -0.3801, +0.2980, -0.1070, -0.2112, -0.2358, -0.0148, +0.0342,
+ +0.1877, -0.0190, -0.3003, -0.0384, +0.3230, +0.0058, +0.1883,
+ +0.1429, -0.0525, -0.0369, +0.1965, +0.4171, -0.2498, +0.3534,
+ +0.1377, -0.1843, -0.0786, -0.0334, -0.2252, -0.2525, -0.4377,
+ +0.0970, -0.0632, -0.1115, +0.1151, -0.2193, +0.4269, +0.0589,
+ +0.2567, -0.0083, -0.1317, -0.0140, -0.2162, +0.1460, +0.2144,
+ -0.2364, +0.2052, +0.1361, +0.3009, -0.0415, +0.0753, +0.1605,
+ -0.0008, +0.1161, -0.0075, +0.1132, -0.1271, +0.5005, +0.0962,
+ +0.0963, +0.2632
+ ],
+ [
+ -0.0499, -0.1868, +0.0577, +0.1447, +0.1636, -0.3556, -0.1492,
+ +0.0388, -0.1583, -0.0774, +0.0437, +0.0230, -0.1318, +0.0701,
+ +0.3213, -0.0902, -0.1691, +0.0205, +0.0912, -0.0380, +0.0704,
+ -0.0709, -0.0177, -0.1689, -0.3108, +0.0728, -0.2808, -0.0876,
+ -0.0702, -0.4691, +0.3010, +0.2589, -0.1658, -0.3264, +0.1423,
+ +0.0444, -0.0579, +0.0883, -0.1900, -0.3669, +0.0899, +0.0842,
+ +0.1387, +0.0023, +0.0807, -0.1238, +0.1961, +0.0881, -0.0594,
+ -0.1222, -0.2213, +0.2254, +0.0348, -0.1841, -0.1994, -0.4183,
+ +0.0770, -0.2080, -0.0388, +0.0821, +0.0289, +0.0999, -0.0389,
+ +0.0711, -0.2250, -0.0025, -0.2014, +0.2883, +0.3065, -0.1356,
+ -0.0597, -0.1037, -0.0451, -0.1849, +0.0913, -0.0457, +0.0217,
+ -0.0981, +0.0654, -0.1176, +0.1646, +0.2142, -0.3388, -0.5200,
+ -0.2313, -0.1905, +0.0708, -0.0961, -0.1217, -0.1662, -0.1982,
+ +0.1837, -0.0128, +0.0935, +0.0200, +0.1873, -0.2688, +0.2296,
+ +0.2719, -0.2736, +0.2598, +0.1866, +0.1070, -0.0368, -0.0790,
+ +0.3079, -0.1966, +0.0417, -0.2708, +0.0273, +0.3073, +0.2085,
+ -0.1423, -0.1677, -0.2092, -0.3405, +0.1060, -0.3134, -0.1067,
+ +0.0272, +0.1868, -0.2262, +0.2388, -0.4858, -0.0006, +0.3641,
+ -0.0149, +0.1635
+ ],
+ [
+ -0.0293, -0.6816, +0.0207, -0.3203, +0.5807, +0.2284, +0.0608,
+ -0.0782, -0.7455, +0.0780, +0.1824, +0.2558, +0.6335, +0.3215,
+ -0.1083, -0.4061, +0.2560, -0.2431, -0.9005, -0.7526, +0.0429,
+ +0.0809, +0.3405, -0.1655, +0.1869, -0.4230, +0.1290, -0.0598,
+ -0.8880, -1.3204, -0.6279, +0.1188, -0.1528, +0.1304, +0.3002,
+ -0.2851, -0.4151, +0.1325, +0.0967, -1.1975, -1.4119, -0.1437,
+ +0.1030, +0.1688, +0.1357, +0.5681, +0.1686, -0.6273, -0.0961,
+ -0.1940, -0.4501, -0.3292, -0.4322, -0.0958, -0.1608, +0.0745,
+ -0.2823, +0.1386, -0.3401, -0.0044, +0.1450, -0.9192, +0.1943,
+ -1.0786, -0.3468, -0.2210, -0.8898, +0.2841, -0.1573, +0.0027,
+ +0.5140, +0.2573, -0.2886, -0.1363, +0.0590, -0.0752, -0.5069,
+ +0.4482, -0.2980, -0.0193, +0.0242, -0.1357, +0.3524, -0.0679,
+ -0.4083, -0.1631, -0.0261, +0.0079, +0.4069, +0.0506, +0.0312,
+ +0.1185, +0.3524, -0.1431, -1.3855, +0.2428, -0.4439, +0.2224,
+ -0.6006, +0.1477, -0.1597, -0.4273, -0.1280, +0.4005, +0.2949,
+ +0.1104, -0.0679, +0.3744, +0.6098, -0.5700, +0.1008, +0.2341,
+ -0.4750, -0.3084, -0.2798, -0.7803, +0.6083, -0.0650, +0.0205,
+ -0.1667, +0.0401, -0.1926, +0.4924, +0.1119, -0.8171, +0.2006,
+ +0.3861, -1.1334
+ ],
+ [
+ +0.3379, -0.0630, -0.3660, +0.3327, +0.0593, -0.1086, +0.5011,
+ +0.1324, -0.2487, -0.0698, +0.1031, -0.1188, +0.2941, +0.0543,
+ -0.0504, -0.1540, -0.0798, +0.2290, +0.2369, -0.0698, +0.1134,
+ +0.4617, +0.1530, -0.3301, -0.2881, -0.2488, +0.0245, -0.0285,
+ -0.2306, -0.1149, -0.0003, -0.0923, -0.1315, +0.0210, -0.1870,
+ +0.0622, -0.0506, -0.0135, -0.1995, -0.0287, +0.0711, -0.0130,
+ +0.3577, -0.1441, -0.1204, -0.3320, -0.2458, -0.0879, +0.0139,
+ +0.2201, -0.3011, +0.0393, +0.2918, -0.0472, -0.1514, -0.1190,
+ -0.0056, +0.2567, -0.3284, -0.5337, -0.0050, -0.1086, -0.1834,
+ -0.3311, -0.1851, +0.1848, -0.0175, -0.1277, -0.1361, +0.1587,
+ +0.0424, +0.0936, +0.1683, -0.0294, +0.1407, -0.0313, -0.0279,
+ +0.2524, +0.1912, +0.1002, +0.1337, +0.0550, +0.1725, +0.0323,
+ +0.1961, +0.2280, +0.4421, +0.1152, +0.0211, +0.1519, -0.0487,
+ -0.0903, +0.1088, -0.1067, -0.1932, +0.0741, -0.1907, -0.1498,
+ +0.3873, -0.1806, -0.1683, +0.1372, +0.0304, +0.0863, -0.1042,
+ -0.0114, +0.1071, +0.1654, +0.2195, -0.1274, -0.2964, +0.1572,
+ +0.1514, +0.0736, +0.1129, +0.1630, -0.0438, +0.2270, -0.0895,
+ +0.2149, +0.2307, +0.0664, +0.0300, +0.3303, +0.0999, +0.3439,
+ +0.0904, +0.1683
+ ],
+ [
+ +0.0340, -0.0989, -0.0451, +0.2294, +0.2241, +0.2625, -0.1814,
+ +0.0073, -0.3025, +0.3027, -0.3313, -0.0211, +0.0333, +0.1126,
+ -0.0768, -0.1360, -0.3812, +0.2599, -0.2655, -0.0163, +0.2248,
+ -0.1354, +0.1735, -0.1578, -0.0827, +0.1191, +0.1209, -0.2733,
+ +0.2359, -0.2004, -0.0624, +0.2381, -0.0092, -0.0115, +0.0134,
+ -0.2366, +0.2267, -0.3574, -0.0541, -0.3561, -0.0686, -0.0024,
+ -0.0964, -0.0168, +0.0758, +0.1287, +0.0970, +0.2117, +0.4078,
+ +0.2125, -0.1938, +0.0866, -0.2325, -0.0116, -0.2797, -0.2403,
+ +0.1878, -0.2757, -0.2458, +0.2984, -0.0047, +0.1370, -0.3392,
+ -0.1224, +0.2413, +0.1075, +0.3686, +0.2316, -0.0368, +0.0658,
+ +0.0282, +0.2231, -0.1776, +0.0984, +0.2372, +0.2452, +0.0692,
+ -0.0771, +0.2522, +0.2017, +0.1455, +0.2602, +0.1297, -0.0145,
+ -0.1484, +0.0469, -0.0616, +0.2906, +0.1185, +0.2783, +0.0614,
+ +0.0493, -0.2796, +0.1048, -0.2029, +0.1820, -0.2846, +0.0042,
+ +0.0699, +0.2208, +0.1126, -0.0028, -0.0612, -0.0730, -0.0883,
+ +0.1355, -0.2635, -0.4806, +0.1522, -0.5489, -0.1904, -0.2650,
+ +0.1945, -0.0204, -0.0391, +0.2104, +0.2261, +0.2982, -0.5277,
+ +0.0563, -0.0652, -0.0232, +0.0058, +0.0107, +0.1389, -0.1388,
+ +0.3945, +0.1338
+ ]])
-weights_dense2_w = np.array([
-[ +0.4072, -0.1577, +0.0300, -0.0725, +0.6609, -0.5568, +0.0820, -0.2073, +0.3434, +0.0637, +0.0899, -0.1563, +0.1371, +0.7268, -0.4818, +0.0706, -0.1386, +0.4026, +0.2577, -0.4374, +0.4362, +0.2120, +0.0860, +0.0373, -0.5472, -0.4427, +0.0769, +0.3067, +0.3401, -0.0008, -0.7384, +0.0566, -0.0583, -0.3481, -0.2953, -0.1032, -0.7956, -0.6262, -0.0733, -0.6908, -0.4126, -0.2014, +0.6791, -0.5321, +0.5106, -0.1055, +0.0604, -0.5233, -0.8984, -0.4227, -1.3192, +0.3693, +0.2789, -0.2774, +0.0132, -0.1824, -0.0690, -1.6134, -0.2901, -0.1739, -0.5780, -0.3432, +0.0980, -0.3106],
-[ -0.3167, -0.2520, +0.1710, +0.1912, +0.0268, -0.1353, +0.0637, -0.3158, +0.3448, +0.4247, -0.2795, -0.6464, -0.5002, +0.1116, -0.0497, -0.7619, -0.1402, +0.0142, -0.0314, -0.0418, -0.6087, +0.1742, -0.2843, -0.3738, +0.0595, +0.2382, +0.7762, +0.4531, -0.8817, -0.0971, -0.4319, +0.0168, -0.7739, -0.6792, +0.3594, -0.2188, -0.7423, +0.2473, -0.2793, +0.0149, -0.2970, -0.0695, +0.6082, -0.5475, -0.5990, +0.6079, +0.2662, +0.2195, -0.5335, -0.1782, -0.1657, +0.0951, -0.1763, -0.3554, -0.1032, +0.3347, -0.2818, -0.6144, -0.2387, -0.3771, -0.0378, +0.0776, -1.4711, -0.1353],
-[ -0.2935, -0.8083, -0.1306, +0.1952, -0.1178, -0.4799, +0.0777, -0.4029, -0.5699, -0.1755, -0.0172, +0.1791, -0.0261, -0.2480, +0.0181, -1.0284, -0.2705, +0.4318, +0.1634, -0.2889, -0.0075, -0.1050, +0.0859, +0.0544, -1.0494, +0.0273, -0.1991, -0.2565, -0.3891, -0.1883, -0.4818, -0.2458, +0.2761, +0.1295, -0.2284, -0.0114, +0.2609, -0.1632, -0.0384, +0.0558, -0.2330, -0.3149, -0.1879, -0.0787, +0.2492, -0.1629, +0.3027, +0.5257, -0.4112, -0.2063, -0.0745, +0.0864, -0.1151, -0.3392, +0.2214, +0.2084, -0.1933, +0.0103, -0.0245, +0.0280, +0.0170, -0.1814, +0.0239, -0.6701],
-[ +0.0470, -0.1471, -0.3533, -0.2277, +0.2617, -0.2955, -0.2491, -0.1937, +0.2634, +0.0681, -0.2869, -0.1950, +0.1615, +0.2557, -0.0025, +0.2327, -1.0104, +0.3358, +0.2386, -0.6202, -0.0829, +0.3342, +0.0617, -0.0119, -0.6297, -0.2430, +0.2088, +0.0102, +0.3480, -0.0119, -0.3172, +0.1668, -0.2217, +0.1130, -0.0817, +0.0391, -0.0480, -0.1680, -0.1306, -0.4677, -0.1638, -0.3569, -0.1594, +0.2110, +0.3875, -0.1732, -0.0210, -0.3070, -0.7983, +0.2381, -0.0294, -0.2019, +0.1801, +0.2116, +0.2506, -0.0342, -0.7177, -0.6430, +0.3333, -0.7577, -0.3507, -1.0563, -0.4578, +0.0739],
-[ +0.0584, +0.2110, +0.2883, +0.4496, -1.4306, -0.3233, +0.1243, -0.5887, +0.1677, -0.1064, -0.3807, -0.0439, -0.8551, -1.2286, +0.2521, -0.0060, +0.6236, -0.1993, +0.3985, -0.2662, -0.0002, +0.0486, -0.2869, -0.6390, -0.1125, -1.3003, +0.1867, -0.3180, -0.7481, +0.1080, +0.3788, -0.3003, -0.1799, -0.4549, -0.0974, -0.0827, +0.3762, +0.2356, -0.2579, +0.4377, -0.1295, -0.3391, -0.7046, -0.1904, -0.1341, -0.0194, -0.2193, -0.3140, -0.1927, -0.3742, +0.2955, +0.1099, -0.5704, +0.0968, -0.0678, -0.1847, -0.0211, -0.3002, -0.4862, +0.4810, -0.0444, +0.4728, +0.1298, -0.0902],
-[ +0.0349, +0.9685, -1.9391, -0.3447, -0.1261, -0.3633, -0.0598, -0.6471, -0.8648, -0.7718, -0.4766, -0.8915, -0.5728, -0.5278, +0.5933, -0.3178, +0.0116, +0.3050, +0.3750, -1.1527, -0.0571, -0.2033, +0.4198, +0.2105, -0.7927, -0.6716, -1.0696, -0.7200, -0.5883, -0.6538, -0.4865, -0.8737, +0.0426, +0.2175, -0.2165, -0.0444, -0.1326, -0.0308, -0.1097, +0.0105, -0.1852, -0.3861, -0.2117, -0.5265, +0.0367, -0.0218, +0.2472, -0.2354, -1.1444, -0.3036, -1.6033, +0.1154, -0.3195, +0.3943, -0.8171, -0.0495, -0.0950, -0.3764, -0.1523, -0.8749, +0.2594, +0.2451, -0.1734, -0.0927],
-[ +0.4523, +0.0513, -0.0013, +0.1556, +0.2430, -1.2187, -0.3108, -0.7597, -0.7845, -0.6297, -0.0224, +0.3207, +0.2222, -0.2645, +0.1510, +0.1624, -0.0568, -0.8426, -0.3564, +0.0187, +0.2791, +0.0447, -0.1822, -0.2627, +0.0078, -0.9392, +0.0805, +0.0339, +0.3228, -0.0153, -1.4823, -0.0994, +0.2658, -0.0138, -0.1071, +0.2001, -0.3299, -0.5982, -0.2859, -0.1269, +0.0496, -0.0371, +0.3491, -0.3822, +0.1167, -0.2964, -0.4635, +0.0549, -0.6313, -0.4994, -0.2447, +0.0584, +0.2663, -0.0663, -0.1714, -0.1748, -0.5364, -0.3646, +0.1584, +0.0349, +0.1420, -0.6877, -0.3539, +0.2209],
-[ -1.2158, -0.7080, +0.1037, -0.1613, +0.0811, -0.9051, -0.4186, -0.6072, -0.6212, +0.0362, -0.3524, +0.2563, -0.7313, -0.2856, +0.0658, -0.1271, -0.1249, -0.6959, -0.4723, +0.4467, -0.1244, -0.0056, +0.5042, -0.5181, +0.0475, +0.2931, +0.3883, -0.2017, -0.0388, +0.0403, +0.1562, -0.9404, +0.0620, -0.5598, -0.5657, +0.0578, +0.0086, -0.5689, -0.9304, +0.3161, -0.1303, -0.4087, -0.5053, -0.1267, +0.0123, -0.6312, -0.6991, -0.0800, -0.8634, +0.2347, +0.1449, +0.3955, +0.4396, -0.0684, +0.2644, -0.7668, -0.1511, +0.0324, +0.0823, -0.3579, +0.0592, +0.0904, +0.2380, +0.0873],
-[ -0.6992, +0.1539, +0.4253, -0.2513, +0.1882, +0.6842, -0.6867, -0.2942, -0.3434, +0.2486, -0.4180, -0.6950, +0.2628, +0.7324, -0.2667, -0.1330, -1.3123, +0.0990, -0.1324, -0.0016, -0.0310, +0.0778, -0.1325, +0.2886, -0.2052, +0.0094, +0.1791, +0.1105, +0.4348, -0.6778, -0.3301, +0.1438, +0.1093, +0.0140, -0.1957, -0.1226, +0.0676, +0.9343, -0.1993, +0.1818, -0.1565, +0.3443, -0.1359, -0.5234, +0.2591, +0.3769, +0.4966, -0.6424, -0.0288, +0.0357, -0.3554, -0.1676, -0.2453, -0.4502, -0.3745, -0.1692, -0.2449, -0.2132, -0.0001, +0.0087, +0.3669, +0.3835, +0.0003, +0.6565],
-[ +0.2329, -0.0695, +0.4082, -0.0004, +0.0059, +0.1418, +0.1081, -0.3141, +0.2218, -0.0538, -0.0670, +0.0018, -0.1211, -0.0491, -0.3059, -0.4239, -0.1665, +0.0700, +0.4327, -0.5063, +0.3045, +0.7774, +0.4464, +0.2276, -0.3467, +0.5197, +0.1607, -0.1339, -0.1663, +0.0881, +0.0232, -0.3337, +0.0157, -1.1305, -0.1427, -0.7464, -0.3650, +0.2386, +0.2734, +0.5966, -0.4067, +0.3709, +0.2986, -0.3682, -0.1436, +0.3259, +0.3393, -1.2748, -0.5180, +0.1099, -0.0843, +0.0421, +0.1176, +0.0935, +0.3649, +0.1282, +0.2074, -0.4244, -0.3379, -0.8103, -0.1238, -0.6615, -0.5262, -0.9899],
-[ +0.2683, +0.0401, -0.2063, -0.0863, -1.1390, -0.1614, +0.4551, -0.2386, -0.9135, -0.1037, +0.3364, +0.0943, +0.3665, -0.2748, +0.2592, -0.0339, +0.4767, -0.1381, -0.2326, +0.0600, +0.1522, -0.3524, +0.4203, -0.4977, -0.2533, -0.4959, +0.1211, -0.1722, +0.0681, -0.2369, +0.2398, +0.2182, +0.0582, +0.4106, -0.2708, +0.1474, +0.3402, +0.3310, +0.1319, -0.2479, +0.1749, +0.3886, -0.1866, +0.0482, +0.2373, -0.4678, -0.1560, +0.4025, -0.3261, +0.6000, -1.2795, +0.2571, -0.0926, -0.2927, +0.2793, -0.4958, +0.0614, -0.0140, -0.1622, -0.4095, -0.1560, -0.2754, +0.1172, -0.1319],
-[ -0.5295, -0.0999, +0.0220, +0.3271, +0.2059, -0.4296, +0.3921, -0.0843, -0.4874, +0.3199, +0.4602, -0.8274, +0.2366, +0.6108, -0.3201, +0.1853, +0.3175, +0.0078, -0.4971, +0.7472, +0.1544, -0.3018, +0.2934, -0.2034, +0.3348, +0.3705, -1.3035, +0.2084, +0.4699, +0.0053, -0.3233, -0.8634, -0.4203, -0.6225, -0.2153, +0.5059, +0.1571, -0.7581, -0.9790, +0.1196, -0.6516, +0.1740, +0.3164, -0.0439, -0.7366, -0.0850, +0.4464, -0.9298, +0.3098, +0.6134, +0.0513, -0.1314, -0.7751, -0.4632, +0.2998, -0.2841, -0.1156, +0.2272, -0.6840, +0.2023, +0.2771, +0.0181, +0.3241, +0.0077],
-[ -0.0280, -1.3387, -0.3547, -0.0743, +0.1483, -0.0627, -0.3067, -0.3430, +0.0588, +0.0807, +0.4038, +0.4257, +0.4200, -0.1636, -0.6085, +0.0772, +0.3777, -0.0100, -0.5085, -0.4027, +0.1783, +0.3648, +0.2458, -0.6546, -0.3100, -0.0142, +0.5146, +0.5179, +0.3174, -0.0085, -0.5655, +0.6930, -0.0170, -0.0840, -0.4820, +0.3951, +0.2091, -0.1006, -0.1043, -0.1592, +0.5631, +0.0762, +0.0353, +0.3549, -0.5710, +0.6521, -0.5372, +0.5439, -0.6006, -0.3861, -0.9696, +0.3836, +0.0144, -0.0445, +0.2625, +0.0893, +0.3533, -0.0816, +0.3946, -0.1645, -1.0470, +0.4605, +0.2646, -0.0709],
-[ +0.1597, -0.1930, +0.1695, +0.0883, +0.3863, -0.0690, -0.3626, -0.0751, -0.2489, -0.2651, +0.3078, -0.0279, +0.0915, -0.3568, +0.0135, +0.0301, +0.1845, +0.0936, +0.1046, -1.0295, -0.4317, +0.0053, +0.3181, +0.1241, +0.1828, -0.1518, +0.3664, -0.0194, -0.0056, -0.9545, -0.3588, +0.5326, -0.9760, -0.2063, +0.4710, -0.7108, -0.0157, -1.2469, -0.3011, -0.2258, -0.1896, +0.0305, +0.1823, +0.2524, +0.0734, -0.0195, +0.2741, +0.0458, -0.0258, -0.1458, -0.0499, +0.2720, +0.2632, -0.1566, -0.3169, +0.4742, -0.1019, -0.1814, +0.3763, +0.2875, +0.4905, -0.4019, +0.2122, -0.9641],
-[ +0.3189, +0.1388, -0.3550, -0.3842, +0.0898, +0.0547, -0.7110, -0.1182, +0.0259, +0.0704, +0.1494, -0.1821, -0.1159, +0.0213, +0.2096, -0.4418, -0.6512, +0.1241, +0.0305, -0.1008, +0.0562, +0.0968, +0.0081, +0.1199, +0.1381, -0.2673, -0.2059, -0.0357, +0.3140, +0.2211, -1.0964, +0.1492, +0.1469, -0.5406, -0.0557, +0.3461, -0.0567, +0.2042, +0.1409, -0.1752, -0.5634, -0.7240, -0.0985, +0.4507, -0.0405, +0.1548, -0.0590, +0.2785, +0.0398, -0.0766, +0.3026, -0.3093, -0.0211, +0.3418, -0.0372, +0.1007, -0.1287, -0.1216, +0.1111, +0.0391, -0.4399, -0.1719, -0.7748, +0.0015],
-[ -0.8898, +0.1587, -0.1158, -0.2147, +0.1854, +0.0673, -1.6078, +0.3145, +0.1855, +0.0176, -0.6532, +0.1946, -0.2744, -0.2392, +0.0001, -0.5411, -0.3275, -0.6474, -0.3419, +0.0351, -0.2511, +0.2090, -0.1401, -1.2570, -0.3467, -0.1794, -0.0238, -0.3511, +0.0885, +0.2340, -0.2762, +0.2349, -0.0718, -0.1801, -0.5107, +0.1164, +0.2997, -0.1047, +0.1091, +0.1830, -0.0604, -0.5492, +0.0451, +0.5144, -0.1682, -0.2848, -0.3148, -0.0800, -0.6753, +0.8912, -0.3167, +0.1553, -0.1064, +0.4668, -0.1185, +0.0205, +0.2634, -1.4268, -1.4053, +0.1865, -1.1680, -0.5715, -0.1411, -0.0048],
-[ -1.1451, -0.8007, -0.7188, +0.2194, +0.0224, -0.3902, -1.0708, +0.1315, -0.4508, -0.0171, -0.1646, -0.8523, +0.0246, -0.2483, +0.2628, -0.0709, +0.1284, -0.0332, +0.2452, +0.6453, +0.0372, +0.0580, -0.4814, -0.0367, -0.6464, -0.1864, -0.0876, -0.3798, -0.1084, -0.2326, +0.3449, -1.0821, +0.3558, -0.2093, -0.1611, +0.0181, -0.1593, -0.7092, -0.5308, +0.3392, -0.2771, -0.8510, -0.0332, +0.1636, -0.1288, -0.1509, -0.0123, -0.3427, -0.2880, -0.9719, -1.0379, -0.2061, -1.2064, +0.0703, +0.0296, -0.5942, +0.1367, +0.2798, -0.9892, +0.2638, +0.6593, +0.3467, +0.2717, -0.2685],
-[ -0.2935, -0.2457, -0.1847, -0.1120, +0.2738, -0.1316, -0.1218, +0.1977, +0.2899, -0.2914, -0.9864, +0.4904, -0.1894, -0.0953, +0.0076, -0.0067, -0.6684, -0.0314, +0.0872, +0.4462, +0.2811, -0.1232, -0.3337, -0.7796, -0.7328, +0.0966, -0.1373, +0.4435, +0.1715, +0.1189, -0.3743, +0.3548, -0.0802, -0.5682, -1.3086, -0.0364, -0.2844, -0.3369, +0.3544, -0.0662, -0.1867, -0.3540, -0.2038, -0.4980, +0.3799, -0.1018, -0.9164, +0.3697, -0.0067, -0.5775, -0.1818, +0.0175, -0.1748, +0.4688, -0.5308, -0.4231, +0.1482, -0.5617, -1.2285, +0.3348, +0.2546, +0.3433, -0.0552, -0.4434],
-[ -0.5986, -0.0456, -0.0579, +0.0098, +0.5195, +0.2289, -0.0547, +0.0712, +0.3579, +0.0200, -0.3965, +0.3115, -0.3113, -0.2659, +0.2821, -0.0527, -0.1284, -0.5430, -0.6974, +0.0659, -0.4766, -0.1915, -0.1467, -1.0685, -0.5390, +0.4510, +0.3700, +0.1105, -0.1987, -0.0297, +0.0635, +0.2345, +0.1594, -0.0839, -0.1305, -0.1000, +0.2680, +0.1591, -0.5661, +0.1602, -0.0069, -0.1623, -1.4309, -0.1520, -0.0090, -0.3502, -0.6969, -0.0949, +0.0562, -0.0869, -0.2017, +0.0475, +0.5724, +0.1771, -0.0398, -0.7070, -0.1830, -0.0220, -0.1941, -0.9674, +0.0262, -0.1637, -0.0094, +0.4634],
-[ -0.0007, -0.1887, +0.2479, +0.0483, +0.2260, -0.1202, -0.2455, -0.5935, -0.0951, +0.2204, +0.2221, +0.3503, +0.0909, -0.2512, +0.0191, -1.0021, -0.2003, +0.6241, +0.2894, -0.0605, -0.4665, -0.2199, -0.1427, -1.2488, -0.1763, +0.3383, +0.4418, +0.2648, -0.9742, +0.2356, +0.1240, +0.1305, -0.4167, +0.0351, +0.3759, -0.2039, +0.0351, -0.6693, -0.8583, +0.0616, +0.2169, -0.4452, -0.4786, -0.0808, +0.0579, -0.1770, +0.1975, -0.3272, -0.0747, -0.3015, -0.0030, -0.3779, -0.1084, +0.0285, +0.2040, +0.0064, -0.6207, +0.1540, +0.2691, -0.4465, +0.3775, -0.7416, +0.0563, -0.0898],
-[ +0.1254, +0.4967, +0.1999, -0.2316, +0.2500, -0.0650, +0.5256, -0.4156, -0.2651, +0.1705, +0.0690, -0.0314, -0.6562, +0.0699, -0.8152, +0.1149, +0.0980, +0.6136, +0.2356, -0.4453, +0.3604, +0.4151, +0.1505, -0.3277, -0.2119, +0.0359, -0.1290, -0.1692, -0.0831, -0.0644, -0.1416, -0.0558, +0.0298, -0.0870, -0.1409, -0.5095, -0.3006, -0.0250, +0.4266, -0.3381, -0.3222, +0.3626, -0.0441, +0.2182, -0.1688, +0.0500, +0.2828, -0.2694, -0.0921, +0.1291, -0.7688, +0.2200, +0.1006, -0.3204, -0.1588, -0.5138, -0.6525, -0.3203, +0.5614, +0.1583, -0.3336, -0.6822, -0.0527, -0.0729],
-[ +0.2401, -1.5531, -1.1594, +0.0219, -0.1680, -0.0307, -0.1397, -0.4195, +0.2302, +0.2705, +0.0780, -0.3434, +0.2748, -0.1826, -0.4300, -1.2819, -2.0983, +0.2545, +0.3414, +0.1059, +0.1937, +0.0885, +0.3678, +0.0745, -0.2122, -0.2374, +0.2199, +0.1136, +0.0291, -1.5077, -0.6176, +0.0825, +0.0813, -0.2417, -0.3546, +0.2231, +0.3004, +0.0066, -0.0259, +0.5017, -0.6783, -0.5061, +0.0575, -0.1790, -0.4460, -0.6383, -0.1353, -0.1327, +0.0067, +0.2322, -0.0208, +0.2877, +0.1562, -0.5431, +0.0227, -0.1356, +0.0365, -0.2004, -0.1343, +0.1730, -0.5527, +0.1656, +0.1991, -0.8294],
-[ +0.4524, +0.7614, -0.1415, -0.0766, +0.1568, +0.0408, +0.0539, -0.2856, +0.1050, -0.1615, -0.8484, +0.5459, +0.1695, +0.2730, -0.0014, +0.6478, +0.1634, -0.0715, -0.0612, -0.1463, -0.1214, -0.1158, +0.1563, +0.2598, +0.0758, -0.4645, -0.2913, -0.3810, -0.7767, -0.3182, +0.1396, +0.1954, -0.0150, -0.1029, -0.2936, -0.5085, -0.0514, +0.1485, -0.1216, -0.1714, -0.1193, +0.4209, +0.0558, -0.4255, +0.2840, -0.5583, -0.3015, -0.2423, +0.0089, -0.4503, +0.3085, +0.2502, +0.2749, +0.2995, -0.7768, -0.3364, -0.5740, +0.0843, -0.2877, -0.5731, -0.3221, -0.2253, -0.3227, -0.0065],
-[ +0.0540, -0.0224, -0.3116, -0.5707, -0.0632, -1.4873, +0.2964, -0.4894, -0.2578, +0.2032, +0.0937, -0.4259, -0.0588, +0.4007, +0.1099, -0.2633, -0.3422, +0.1973, -0.0170, +0.0451, +0.1670, +0.4853, +0.2068, +0.2066, -0.1544, +0.0191, -0.0957, -0.9554, -0.6965, -0.6022, +0.1666, +0.0026, +0.5176, -0.0584, -0.9679, -0.2898, +0.2451, +0.2050, -0.2909, +0.0002, -0.0763, -0.2100, -0.1929, +0.0985, -0.2612, -0.3684, +0.3190, -0.5681, +0.2765, -0.1663, +0.0422, +0.3252, +0.2741, -0.2385, -0.1602, +0.2504, -0.2370, +0.0891, -0.2204, +0.1525, +0.0444, +0.0188, +0.3538, -0.0313],
-[ +0.0984, +0.2622, +0.1601, -0.3252, -0.2292, -0.0494, +0.2185, +0.2202, +0.4945, -0.3545, -0.1730, -0.6882, -0.6645, -0.1178, -0.2491, +0.2497, -0.1072, -0.2019, -0.0944, +0.2118, -0.2281, +0.2338, +0.0924, +0.1178, +0.0920, +0.0422, +0.3113, -1.1795, -0.8658, -0.6011, +0.0714, +0.0290, -0.5830, +0.2370, +0.3508, -0.0178, -0.6966, +0.2269, -0.2966, -0.6947, +0.1769, +0.1461, -1.0021, +0.0781, -0.3731, -0.0153, -0.2721, +0.0699, -0.2057, +0.0791, -0.2055, -0.4152, +0.2414, +0.0939, -0.4560, -0.3566, -0.0381, +0.1090, -0.5755, -0.4283, +0.2504, +0.0863, -0.6288, -0.9822],
-[ -0.0122, -1.0238, +0.0346, -0.2412, -0.7928, -0.3765, -0.2889, -0.0948, +0.1003, +0.7268, +0.2033, -0.6144, +0.4689, +0.2045, +0.0799, +0.2687, -0.3528, +0.0560, +0.0682, +0.0874, -0.1901, -0.0082, +0.3474, -1.0391, -0.4695, -0.0233, -0.0259, -0.0901, -0.1084, -1.4681, +0.0081, -0.3583, -0.2599, -0.1273, -0.6221, +0.2186, -0.1878, +0.4510, +0.0409, -0.1692, +0.1495, -0.3093, -0.0192, -0.1835, -0.5964, +0.0327, -0.5086, +0.2446, -0.5980, +0.1981, +0.0441, -0.1232, -0.4881, -0.6698, -0.0519, -0.0831, -0.6186, -0.6176, +0.0503, +0.2250, +0.0662, -0.8334, -0.0077, -0.7196],
-[ -0.2566, -0.7118, +0.2935, -0.1195, -0.1146, -0.0123, +0.1455, +0.1784, -0.2927, +0.3859, +0.2592, -0.0991, -0.6787, -0.2469, +0.1925, +0.0359, +0.2956, +0.2008, +0.0844, -0.3478, -0.2671, -0.0078, +0.3483, -0.0814, +0.5766, +0.2134, +0.0878, +0.3362, -0.1537, +0.3245, +0.2214, -0.2824, +0.1635, -0.5485, -0.1898, -0.1885, -0.0076, -0.2640, -0.2163, +0.4214, -0.2781, +0.1793, -0.1132, -0.3325, -0.3830, +0.1018, +0.0151, -0.7901, +0.1946, +0.3539, -0.4104, -0.1557, +0.3991, -0.0178, +0.1242, +0.4661, -0.0344, -0.4815, +0.1843, +0.6808, -0.0437, -0.3225, +0.2147, -0.4555],
-[ -0.0638, -0.3322, -0.2387, +0.2534, -0.5326, -0.8410, -0.2301, -0.8189, -1.0886, +0.2326, -0.6260, -0.4507, -0.1068, -0.7282, +0.5187, +0.1134, +0.2561, +0.1038, +0.3431, -1.1889, +0.6843, -0.7160, -0.6177, -0.2679, -0.0451, +0.0572, +0.0807, +0.6884, +0.5089, +0.5436, +0.3386, -0.4832, +0.4377, +0.4794, -0.4475, -0.6358, -0.0388, +0.3861, +0.1041, +0.0640, -0.0701, +0.0340, +0.1640, -0.4543, -0.4830, -0.4003, -0.2349, +0.1010, -0.9351, -0.2592, -0.2928, -0.1271, -1.0826, -0.1847, +0.1704, -0.4475, -0.2948, +0.2068, -0.5627, -0.0093, +0.0881, -0.2164, -0.0049, +0.1603],
-[ +0.1574, -0.0650, -0.2662, +0.1164, +0.4237, -0.6874, +0.4308, +0.4112, -0.0215, -0.0763, +0.2667, -0.3433, -0.4008, +0.2368, +0.1596, -0.1390, -0.4850, -0.0810, +0.1081, -0.1730, -0.8641, -0.3173, -0.2085, +0.1296, +0.2189, -0.4631, -0.3093, +0.0174, -0.0811, -0.4710, +0.0884, -0.5081, -0.2918, -0.0430, -0.1509, +0.4783, -0.1912, -0.7071, -0.3763, +0.0781, +0.1794, -0.3923, -0.9474, +0.3877, -0.2204, -0.2234, -0.0250, -0.3792, -0.6236, +0.1750, -1.4279, -0.4849, -0.6417, +0.1128, -0.2395, -0.1343, -0.5671, -0.1158, -0.1158, -0.3690, -0.1078, -0.2042, -0.3332, -0.2509],
-[ +0.0333, -0.2800, -0.1392, +0.0001, +0.0705, -0.1369, -0.1756, +0.1453, +0.3505, +0.3330, -0.1388, -0.7255, -0.4376, -0.0105, +0.0049, -0.8412, -0.3385, -0.1028, -0.3672, -0.8725, -0.3093, -0.0453, +0.0416, -0.1510, +0.3841, -0.2103, +0.0864, +0.1017, -0.3006, -0.0184, +0.4379, +0.4946, +0.1351, +0.2742, -0.1733, +0.1185, +0.0766, -0.7874, +0.3184, -0.5364, +0.1065, +0.1258, -0.2782, +0.2434, +0.3819, -0.2390, +0.2471, +0.1067, +0.1810, +0.0401, -0.4542, +0.1356, +0.1049, -0.1339, -0.1564, -0.0183, +0.1957, -0.1304, -0.0602, -1.1445, -0.1470, -0.0536, -0.0504, +0.3606],
-[ -0.4758, +0.1761, -0.4846, -1.0187, -0.1317, +0.4057, -0.7446, -0.0029, -0.1074, +0.3271, +0.2986, -0.2398, -0.1716, +0.0999, -0.3667, -0.3235, +0.0859, -0.2204, -0.0886, -0.3845, -0.1990, -0.4520, -0.0453, +0.0367, +0.4391, -0.5058, -0.5205, +0.0438, +0.0949, -0.2365, +0.0034, -0.0972, +0.2460, -0.3402, +0.2640, +0.1962, +1.0076, -0.0240, -0.0881, +0.3680, +0.1796, -0.1007, -0.7938, +0.1620, -0.2244, +0.1086, +0.0835, -0.6081, -0.0907, -0.2010, +0.1411, -0.1199, +0.1650, +0.0291, -0.1783, -0.2652, -0.1174, -0.4219, -0.2506, +0.0413, +0.0460, -0.6699, -1.2885, +0.1545],
-[ +0.1129, -0.1235, -0.0860, -0.3039, +0.0470, +0.1649, -0.6282, -0.0529, -0.0862, +0.2638, -0.0880, -0.9592, +0.3736, -0.1045, +0.3156, -0.3239, -0.0977, +0.1138, +0.1028, +0.0075, -0.4383, +0.0055, +0.1644, -0.5601, +0.0328, +0.2353, -0.1457, +0.0268, -0.1316, +0.1369, +0.1295, -0.0454, -0.0704, -0.6862, -0.1434, +0.1058, -0.0882, -0.2573, -0.1518, -0.0106, -0.1371, +0.3189, +0.4066, -0.2663, -0.5477, +0.3918, +0.0601, -1.2816, +0.0213, -1.0473, +0.2741, -0.0658, -0.3203, +0.0561, +0.2982, -0.0264, +0.3706, +0.3083, +0.4189, -0.3125, +0.2324, -0.0699, -0.0653, +0.3647],
-[ -0.0693, +0.4631, +0.0902, +0.3558, -0.1712, +0.1079, -0.0386, +0.1094, -0.3096, -0.2886, -0.2315, -0.2787, -0.5874, -0.6247, +0.5268, -0.1084, +0.7058, +0.1418, -0.5504, +0.0670, -0.0498, +0.1770, -0.1857, -0.0256, +0.0751, +0.1447, +0.1853, -0.1040, +0.0456, -0.5765, +0.0473, +0.1485, +0.3068, -0.2301, -0.2385, +0.2792, -0.8568, -0.5057, -0.0070, +0.0129, +0.4641, -0.2125, -0.6467, +0.0405, +0.0443, +0.0706, -1.0480, -0.2147, +0.1343, +0.1673, +0.0443, +0.1780, -0.3776, +0.3203, -1.0370, -0.5205, -0.0960, +0.4009, +0.2349, +0.1341, +0.0472, -0.1244, -0.1439, +0.0556],
-[ +0.1598, -1.2782, +0.6361, -0.5370, -0.1456, -0.8548, -1.0428, -0.8559, -0.2116, -0.3637, -0.4516, -0.0612, +0.0129, +0.0675, -0.5432, +0.1841, -0.3792, +0.2158, +0.0596, -0.6030, +0.8449, +0.4651, -0.2557, -1.2864, -0.2594, -0.0408, -0.4892, +0.3451, +0.3054, +0.3925, -0.1913, -0.4430, -0.0513, +0.2399, -0.3757, +0.4300, -0.5091, +0.3864, -0.5291, -0.4042, +0.1954, +0.5566, +0.5156, +0.3129, -0.0074, -0.5308, -0.0965, +0.4685, -0.6602, -0.5140, -0.0500, -0.0512, -0.0719, -0.2983, -0.0757, -1.4385, -0.3450, -0.5004, -0.8424, +0.3685, -0.4302, -0.3252, +0.2352, -0.2397],
-[ +0.2517, -0.0510, -0.8445, -0.0101, -0.2960, +0.3604, -0.0354, -0.2369, +0.4843, -0.2510, -0.0606, -0.0558, +0.1601, +0.1233, -0.0533, -0.6993, -0.1938, -0.0681, +0.1999, +0.1705, -0.3202, -0.0766, +0.2753, -0.4941, +0.2154, +0.1077, +0.2094, -0.0723, -0.1037, -0.0066, +0.0075, -0.0346, +0.2195, +0.1334, -0.1074, +0.0879, -0.2654, +0.2319, -0.1298, -0.3219, +0.3351, -0.6852, -0.5198, -0.2214, -0.0373, +0.2662, -0.2757, +0.0667, +0.1171, +0.1987, +0.4252, -0.5109, -0.5771, -0.2238, -0.0016, -0.1032, +0.2942, -0.4498, -0.1209, +0.0526, +0.0681, -0.0631, -0.2249, -0.5044],
-[ +0.1015, -0.1221, -0.0457, -0.1632, +0.1805, -0.4646, +0.1515, +0.3582, +0.0226, -0.1206, -1.2033, -0.5519, -0.7632, +0.1745, +0.2149, -0.3880, +0.8417, +0.0764, +0.3466, -0.0296, -0.1456, +0.0030, -0.4206, -0.6899, +0.1030, -0.4873, -0.1851, +0.2350, -0.5323, -0.7947, -0.1631, -0.0664, -0.7279, +0.2869, -0.1196, +0.3290, -0.3650, -0.2667, +0.0680, +0.0420, +0.0880, +0.0988, -0.7243, +0.2308, +0.6681, -0.4614, -0.2574, +0.1210, +0.1116, -0.0749, -0.8760, -0.2902, -0.0932, -0.0302, -0.4676, -0.0909, -0.0998, -0.1058, -0.1159, -0.0889, +0.1690, +0.0106, -0.1399, -0.6091],
-[ -0.3936, -0.2924, -0.0566, +0.0908, +0.1229, -0.4908, +0.2100, +0.3042, -0.1919, -0.2383, -0.1356, -0.2715, +0.5147, -0.0937, -0.2436, +0.2805, -0.4522, +0.1256, +0.0199, -0.2870, -0.1586, -0.1113, -0.4221, +0.5571, +0.4612, +0.0522, +0.0469, +0.1000, -0.3156, -0.2255, +0.0661, -0.8530, -0.1866, -0.0146, -0.2175, -0.5078, -0.2589, -0.0452, -0.0606, -0.1495, -0.0759, -0.0676, -0.4239, +0.1552, -0.3918, +0.2913, -0.1573, -0.1386, +0.4216, +0.3134, -0.2761, -0.0822, +0.4101, -0.4691, -0.3533, -0.4907, -0.6454, -0.6846, -0.5219, +0.2845, +0.0990, +0.5448, +0.0043, -0.1068],
-[ +0.2038, +0.3592, -0.0381, -0.3525, -0.4154, -0.0967, +0.1296, +0.0537, -0.0668, +0.1384, -0.3061, -0.3796, -0.0676, +0.2463, +0.0337, +0.2712, +0.2327, +0.2747, -0.0390, -0.4290, -0.1667, -0.2714, +0.0036, -0.2474, -0.0108, -0.5544, -0.3588, -1.0251, -0.1637, -0.6376, +0.1074, -0.2695, -0.2931, +0.2847, -0.3638, +0.2679, +0.3571, +0.3164, +0.0257, -0.1720, +0.0306, -0.0424, -1.3316, -0.2671, +0.1664, -0.6751, -1.3701, -0.1609, -0.5226, +0.2046, -0.2826, +0.0329, -0.1094, +0.0457, +0.2797, -0.3022, -0.2398, -0.1309, +0.1237, -0.6917, -0.1042, -0.5504, +0.0599, -0.0993],
-[ +0.2578, +0.2448, -0.3515, +0.2550, -0.4556, -0.1521, -0.0937, +0.1082, +0.0064, -0.1935, -0.0986, -0.4707, -0.8805, +0.0902, -0.2753, -0.1709, -0.0610, -0.5028, -0.2642, -0.5600, +0.0068, +0.3170, +0.3340, -0.3805, +0.2661, -0.6105, -0.0338, -0.3294, -0.5872, -1.0930, -0.0021, +0.0525, -0.4677, +0.2302, +0.2422, +0.0805, -0.8454, -0.1925, +0.3445, -0.0826, +0.1550, -0.1808, -0.9067, +0.1723, +0.0365, -0.2956, -0.0784, +0.2945, +0.0641, +0.0239, -0.0561, +0.0630, -0.1646, +0.0403, -0.9467, -0.6385, +0.1264, -0.2964, -0.1579, +0.2373, -0.0417, +0.1332, +0.4347, -0.2901],
-[ -0.1863, -0.0242, -1.3175, -0.0210, +0.7122, -0.0967, +0.2298, -0.2379, +0.0625, -1.0683, -0.5156, -0.2993, +0.3003, +0.2490, -0.2035, +0.1202, -0.0714, -0.2515, +0.1050, -0.0244, -0.0323, -0.0142, -0.3243, -1.0355, -0.1945, -0.6769, -0.1482, -0.6095, -1.2543, -0.1212, +0.2109, +0.1281, -0.5586, -0.1869, -0.0505, +0.3053, -1.4947, -0.4599, +0.3102, -0.0713, +0.0294, -0.3146, +0.3229, +0.0378, +0.5098, +0.3752, -1.1693, +0.2510, +0.5305, +0.0346, +0.4966, +0.1118, -0.1061, -0.2008, -0.8236, -0.3700, +0.0883, -0.3168, -0.6185, +0.7089, -0.7464, +0.0953, +0.5762, -0.1075],
-[ -0.0649, +0.0128, -0.1768, -0.6602, -0.1332, +0.2819, +0.2196, -0.5156, +0.3175, +0.1690, +0.2806, -0.4787, -0.6439, +0.2791, -0.2997, +0.1521, -0.1161, -0.0450, +0.3153, +0.2059, -0.0687, +0.1672, +0.1408, +0.1332, -0.0993, +0.3110, +0.0697, +0.1563, +0.1029, -0.9687, -0.0195, +0.2097, -0.1263, +0.0773, +0.0347, +0.1860, -0.0304, -0.2414, -0.8054, +0.1562, +0.2249, -0.9248, -0.8415, +0.3590, -0.1355, +0.3704, -0.4522, -0.3624, -0.7113, +0.2271, -1.0906, -0.5597, +0.2343, -0.3852, -1.1641, -0.2844, +0.3131, +0.0553, +0.1024, -1.8251, -0.7928, +0.1100, -0.1679, -0.9488],
-[ -0.2144, -0.1724, -0.3429, +0.4875, +0.1602, +0.3609, +0.2947, -0.0800, -0.1385, +0.1008, +0.0328, -0.4782, -0.0638, +0.1748, +0.1134, -1.1389, -0.3115, -0.5365, -0.6607, -0.4707, -0.7305, +0.1676, -0.0230, +0.2286, -0.6695, +0.0748, +0.1772, -0.2285, -0.4459, +0.1489, -0.3056, -0.2268, -0.1158, +0.2677, -0.5665, +0.2966, -0.1029, +0.0172, +0.5579, +0.2357, -0.2072, -0.3823, -0.7458, +0.2185, -0.7836, -0.2562, -0.5589, -0.0523, -0.5152, +0.1166, +0.2566, -0.4698, +0.1755, +0.2976, -0.2948, -0.0285, -1.5112, +0.1225, -0.0690, -0.0911, +0.1124, -0.3546, +0.0632, +0.4610],
-[ -0.1956, +0.0370, -0.0308, -0.1817, +0.1882, -0.1052, -0.0503, +0.3709, -0.2240, -0.0828, -0.8304, +0.0044, +0.0459, +0.0761, +0.0206, +0.1419, +0.4986, -0.0567, -0.3287, -0.7981, -0.2592, -0.7543, -0.4157, -0.0182, -0.0886, -0.7827, +0.0057, -0.0465, -0.3869, -1.4567, +0.2595, +0.0849, -0.8865, +0.0156, -0.1862, +0.2267, +0.4277, +0.2811, -0.8963, -0.2927, +0.1019, -0.1663, -0.8428, -0.2191, +0.4336, -0.9808, -0.8575, +0.1630, +0.0028, -0.4473, +0.5544, -0.2155, +0.0422, +0.1349, -0.3771, -0.0671, -0.0194, +0.2140, -0.3160, -0.5825, +0.3150, -0.0496, -0.0514, -0.2068],
-[ +0.2710, +0.2079, -0.7397, -0.5588, -0.3865, -0.3099, +0.3502, -0.0669, -0.0064, +0.1037, -0.8617, -0.3000, -0.2977, +0.2392, -1.4580, +0.3477, +0.0329, -0.5653, -0.6458, -0.2955, +0.1288, +0.1199, -0.5390, +0.1431, +0.1088, -0.5537, -0.0880, -0.3841, +0.0801, -1.8213, -0.5604, -0.9688, +0.3403, +0.7033, +0.7676, -0.0232, +0.1272, -0.0812, +0.0785, -0.0681, +0.3825, -0.1818, +0.0268, +0.0546, +0.0451, -0.4763, -0.0513, -0.3287, +0.5841, -0.1963, +0.1147, +0.1113, -0.5448, -0.3498, -0.0750, -0.0585, -0.5094, +0.0116, +0.6219, -0.1440, -0.0742, -0.1261, +0.0572, +0.4366],
-[ +0.0369, -0.3345, -0.0768, +0.4205, -0.1390, -0.2384, -0.1629, +0.0786, +0.6107, -0.2725, +0.0444, +0.2727, +0.3295, +0.3000, -0.4049, +0.1150, -0.7289, -0.5964, +0.1346, +0.0574, -0.1202, -0.2461, -0.1504, -0.1282, +0.5685, -0.3631, +0.4576, +0.6880, +0.2554, -0.1782, -0.2704, -0.5299, +0.0232, -0.4567, -0.1116, -0.2672, +0.4286, -0.0448, +0.2230, +0.0236, -0.0343, -0.0985, +0.8088, +0.2633, -0.7682, -0.0642, +0.0384, +0.0750, +0.0595, +0.1717, +0.5152, +0.2972, +0.0325, +0.0450, +0.2534, -0.1186, +0.1540, -0.0107, -1.5430, -0.1050, +0.4161, +0.0592, +0.0044, +0.0843],
-[ +0.1402, +0.1111, +0.4706, +0.3944, -0.1486, +0.1623, -0.1863, +0.0468, -0.4898, -0.0224, +0.2583, +0.1336, -0.1123, +0.0581, -0.0853, -0.0288, +0.0372, -0.1358, -0.0016, -0.5055, -0.2581, -0.3232, +0.0418, -0.5329, +0.0167, -0.1626, +0.0284, -0.8795, +0.1812, +0.1044, +0.3439, -0.3482, -0.1301, +0.1099, -0.3284, -0.3683, -0.0479, -0.2303, -0.2175, +0.2400, +0.4435, +0.0818, +0.3271, -0.0304, -0.4587, -0.3401, +0.1851, +0.1210, +0.0699, +0.2149, +0.3445, -0.3352, -1.0872, +0.1455, +0.2182, -0.7787, -0.4760, +0.0306, -0.2152, +0.1286, +0.1384, -0.0821, +0.1290, -0.0055],
-[ -0.3143, -0.1360, -0.4878, +0.1358, +0.5162, -0.0948, -0.1355, +0.0911, +0.3592, +0.3475, -0.5666, -0.1593, +0.1584, +0.3172, -0.0814, -0.1594, +0.1179, -0.6127, -0.3628, +0.1970, -0.6501, +0.1911, +0.4294, -0.2048, +0.3984, -0.0478, +0.1101, -0.5869, +0.4901, +0.2732, +0.1232, +0.4142, -0.1033, -0.7990, -0.2998, -0.2509, +0.2344, -0.2567, -0.0217, -0.0533, +0.0065, +0.2979, +0.1800, -0.0104, +0.1369, -0.0922, +0.0936, -0.7170, -0.0760, +0.8108, -0.5491, +0.6483, -0.2240, +0.3839, +0.1498, -0.3039, -0.1461, +0.6054, -0.2897, -0.0078, -0.5547, -0.2711, +0.0759, +0.3237],
-[ +0.5616, +0.6020, +0.1514, -0.0995, -0.2372, +0.0439, +0.1131, -0.4839, -0.0951, +0.0364, -0.5441, +0.4846, -1.2297, +0.0283, +0.0222, -0.0880, -0.2479, -0.9553, -0.3495, -0.2920, +0.1952, +0.1342, -0.0358, +0.0231, +0.2965, +0.1285, -0.6684, -0.1393, +0.0285, -0.2817, +0.4368, +0.2012, -0.2838, +0.4132, +0.1914, +0.0013, -1.7082, -0.0351, -0.4860, +0.7094, -0.2159, -0.1761, -1.0276, -0.1694, -0.3221, +0.0570, -0.4394, -0.2167, +0.4231, -0.1657, +0.6024, -0.2707, -0.8380, -0.3110, -0.2727, -0.0000, +0.0231, -0.1633, -0.1836, -0.2276, -0.4032, +0.1383, -0.1814, +0.0089],
-[ -0.5613, +0.4738, -0.0094, +0.1051, -0.1535, +0.4020, +0.1245, -0.2956, -0.3178, +0.2353, -0.1440, -0.4745, +0.5712, -0.6119, -0.2502, +0.1111, -0.2901, +0.1149, -0.2184, +0.0947, -0.2306, +0.0607, +0.5822, +0.1520, +0.3781, +0.1310, -0.1419, -0.3509, -0.0049, -0.1097, -0.0186, +0.1534, +0.0022, -0.0835, +0.1862, -0.2482, -0.1495, +0.1222, +0.4941, +0.1029, -0.7218, -0.3025, +0.1426, +0.5004, -0.0558, +0.2425, +0.0040, +0.1861, +0.2947, +0.1472, -0.1007, +0.4316, +0.2087, +0.1794, -0.3261, +0.3879, +0.3172, -0.1491, -0.2332, -0.1210, +0.1350, -0.6219, -0.1570, -0.3347],
-[ -0.3358, -0.0382, -0.7346, +0.4532, +0.1010, +0.1139, +0.2213, -0.1050, -0.0101, +0.3208, -0.0250, -0.7625, -0.2357, -0.4067, +0.3186, -0.9441, -0.0734, +0.0728, +0.0527, -0.0968, -0.0641, +0.2877, -0.0233, +0.0247, -0.1409, +0.1281, +0.0714, -0.0970, -0.4026, -0.3684, +0.3176, -0.1875, +0.5452, +0.0015, -0.0651, +0.1397, +0.1550, -0.2029, +0.1350, +0.5028, -0.4886, +0.0630, +0.1046, +0.5003, -0.5631, -0.1724, +0.2490, -0.0635, +0.2186, -0.6167, +0.2855, -0.0579, -0.3821, +0.0562, +0.3526, +0.1313, -0.1232, +0.5154, +0.2603, -0.0256, -0.0428, -0.4523, +0.1544, +0.4509],
-[ +0.4364, +0.1492, -0.8081, -0.7765, +0.6166, -0.1982, -1.1432, +0.1429, -0.2398, +0.5563, +0.6239, -0.5039, +0.5798, +0.2796, -0.1920, +1.1087, -1.2430, +0.3100, -0.1673, -0.2110, -0.1677, -0.2675, -0.6310, +0.4756, -0.9587, +0.2184, -0.4932, +0.1294, +0.3719, -0.4294, -0.5482, -0.0035, -0.8373, -0.8548, -0.3245, -0.0418, -0.0565, +0.1039, +0.0908, -0.7536, -0.2366, +0.3019, +0.2688, -0.5386, +0.1596, -0.1945, +0.6900, -0.8411, -0.2744, -1.1320, +0.0096, +0.0270, +0.4991, -0.1475, -0.0282, -0.0996, -0.1922, +0.1317, +0.0331, -0.1740, +0.0127, -0.5657, -0.0071, +0.3783],
-[ -0.9835, -0.0852, +0.0673, +0.3608, -0.5972, -0.6473, +0.2292, -0.8121, -0.2935, +0.3361, +0.1431, -0.9612, -0.4476, -0.3111, -1.0042, -0.3003, +0.0550, -0.4980, -0.1894, -0.2824, +0.2057, +0.4801, +0.2026, -0.0641, -0.5990, +0.2153, +0.1995, +0.2198, -0.3514, -0.0224, -0.1561, -0.9427, +0.5208, +0.2935, +0.3871, -0.1506, -0.0125, +0.6396, -0.0254, +0.4302, -0.3523, +0.0043, -0.0100, +0.3120, -0.1009, -0.9246, +0.0267, -0.1770, -1.4509, +0.0446, -0.3987, -0.0527, -0.3977, -0.8643, +0.0371, -0.2630, -0.0853, +0.1048, +0.0452, -0.5723, -0.0805, -0.0452, -0.0489, +0.3637],
-[ -0.1134, +0.1550, -0.0273, -0.5159, -0.1409, -0.0753, +0.3230, -0.4589, +0.2979, +0.1357, +0.1507, -0.9132, -0.9848, -0.0549, -0.1922, +0.1292, -0.2662, -0.0223, +0.1236, -0.1861, +0.1619, +0.3042, +0.2029, -0.1568, +0.1171, +0.2165, +0.3397, +0.4358, -0.0830, -1.0290, +0.2147, +0.1445, -0.0959, +0.4696, +0.1496, +0.2696, -1.2499, +0.0610, -0.7221, -0.5853, +0.1479, -0.7158, -0.9965, +0.4685, +0.1279, +0.2654, -0.2122, -0.2593, -0.0377, +0.1686, +0.2055, -0.4425, -0.3739, -0.5889, -0.2026, +0.0867, +0.1399, -0.2259, -0.1120, -0.7030, -0.2465, +0.1833, -0.4158, +0.2191],
-[ -0.3483, +0.1839, +0.0828, -1.1050, -0.1233, +0.1977, +0.1525, +0.4061, +0.5995, +0.0719, +0.2548, -0.7088, +0.0960, +0.8649, -0.4205, +0.0785, -1.6571, +0.3270, +0.1325, -0.3489, -0.1474, +0.4878, +0.6677, +0.1169, +0.0927, -0.7217, +0.2176, +0.4076, +0.2830, +0.1905, +0.2715, +0.0414, +0.0528, +0.2191, -0.0137, -0.6578, +0.0925, -0.0096, -0.0277, +0.3254, -0.1541, -0.1264, +0.3611, +0.4325, -0.5513, +0.5342, +0.5277, +0.0938, +0.1011, -0.3802, -0.3093, -0.3772, +0.2394, -0.0069, +0.2487, -0.0366, -0.2062, -0.4031, +0.1757, +0.1664, -0.6083, -0.4812, +0.3686, -1.8912],
-[ +0.4638, -0.6215, -0.9444, -0.2262, -0.0024, -0.1107, +0.2688, -0.8943, +0.2925, +0.0938, -0.2213, -0.0040, +0.5671, +0.1933, -0.1180, +0.8275, -0.4667, +0.4134, +0.2031, -0.7823, -0.2169, -0.0449, -0.0460, +0.2337, -0.6242, +0.1746, +0.1719, -0.3266, -0.0035, -2.0916, -0.9540, -0.4786, +0.1893, +0.0484, -0.2314, +0.0707, +0.6548, +0.1558, -1.5931, -0.1063, -0.0078, -0.1189, +0.2243, -0.4626, +0.9811, +0.0963, +0.3128, +0.2263, -0.1932, +0.2922, -0.8837, +0.4654, +0.3331, -0.7873, -0.1036, +0.1652, -0.3548, -0.6482, -0.3590, -0.4473, -0.5732, -0.6507, +0.0124, +0.3495],
-[ +0.2305, -0.0983, -0.6019, +0.0341, -0.0379, -0.3943, +0.2129, -0.1420, -0.4793, +0.1007, +0.0970, -1.2953, +0.1626, +0.1505, -0.0289, -0.0156, -0.8020, -0.5636, -0.3583, -0.5833, -0.0779, +0.0571, -0.6464, -0.3262, -0.0799, +0.1420, -0.2370, +0.2553, -0.0499, +0.0923, -0.0051, +0.1285, +0.3178, +0.4984, -0.8847, +0.0226, -0.0542, +0.0218, +0.1203, -0.3696, -0.1743, +0.2263, -0.2901, +0.2136, -0.1456, -0.1032, -0.3173, +0.2449, +0.3368, -0.0686, +0.2705, -0.3874, -0.0087, +0.1807, +0.1054, -0.5347, -0.4611, -0.0363, +0.3767, -0.4282, +0.2581, -0.1649, +0.2136, +0.2720],
-[ +0.0920, -0.0227, +0.2435, -0.0693, -0.1166, +0.4459, +0.0340, +0.1341, +0.0651, -0.4839, -1.2283, -0.3406, -0.0625, -0.1543, -0.5159, -0.1331, -0.1011, +0.1511, +0.1291, -0.3677, +0.1103, +0.3123, -0.0555, +0.0921, +0.2083, -1.2922, +0.4564, +0.2563, -0.3195, -1.2801, +0.2871, -0.2701, -1.0224, -0.4784, +0.2698, +0.0970, -0.3113, -0.2468, -0.5107, -0.1610, -0.0608, -0.5730, +0.0112, -0.3562, +0.0284, +0.3547, -0.1682, -0.4646, -0.5916, +0.0556, -0.4088, +0.3740, +0.1835, +0.2922, -0.2365, -0.0748, +0.3475, -0.1332, -0.0565, -0.6135, -0.2440, -0.0980, +0.0177, +0.2084],
-[ +0.5078, +0.2882, -0.1070, -0.2375, +0.1945, -0.1556, -0.1868, +0.4579, -0.1407, -0.3003, +0.5034, -0.1413, -0.1191, +0.5198, -0.0995, +0.2052, -0.6323, +0.3269, +0.1478, -0.9499, -0.0894, -0.5471, -1.0356, -1.0237, +0.1626, +0.0408, -1.5120, +0.5972, -0.2106, -0.1963, -0.2037, +0.4696, +0.0170, +0.3471, +0.6302, +0.3234, +0.0171, +0.2163, -0.2019, -0.8498, -0.7691, +0.0792, +0.1790, -0.2880, +0.1583, -0.2802, +0.3539, -0.2478, +0.2920, -0.8338, +0.3591, -0.6136, -0.0626, +0.5065, +0.3065, -0.3856, -0.7768, +1.0600, -0.3624, +0.4283, +0.6014, -0.2987, -0.5462, +0.5388],
-[ -0.1657, +0.2175, +0.1502, +0.1590, +0.2511, -0.1747, +0.0322, +0.0047, -0.1304, +0.1304, -0.2217, +0.2689, -0.0998, +0.0495, +0.5198, -0.4353, +0.3513, -0.3965, -0.7116, +0.1963, -0.2455, +0.1669, +0.0317, +0.0209, -0.9937, +0.0478, -0.1112, +0.0802, -0.0946, +0.2395, -0.4575, +0.2455, -0.0041, +0.2040, -0.1288, +0.4845, -0.0935, +0.1073, -0.1772, -0.0717, +0.1100, -1.2535, -0.4555, +0.1200, +0.0925, +0.2260, -0.3057, +0.1682, -0.7064, +0.0541, +0.2077, -0.6310, +0.1636, +0.4050, +0.0783, -0.2254, -0.5860, +0.0542, -0.1233, +0.0088, -0.1021, -0.4150, -0.5846, +0.0780],
-[ +0.0137, +0.1261, +0.2534, +0.0314, +0.1516, +0.2854, -0.2887, -0.0637, -0.1735, +0.0230, -0.2352, -0.2550, -0.4087, -0.1375, +0.5831, -0.4667, -0.1422, -0.0267, -0.1625, -0.4943, +0.0660, -0.0611, -0.2226, -0.1747, +0.2218, +0.0342, -0.0662, -0.5225, -0.2543, -0.3675, +0.2921, -0.5501, -0.6124, -1.0240, -0.0340, +0.3921, +0.0436, -0.1442, +0.1874, +0.3041, -0.1329, +0.0904, -0.4785, -0.1100, +0.7130, -0.9416, -0.3120, -0.3972, -0.0667, -0.2238, +0.5337, +0.2120, -0.3086, +0.1386, +0.0945, -0.0784, +0.0060, +0.3076, +0.1153, -0.8886, +0.2775, -0.3114, +0.1672, +0.2318],
-[ +0.0146, -0.1282, -1.1506, +0.1754, +0.0246, -0.4277, +0.1070, -0.5093, -0.0829, -0.9763, -1.5423, +0.0999, +0.1235, -0.5906, -0.0747, +0.0536, -0.0421, +0.0307, +0.2496, +0.1554, -0.0956, +0.2644, +0.0617, -0.0836, -0.8209, +0.2670, -0.0349, -0.7920, -0.0636, -0.5876, -0.5698, -0.2682, -0.3274, +0.2240, -0.0315, -0.3318, -0.1250, -0.1955, -0.2965, +0.2306, -0.0729, -0.2693, -0.2185, +0.1496, +0.1656, +0.2526, -0.3052, -0.1906, -0.3483, -1.2051, +0.3049, -0.1922, -0.3015, -0.4155, -0.3547, +0.0109, -0.4658, -0.7525, -0.4770, -0.5124, +0.1414, -0.1773, -0.5394, +0.0918],
-[ -0.9757, +0.5451, -0.1582, -0.0760, +0.2780, +0.0088, -0.5886, +0.7647, +0.0055, +0.2014, +0.2445, -1.4211, -0.0321, +0.2212, +0.4337, -0.5242, -0.2517, +0.1777, -0.0283, -0.4325, -0.0527, -0.3353, -0.1614, -0.7283, +0.6176, -0.4128, -0.2551, +0.1218, -0.2137, -0.5500, +0.2138, -0.5199, +0.1999, +0.5070, +0.8055, +0.4022, -0.0963, -0.0710, -0.6852, -0.1077, +0.1993, -0.0105, +0.1279, +0.0083, -0.2906, -0.6892, -0.5177, -0.5738, -0.0834, -0.1992, -0.2419, +0.5335, -0.1230, +0.1839, -0.2993, +0.4106, -0.7241, +0.3990, +0.1751, +0.2938, +0.0499, -1.0744, -0.2422, -0.4619],
-[ -0.4866, -0.3855, -0.1042, -0.1423, +0.2359, +0.2600, -0.1206, -0.1596, -0.0135, -0.7623, +0.8498, -0.4058, -0.2221, -0.2718, -0.2202, -0.0022, -0.3595, -0.5880, -0.2412, -0.0803, +0.2923, +0.0932, -0.0245, +0.0494, -0.0914, +0.0065, -0.1044, +0.2288, -0.2645, +0.1512, -0.7647, +0.4264, +0.5612, -0.1165, +0.0498, +0.2486, -0.4278, -0.5425, +0.2555, -0.2089, +0.1553, +0.2537, +0.6342, -0.6339, -0.3252, +0.4005, +0.3177, -1.0503, -0.0484, -0.6869, -1.2052, +0.0518, -0.2127, +0.6565, +0.1174, -0.0542, +0.0330, -0.3769, -0.8160, -0.3341, +0.5011, -0.2296, -0.0582, +0.2720],
-[ -0.2740, -0.4031, +0.1220, +0.2121, -0.2756, -1.1033, -0.7286, -0.1866, +0.3279, +0.2347, -0.6916, +0.0782, -0.3519, +0.5791, -0.0632, -1.1896, -0.5604, -0.2738, +0.2529, +0.0344, -0.0932, -0.1923, -0.1518, -0.0706, +0.1075, +0.2185, -0.3537, -0.3668, -0.5451, +0.7531, -0.2921, +0.9216, -0.6654, -0.4376, +0.0435, -0.4269, +0.0265, -0.4000, -0.5693, -0.2149, +0.0681, -0.1618, -0.1684, -0.1539, -0.0432, +0.0356, +0.1934, +0.1132, -0.8665, -0.2111, -0.0802, +0.0847, +0.2886, -0.2710, -0.1154, -0.1229, +0.0220, -0.2838, -0.2988, +0.2642, -0.1269, +0.0378, -0.0577, +0.2332],
-[ -0.0167, -0.2866, -0.5837, -0.3393, -0.2001, -0.2052, -0.0069, -0.0557, +0.0957, -0.0296, -1.2254, +0.6089, -0.7623, +0.2794, -0.1563, -0.5299, -0.2602, +0.3578, +0.2024, -1.1151, -0.7019, -0.3572, -0.2302, -0.0681, +0.1533, -0.3679, +0.3212, -0.0854, -0.3797, -1.4589, +0.2442, -0.7591, -0.5560, -0.1719, -0.4811, +0.0760, +0.2026, -0.0090, +0.3387, +0.5250, -0.3101, -0.5067, +0.6807, -0.2780, +0.1402, +0.0732, -0.0141, -0.5621, -0.5418, -0.1793, -0.1043, -0.1398, -0.2086, +0.0398, +0.5175, -0.0853, +0.2001, +0.0463, +0.0370, -0.1317, -0.5319, +0.1052, -0.3744, -0.0245],
-[ -0.2261, +0.1322, +0.2244, +0.0686, +0.6216, +0.2085, -0.2037, -0.6063, -0.1096, -0.3126, +0.4351, +0.3109, -0.1477, -0.0571, +0.4007, -0.3581, +0.3124, +0.2700, +0.3172, -0.5340, +0.2530, +0.1908, +0.0630, +0.4039, +0.2531, +0.1035, +0.5428, +1.0849, -0.6678, -0.1461, +0.1677, +0.6444, -0.1607, +0.0921, +0.0428, -0.4171, +0.0052, -0.6449, +0.5795, +0.3778, -0.2117, +0.6219, +0.4147, -0.2854, +0.0800, +0.2086, +0.1057, +0.0211, +0.1335, +0.0754, -1.0412, +0.3630, -0.3308, -0.0163, +0.3209, +0.6749, +0.1818, +0.0622, +0.0631, -0.0780, -0.2003, +0.0502, -0.1801, +0.1226],
-[ -0.5705, -0.4520, -0.2005, -0.1099, +0.0716, +0.1710, -0.5488, -0.0350, +0.3769, +0.5694, +0.2142, -0.2680, +0.3770, +0.0675, +0.1544, -0.1849, -0.1091, -0.8965, +0.2643, +0.0145, -0.1163, +0.0022, +0.0120, +0.4676, +0.0786, +0.0047, -0.0236, +0.2523, -0.0296, -0.1272, -0.1784, -0.0316, -0.1040, -0.0833, -0.5759, +0.1137, +0.1781, -0.1794, -0.7452, +0.2339, -0.2118, -0.0421, +0.1374, -0.7774, +0.0419, +0.2437, -0.1457, -0.3050, -0.5618, -0.8883, +0.3731, +0.1214, +0.2160, -0.2766, +0.2474, -0.0136, -0.0689, +0.2249, +0.4861, +0.3022, +0.0187, +0.4610, +0.0144, -0.0760],
-[ +0.0452, -0.0096, +0.0093, +0.3166, +0.0104, -0.8211, +0.0320, -0.9130, -0.9762, +0.3912, +0.0517, -0.0086, -0.1364, -0.5440, +0.3999, -0.8466, +0.1587, +0.3064, -0.0849, -1.0372, -0.3295, -0.0011, +0.0702, +0.0558, -0.3068, -0.0579, +0.1683, +0.1862, -0.3232, +0.0126, -0.0197, +0.3761, +0.3451, +0.1456, -0.1702, +0.3671, +0.2129, +0.1910, -0.4390, -0.2298, +0.2539, -0.2647, -0.0812, +0.1049, +0.0182, +0.0124, +0.1412, +0.7550, +0.1466, +0.0842, -0.2089, -0.1244, -0.1409, -0.0448, +0.4329, +0.2906, +0.1276, +0.0849, +0.1483, -0.1114, +0.1040, -0.1841, +0.0504, +0.0628],
-[ -0.7229, -0.2299, +0.3797, +0.2634, +0.1779, +0.1996, -0.0516, +0.1889, -0.0321, -0.0180, +0.1005, -0.1224, -0.7053, -0.1657, +0.2718, -0.1325, -0.3542, -0.0817, +0.0660, -0.3473, -0.1094, +0.3669, +0.0287, +0.4202, +0.5254, +0.3843, +0.2454, -0.1032, -0.2225, +0.1151, +0.2620, -0.2615, +0.1377, -0.0886, +0.1253, -0.2241, +0.2043, -0.6399, -0.0001, +0.2756, -0.5004, +0.0097, +0.1577, +0.1704, -0.4630, +0.0586, +0.1950, -0.2765, +0.3850, +0.1792, -0.0390, +0.0853, +0.0609, +0.3052, +0.1366, +0.4978, -0.0320, -0.0238, -0.2433, +0.1354, -0.3672, +0.1638, +0.3015, +0.0190],
-[ -0.5652, -0.5404, +0.3047, +0.2983, +0.0327, -0.2695, +0.3298, +0.0245, -0.8883, -0.2214, +0.0148, +0.2319, -0.4585, -0.4131, +0.1738, -0.0687, +0.2266, -0.0930, -0.0778, +0.0594, -0.7182, -0.5207, -0.1110, -0.6784, +0.1840, +0.4566, +0.0854, -0.0213, -0.4181, +0.1902, +0.3848, -0.3574, +0.0339, +0.0642, +0.2140, +0.2387, +0.1925, -0.4425, -0.1289, +0.0003, +0.4367, -0.1658, -0.6550, +0.0966, -0.2929, -0.0290, +0.0821, +0.0917, +0.0588, +0.0215, +0.2516, -0.6177, -0.3127, +0.1305, +0.1058, -0.2301, -0.1769, +0.3145, +0.0931, +0.0435, +0.2786, +0.4412, +0.1732, -0.1200],
-[ -0.0996, -0.6608, -0.0364, +0.3340, +0.0165, +0.3010, +0.0927, +0.1056, -0.2970, -0.1835, +0.0571, +0.2240, +0.0030, -0.6368, +0.2202, -0.1890, +0.4696, -0.0632, -0.0631, +0.0907, -0.1202, -0.3129, -0.0065, -0.2858, +0.5460, +0.2200, +0.2605, +0.0594, -0.2014, +0.3389, +0.3456, -0.0752, +0.0585, -0.0157, +0.0157, +0.0445, +0.3628, -0.4249, -0.3869, -0.0149, +0.3033, -0.2029, +0.3068, +0.2245, -0.3317, +0.5013, +0.2260, +0.0021, +0.5501, +0.0470, +0.0281, -0.4652, -0.5074, +0.0623, +0.2559, +0.1474, +0.3211, +0.3766, -0.0389, +0.3026, +0.0087, +0.4048, +0.4947, -0.1758],
-[ +0.1554, -0.1069, +0.0311, +0.1231, +0.1511, -0.5720, -0.2430, +0.0702, -0.3883, +0.0351, -0.4604, +0.2486, -0.1264, +0.0224, -0.4056, -0.0509, -0.2476, +0.4460, +0.3992, -1.0177, -0.4811, -0.0661, -0.4349, +0.0118, -0.3434, -0.0266, -0.4486, -0.2416, -0.2670, -0.2086, -0.6751, +0.0134, -0.0306, +0.1693, -0.1759, +0.2342, +0.0876, +0.0606, +0.5759, -0.6247, -0.0825, +0.8001, -0.4028, -0.3971, +0.4740, -0.7486, -0.1452, +0.0966, -1.1183, -1.7440, +0.3747, -0.2859, -0.4128, +0.0351, -0.1834, +0.2799, -0.5416, +0.1614, -0.1525, +0.5196, +0.1470, +0.2015, -0.0209, +0.4493],
-[ +0.4452, +0.3101, -0.1846, -0.2601, +0.0557, -0.1652, +0.2796, -0.2789, -0.3574, +0.7659, -0.0928, -0.1773, +0.2040, +0.3471, +0.0277, +0.1219, +0.1127, +0.2735, -0.0420, -0.3129, -0.8266, -0.0287, -0.1716, +0.0738, -1.1224, -0.2538, -0.1206, +0.4969, +0.5520, -0.9201, -0.4422, -0.4078, -0.2800, +0.0784, -0.1056, -0.1181, -0.6464, +0.1835, -0.1094, -0.0400, +0.3895, -0.4687, +0.7645, +0.1850, +0.8089, -0.0632, +0.3379, -0.1370, -1.2702, -0.1647, -0.0076, -0.3014, +0.5104, -0.8770, -0.1667, +0.0547, -0.9042, -0.7874, +0.4112, -0.6015, +0.1230, -0.3193, -0.3689, +0.7722],
-[ -0.1760, +0.0806, +0.0633, +0.1495, -0.2089, -0.1720, +0.3683, -0.7910, -0.1092, -0.0286, -0.2381, -0.3570, -0.3146, -0.4156, -0.4463, +0.2495, +0.1315, -0.4987, -0.0444, -0.3366, +0.4729, +0.5814, +0.2111, +0.5879, -0.4906, -0.2095, +0.1884, -0.8830, +0.0099, -0.5141, -0.0253, +0.0638, -0.5014, -0.6889, +0.4109, -0.3437, -0.5957, -0.3521, +0.4051, +0.1513, +0.0929, +0.2743, -0.5853, -0.0101, +0.0543, +0.0796, +0.0171, -0.1006, -0.8329, +0.3093, -0.7488, -0.1443, +0.4323, -0.3448, -0.6281, +0.4770, +0.4202, -0.8632, -0.3805, -1.1830, -0.7543, -0.5576, -0.5449, +0.2612],
-[ -0.7124, +0.0296, -0.0180, +0.1221, +0.3492, -0.1979, +0.1803, -0.6664, -0.4365, +0.0834, +0.0055, +0.2783, +0.2842, -0.3726, -0.1905, -0.3562, +0.4659, +0.5841, +0.2670, +0.3766, +0.2223, -0.2560, -1.2231, +0.3688, -0.6143, -0.4259, -0.0066, -0.6308, -0.0026, -0.4631, -0.1651, -0.3861, +0.1432, +0.3695, +0.3812, +0.1687, -0.0687, +0.6742, -0.1006, -0.0740, +0.3388, -0.1572, +0.3848, +0.1060, -0.3427, -0.0441, +0.1701, -0.9669, -0.6756, -0.7418, -0.4919, +0.1873, -0.0749, -0.0006, -0.2966, -0.3439, +0.1329, +0.1904, -0.4898, -0.7065, +0.3420, -0.1842, +0.2152, -0.0524],
-[ -0.0034, +0.0550, -1.2687, -0.0799, +0.3824, -0.1359, +0.2033, -0.0635, -0.1804, -0.0437, +0.1483, -0.5138, -0.7083, -0.4176, +0.4133, -0.9608, -0.1535, +0.2607, +0.1512, +0.0048, +0.1409, +0.0624, -0.2070, -0.6507, -0.1054, -0.1554, -0.9355, +0.1028, +0.6517, -0.1690, -0.0253, -0.6379, -0.4949, -0.0544, -0.0154, +0.2114, -0.2261, +0.6168, +0.0140, +0.0834, +0.2390, -0.4280, -0.5701, -0.3384, +0.3953, -0.0290, -0.0415, +0.1204, +0.0763, -0.5635, -0.6979, -0.2972, +0.1168, +0.0858, +0.5719, +0.0460, -0.1850, +0.3278, +0.2367, -0.1745, +0.3339, +0.2345, -0.7674, +0.2316],
-[ -0.7640, +0.4325, -0.7808, -0.8599, +0.0685, +0.1389, -0.4254, +0.1816, +0.5504, +0.5307, -0.3181, -0.6939, -0.4922, +0.2190, -0.0280, +0.0948, -0.0696, +0.2561, -0.3489, +0.1103, +0.2562, -0.0775, -0.4995, -0.3639, +0.4419, -0.0798, +0.1815, -0.4532, +0.0092, -0.3042, -0.5383, +0.2354, -0.0964, -0.3795, +0.6289, -0.0032, +0.8141, +0.1504, +0.3532, +0.4816, -0.4394, -0.2215, -0.2689, +0.6740, -0.1720, +0.0399, -1.3940, -0.0466, -0.6636, -0.7952, +0.2715, +0.1412, +0.1164, +0.1355, -0.4197, -0.1231, +0.0225, +0.1704, -0.6381, -0.1786, +0.1951, +0.7547, +0.0585, -0.9978],
-[ +0.2424, +0.1429, -0.5942, -0.8311, -0.4039, +0.0123, -0.5286, -0.1538, +0.1444, -0.2057, +0.1541, +0.3277, +0.0325, -0.1216, -0.2855, -0.3571, -1.2245, +0.5472, +0.8566, -0.4063, -0.0020, +0.0161, -0.0828, +0.1365, -0.3165, +0.1856, +0.4180, +0.3827, +0.4085, +0.1363, -0.5951, +0.2136, +0.4635, -0.3175, -0.0179, -0.1298, +0.3717, +0.3155, +0.7539, -0.3723, -0.9288, -0.0145, +0.2546, -0.1112, +0.0629, +0.1843, +0.3677, -0.3291, -0.4158, -0.4757, -0.6994, +0.1739, +0.2550, -0.2444, +0.1263, +0.2426, +0.2999, -0.1290, -0.3900, +0.3528, +0.1145, +0.2559, -0.0819, -0.4488],
-[ -0.4228, -0.1394, -0.2091, -0.0344, +0.4417, -0.0600, -0.5085, +0.2543, -0.0523, +0.3243, +0.0854, +0.2292, +0.0820, -0.0431, +0.0678, -0.0514, -0.0348, -0.0160, +0.5653, +0.1224, +0.2047, -0.1892, -0.9762, -1.0318, -0.9600, +0.2571, +0.0527, +0.2796, -0.0836, +0.0239, -0.6415, +0.2080, +0.3183, +0.1883, -1.2626, +0.2661, +0.1099, -0.3269, -0.3931, -0.2218, -0.0774, -0.1932, -0.2984, -0.2962, -0.0536, -0.4651, -0.2370, -0.1265, -0.1956, -0.5390, -0.5313, -0.4435, -0.0816, +0.1992, -0.2242, -0.5927, -0.0626, +0.1441, +0.0228, -0.1464, +0.1223, -0.0883, +0.2199, +0.1578],
-[ +0.3977, +0.0629, -0.0984, -0.4987, +0.4269, -0.1940, -0.1254, +0.2561, +0.2799, -0.2491, -0.1810, +0.2404, +0.5219, +0.0879, -0.2920, +0.3293, +0.0132, +0.0919, -0.1286, +0.5001, +0.1045, -0.1544, -0.5092, -0.2277, +0.1893, -0.6046, +0.1304, +0.9889, +0.1189, +0.2228, -0.3941, -0.0629, -0.3580, -1.2052, -0.3574, -0.5456, -0.2044, -0.3054, -0.0874, -0.7163, +0.0782, +0.4724, +0.4832, -1.0618, +0.2777, -0.3273, +0.0845, +0.0028, +0.1905, +0.3128, +0.1351, +0.1499, -0.1993, +0.0798, +0.0308, -0.8532, +0.0118, -0.2095, -0.0387, +0.1203, +0.1096, -0.0137, +0.1436, -0.2861],
-[ -0.2417, -0.0439, +0.1189, +0.2369, -0.2781, +0.3031, +0.0773, +0.6085, +0.0232, -0.1423, -0.6961, -0.8309, -0.6136, -0.2563, +0.0283, -0.1212, -0.4166, -0.0050, +0.0318, +0.0260, -0.2687, -0.1907, -0.2317, -0.6242, +0.4980, -0.2121, -0.2454, -0.8505, -0.6092, -1.1722, +0.5666, +0.1006, -0.1905, -0.0702, +0.0700, +0.0617, +0.1817, -0.2282, +0.0176, -0.2242, +0.1264, -0.2623, -0.7171, -0.1821, -0.3619, -0.1819, -0.2828, -0.2249, -0.0303, +0.0185, +0.2609, -0.0549, -0.0996, +0.4723, -0.3633, +0.0846, +0.0765, +0.3280, -0.2451, +0.1041, -0.0034, +0.2080, +0.1936, -0.4749],
-[ -0.4080, +0.0101, +0.4896, +0.2650, -0.0713, -0.4852, -0.4725, -0.1664, +0.1746, -0.1745, +0.1742, +0.0886, -0.0533, -0.2693, -0.1717, -0.1211, -0.5343, -0.2970, -0.2407, -0.0890, +0.2510, +0.1665, -0.0280, -0.5085, -0.0720, +0.0815, +0.0286, -1.0586, -0.0480, +0.6197, -0.1686, -0.0971, -0.0590, -0.0530, -0.5561, +0.2351, -0.8316, -0.4513, -0.0833, +0.3241, -0.2440, +0.0885, -0.0566, -0.0628, +0.0390, +0.0530, +0.1303, +0.2249, +0.3535, -0.1897, -0.0028, -0.4503, -0.4608, -0.4771, +0.0547, +0.1368, -0.0396, -0.0574, -0.7205, -0.0545, +0.3713, -0.1449, +0.0460, -0.2573],
-[ +0.1729, +0.3328, -0.0483, +0.3430, -0.8166, -0.7130, -0.1524, -0.8914, -0.0284, +0.3845, +0.3261, -0.2930, -0.1704, -0.0667, -0.0761, -1.0040, +0.5002, +0.0138, +0.0480, -0.1500, -0.1398, +0.1682, +0.4195, -0.2878, -0.4181, -0.5565, +0.1091, -0.2138, -0.0314, -0.9147, -0.2513, +0.0348, -0.1134, -0.1961, +0.5464, +0.2765, +0.0357, -0.5474, -0.6593, -0.0637, -0.5578, +0.0965, -0.3782, -0.0283, +0.1986, -0.7640, -0.2243, +0.1620, -0.4975, +0.4370, -0.0027, -0.4728, -0.5417, +0.1895, +0.4871, -0.7267, -0.0884, -0.4895, -0.3184, -0.2400, +0.5365, -0.6006, -0.0316, -0.2627],
-[ -0.1250, -0.2274, -0.4734, -0.8212, -0.8737, -0.2582, -0.1367, +0.0765, +0.1154, -0.0014, +0.1208, -0.0270, -0.0425, +0.3288, -0.1526, +0.3159, -0.3454, +0.3237, +0.0894, -0.5365, +0.1782, -1.0302, +0.0365, -0.2069, +0.1498, -0.5999, -0.2724, -0.1894, +0.4306, -0.3260, -0.3904, -0.0550, -0.2776, -0.2343, +0.4672, -0.1577, -0.2296, +0.2996, -0.6247, -0.2263, -0.4007, -0.2281, -0.0291, -0.6503, +0.3853, -0.7961, +0.3894, -0.0580, -1.3425, -0.2164, -0.1007, +0.1227, -0.4520, +0.1167, +0.1217, +0.1238, +0.0792, -1.1752, +0.1036, +0.0568, -0.3924, +0.0349, -0.5209, +0.3545],
-[ +0.0287, -0.3782, +0.1962, -0.1268, +0.3571, -0.0019, -0.0362, -0.0845, +0.3061, +0.2659, -0.5059, -0.1129, -0.4579, +0.2661, +0.0929, +0.0436, +0.0056, +0.2657, +0.3845, -0.5530, +0.1714, +0.4608, +0.2531, +0.3154, +0.0426, +0.5664, +0.2775, -0.1081, +0.2637, -0.1573, -0.2128, +0.0684, -0.4874, -0.0263, -0.0327, -0.0933, -0.1256, -0.7359, -0.0188, +0.5449, -0.1793, +0.2461, +0.1168, +0.1503, +0.4420, +0.0875, -0.4102, +0.0356, -0.2893, +0.2913, -0.8194, +0.4889, +0.0413, +0.3302, -0.2903, +0.0952, +0.0212, +0.3041, +0.1542, -0.4005, -0.2331, -1.3377, +0.1470, -0.7202],
-[ -0.9282, -0.1059, -0.0082, -0.1766, -1.3977, -1.3125, +0.3087, -0.3368, -0.6917, +0.0534, +0.0881, -0.7281, -0.4862, +0.0312, -0.8796, -0.0374, -0.0516, -0.3584, -0.9422, -0.8726, +0.0645, +0.0442, -0.2800, -0.3980, -0.1358, +0.4521, +0.1079, -0.1224, +0.1390, -0.5237, -0.2044, -0.8309, +0.2561, +0.4951, -0.7866, -0.1615, -0.2310, -0.2373, +0.0514, +0.2622, -0.4641, -0.1833, -0.1839, -0.0406, -0.3321, -0.2933, -0.0421, +0.1813, -0.2127, -0.1382, -0.0012, -0.6567, -1.4080, -0.3627, +0.3178, -1.2242, -0.9392, -0.1510, +0.2459, -0.0221, +0.4568, -0.4586, -0.0793, +0.3680],
-[ -0.3041, +0.2604, -0.2652, +0.6025, +0.0916, +0.0136, -0.2971, +0.3269, +0.0725, -0.2456, -0.3518, +0.2903, +0.1801, -0.6663, +0.3020, +0.1644, +0.3541, -0.2844, -0.5166, -0.1280, -0.0661, +0.5309, +0.2226, +0.0688, -0.1076, -0.0739, +0.1466, +0.5006, -0.0508, -0.1852, +0.0641, +0.0069, -0.6020, -0.2326, -0.1071, -0.1683, +0.1069, +0.3673, -0.1795, -0.3418, -0.0471, +0.2649, +0.0608, -0.9008, +0.1314, +0.0451, -0.4691, -0.1016, -0.5714, +0.0841, +0.1224, +0.1867, -0.0598, -0.1693, -0.3963, +0.0738, +0.5359, +0.3494, +0.1235, +0.4378, -0.0009, +0.5538, +0.4332, -0.0908],
-[ -0.5524, +0.2589, +0.1305, -0.4090, -0.0750, +0.1026, +0.5287, +0.2289, +0.4169, -0.0428, -0.3602, -0.1625, +0.0370, -0.4344, -0.2947, -0.0240, +0.1273, -0.0985, -1.3586, -0.7712, -0.2291, -0.4270, +0.4181, +0.3414, +0.1665, +0.0272, +0.3223, -0.1411, -0.0644, -0.7001, +0.1848, +0.3318, -0.4295, -0.7952, -0.0880, -0.4895, +0.2159, -0.1718, -0.3125, +0.0386, -0.6332, -0.3036, -0.5912, -0.4327, -0.0451, -0.5203, -0.0132, -0.1439, -0.1113, +0.0051, +0.0134, -0.0185, -0.0601, -0.0629, -0.2407, -0.4088, +0.0155, -0.2293, -1.0280, +0.0067, +0.1398, -0.1448, +0.3806, +0.2182],
-[ +0.0648, -0.0437, -0.0942, -0.2744, -0.4381, -0.2502, +0.1999, -0.1825, +0.3736, -0.5487, -0.2808, -0.8762, -0.0995, -0.7099, -0.1731, -0.0471, +0.0135, +0.3748, -0.4082, -0.2058, +0.5860, +0.4465, +0.2315, +0.1135, -0.3129, -0.8307, +0.1438, -0.6274, +0.0895, -0.1950, -0.0484, -0.2457, +0.1510, -0.8775, -0.9142, -0.1708, -0.0972, -0.6048, +0.2905, +0.5451, -0.2202, -0.3213, -0.0398, -0.3397, +0.0215, -0.1846, +0.1132, -0.0441, -0.4064, -0.2330, -0.5510, +0.4083, +0.0116, -0.1033, -0.0460, +0.1744, +0.1322, -0.7649, -0.5508, +0.6277, +0.0331, -0.4214, +0.2977, +0.3355],
-[ -0.1351, -0.2439, +0.3468, +0.2800, -0.0715, +0.0273, +0.0259, +0.2220, -0.1142, -0.2086, +0.1733, -0.3081, -0.0993, +0.0308, -0.8777, +0.2663, -0.0156, -0.0179, +0.3093, +0.2105, -0.1656, -0.3246, -0.0365, -0.4435, +0.3391, -0.0303, +0.2684, -0.6413, -0.0021, -0.7990, +0.1877, -0.3394, +0.2103, +0.0907, +0.0610, +0.0687, +0.2747, -0.3606, +0.1065, +0.0569, +0.2614, +0.1773, -0.8595, +0.0669, -0.1244, -0.4618, -0.3705, -0.0510, +0.2129, +0.1995, +0.0395, -0.0747, -0.2724, +0.1117, -0.3345, -0.3311, +0.0042, +0.3678, +0.3423, +0.2525, -0.0849, +0.3778, +0.4023, -0.1001],
-[ +0.1241, -0.0503, -0.0182, -0.2132, -0.2386, -0.3724, -0.2412, -0.1737, -0.1700, +0.3160, -0.0092, +0.2899, -1.5977, +0.1411, -0.7268, -0.0835, +0.5029, +0.1386, -0.0634, -0.4580, +0.1020, -0.4675, +0.5110, -0.2398, +0.3636, -0.5651, -0.1730, +0.1509, +0.3955, -1.8248, -0.0228, -0.4183, -0.2963, +0.1007, +0.4309, +0.0637, -0.0066, -0.0472, -0.1385, +0.0819, +0.0202, -0.3139, -0.0896, +0.5357, -0.7048, -0.0429, -0.1733, -0.6343, -0.2395, +0.2319, +0.1909, -0.3611, -0.0093, +0.0513, +0.2180, -0.2943, +0.1112, -0.1285, -0.6500, +0.4892, +0.0203, -1.1220, -0.0724, +0.4504],
-[ +0.1112, -0.0448, -0.6431, +0.1884, +0.3960, -0.1572, +0.1121, -0.1994, -0.0486, -0.2115, -0.0936, -1.5022, -0.2118, -0.6693, +0.3676, -0.2709, -0.3703, +0.3534, -0.0593, +0.2411, -0.3764, +0.2110, +0.2070, -0.3406, -0.2990, +0.4268, -0.0408, +0.1984, -0.3161, +0.3869, -0.3141, -0.4338, +0.0395, -0.3092, +0.2746, -0.2975, -1.0016, +0.0616, -0.2120, +0.0863, -0.0899, -0.3227, -0.1391, +0.2368, -0.5746, +0.3478, +0.0162, +0.8646, -0.4043, -1.0257, +0.3557, -0.1569, +0.1722, -0.1626, +0.2160, +0.4056, -0.7633, -0.3259, -0.2412, -0.0411, -0.0130, -0.1054, -0.6206, -0.3220],
-[ +0.4052, -1.3239, +0.1395, +0.1058, -0.1199, -0.1038, +0.1456, +0.3265, -0.3059, -0.7138, -0.0618, +0.3480, +0.5171, +0.0254, -0.2988, +0.2774, +0.0976, -1.0849, +0.3354, -0.0790, +0.2007, -0.1853, -0.5298, +0.0797, -0.0231, -0.7360, +0.0341, -0.2407, -0.0900, -0.2925, -0.3616, +0.1548, -0.2782, -0.0473, +0.0645, -0.1320, +0.1575, +0.0137, +0.1537, -0.3346, -0.0175, +0.1294, +0.2803, +0.2576, -0.1722, -0.4272, +0.1171, +0.0722, +0.1484, -0.6063, +0.0117, -0.1859, -0.8487, +0.4184, -0.0151, +0.1533, +0.1805, +0.0843, -0.2879, +0.1382, -0.2115, -0.0440, +0.0444, -0.0504],
-[ +0.2015, -0.0965, -0.1258, +0.1679, -0.1030, -0.0350, -0.6746, -0.3363, +0.0040, -0.4968, -0.5428, +0.0732, +0.1692, -0.2251, -0.1405, -0.8176, -0.8816, -0.2601, -1.5304, +0.1403, +0.0187, +0.2748, -0.3534, -0.5089, -0.3561, +0.0367, -0.1690, -0.1544, +0.0946, -0.2731, -1.0779, -0.0782, +0.0202, +0.2626, -0.1983, -0.0035, +0.0846, +0.2907, +0.3259, -0.2063, -0.2135, -2.0981, -0.0221, +0.0993, +0.0145, +0.1018, -1.0300, +0.1958, -0.4191, -0.1791, -1.3965, -0.0060, -0.2669, +0.1638, -0.2012, +0.1843, +0.0784, +0.2943, -0.7675, +0.2927, -1.4470, +0.0775, -0.3201, -0.3827],
-[ +0.0769, +0.5498, -1.0880, -0.2418, -0.2665, -0.2998, -0.1256, -0.6255, -0.3412, -1.4133, -0.0203, -0.0106, -0.3917, -0.8333, +0.4150, -0.3510, -0.5165, -0.4994, -0.7379, +0.3555, -0.0781, +0.0691, +0.6025, -0.1950, -0.5176, -1.1022, -0.2531, +0.1358, -0.7036, -0.2015, -0.3584, -1.2470, -0.1838, -0.2505, -0.1474, -0.4272, +0.2569, -0.5964, -0.9194, -0.0551, +0.3572, -0.0710, +0.1742, -0.4531, -0.3903, -0.3115, -0.1155, -0.2580, -0.7872, +0.2532, -0.1176, -0.1610, -0.7792, -0.6183, -0.4232, +0.3920, -0.2407, -0.8548, +0.3624, +0.3435, -0.8205, -0.2136, -0.2942, -0.8762],
-[ -0.0060, -0.1489, -0.0067, -0.0177, +0.2215, -0.0389, -0.5227, -0.2337, -0.2741, +0.0386, -0.3261, -0.0032, -1.0200, -0.1971, -0.2788, +0.1595, -0.2238, +0.0137, -0.0144, -0.2236, -0.2323, +0.2903, +0.3488, -0.2384, +0.1007, +0.2121, +0.3509, -0.4017, +0.0860, -0.7740, +0.0739, -0.8059, -0.0612, -0.0426, +0.2213, +0.2794, -0.1782, -0.0981, +0.0738, -0.1360, +0.0495, +0.1766, -1.0368, +0.0651, -0.1478, -0.3529, +0.6294, -0.0024, +0.0441, -0.2223, +0.2321, +0.5418, -0.3990, -0.1180, +0.2173, +0.0073, +0.0535, +0.0381, +0.0572, +0.1349, +0.1543, -0.0255, -0.0671, -0.3958],
-[ +0.0025, +0.2615, +0.2055, -0.3618, +0.2058, -0.0355, +0.2262, +0.1584, -0.2848, +0.3526, -0.1021, +0.4582, -0.2301, +0.8823, -0.3449, +0.7340, -0.2356, -0.1065, -0.1333, +0.1678, +0.0023, -0.5715, +0.0944, -0.2364, -0.0328, -0.1789, -0.7771, +0.0033, +0.6611, +0.1509, -0.0369, -0.1838, -0.0900, +0.0302, +0.4032, +0.3461, -0.3497, +0.3714, -0.2241, +0.3681, -0.1810, +0.1401, +0.4326, -0.3580, +0.1228, -0.5266, +0.1445, -0.1295, -0.7390, -0.0307, +0.2383, -0.3647, +0.8082, -0.2832, -0.1272, -0.6293, -0.0267, +0.0772, +0.5436, -0.4430, +0.2039, -0.0094, -0.4602, +0.3507],
-[ +0.4441, -0.5284, -0.3247, -0.1185, +0.1127, +0.2549, -0.1608, +0.0508, -0.1256, +0.1456, +0.0630, -0.3331, +0.2147, -0.1859, -0.1065, -0.8297, -0.8537, -0.5747, -0.2079, -0.2383, -0.0755, +0.2487, +0.4479, +0.2179, -0.4586, -0.0045, +0.0736, +0.0240, -0.1013, +0.1411, -0.3923, +0.0215, -0.2443, -0.9218, -0.0136, +0.2523, -0.3079, +0.2825, +0.4820, -0.0487, -0.4192, +0.3460, +0.2341, -0.1544, -0.1730, +0.1748, +0.4015, -0.0670, -0.4138, -0.7546, -0.0984, -0.1398, -0.1484, +0.2143, +0.3287, +0.3576, -0.1715, -0.4426, -0.1114, +0.2873, -0.1759, -0.2131, -0.3125, +0.2399],
-[ -0.3040, -0.7858, -0.0431, +0.2444, -0.4689, +0.5505, -0.0415, -0.2255, +0.4772, -0.9782, -1.3075, -0.7475, -0.2918, -0.4632, -0.4139, -0.2807, -0.9729, +0.0464, +0.2641, -0.0045, +0.2904, +0.2615, -0.4323, -0.2294, +0.4595, -0.4169, +0.2735, -0.7092, -0.8494, -0.9467, +0.0363, -1.6053, -0.0743, +0.1101, +0.2005, -0.1111, -0.2316, +0.3037, -0.0224, +0.4787, -0.1178, -0.2842, -0.1521, +0.0089, +0.0149, +0.2476, -0.3097, +0.4197, -0.0513, -0.3052, -0.1770, +0.0698, -0.0028, -0.7217, -0.0423, +0.0789, +0.0522, -0.4582, -0.0321, +0.8307, +0.2203, -0.0733, +0.3136, +0.0570],
-[ +0.1303, +0.0891, -1.0181, -1.4978, +0.0734, +0.1124, +0.2199, +0.0153, +0.4390, -0.4317, -0.5141, -0.4691, +0.0737, +0.3579, -0.1853, -0.0772, -0.8077, -0.6385, -0.4633, +0.4321, +0.5496, +0.2986, -0.1555, -0.1559, +0.0699, -0.3715, -0.2052, -0.2325, +0.3984, -0.4306, -0.6361, -0.3066, -0.4227, -0.7002, -0.5833, -0.0950, -0.2275, -0.2462, -0.2574, +0.3585, -0.2933, -0.1192, +0.4343, -0.5342, +0.1994, +0.3493, -0.7433, +0.0396, -0.2139, -0.7354, -1.5901, +0.2998, +0.2103, -0.2378, -0.3848, -0.1763, +0.5698, -0.8950, -1.7041, +0.2384, -0.1701, +0.1376, +0.3842, -0.8876],
-[ -0.1219, +0.3198, -0.2701, +0.1497, -0.1258, +0.3358, -0.4570, -0.4552, +0.5140, -0.1106, -0.5427, -1.0853, -0.1620, +0.1679, -0.7057, -0.5208, -1.5624, -0.6301, -0.6283, +0.0699, -0.1598, -0.1935, +0.0253, +0.1096, +0.0912, -0.0082, +0.0710, -0.9496, -0.0222, -0.3077, -0.4092, -0.1090, -0.1891, -0.0032, +0.4414, -0.4561, -1.1972, +0.4971, -0.0040, +0.0863, -1.3692, -0.1463, -0.1298, +0.3283, -0.2834, -0.0431, +0.0177, +0.0811, -0.2410, -0.0614, +0.2315, +0.3008, -0.6321, -0.8940, -1.5395, -0.6845, -0.5164, +0.5963, -0.1694, +0.0239, +0.3146, +0.5295, -0.1202, -0.2046],
-[ -0.4515, -0.5445, -0.4470, +0.1876, -0.0639, -0.2497, +0.2629, +0.2056, +0.4504, +0.1000, -0.1992, -0.1178, +0.5982, +0.1020, +0.2526, -0.5141, -0.3257, +0.2873, +0.2843, +0.0204, -0.0355, +0.4963, -0.0575, -0.2666, -0.6928, -0.0279, -0.4045, +0.4385, -0.1725, +0.2043, -1.0905, +0.3458, +0.2299, -0.1574, -0.6403, +0.4463, -0.4436, -0.0591, -0.8299, -0.2485, +0.3504, -0.2333, +0.1834, +0.0245, +0.0756, -0.0047, -1.1088, -0.0788, -1.0611, -0.2504, +0.2807, +0.1821, -0.1618, +0.0871, -0.1961, -0.0566, -0.8393, -0.2867, -0.5395, -0.7387, -0.9088, +0.1558, -0.0021, +0.1817],
-[ +0.2262, -0.0991, -0.7318, +0.0777, +0.0829, +0.1066, +0.0909, +0.0586, -0.1002, +0.2647, +0.3763, +0.2981, +0.2813, +0.1898, +0.2196, +0.1406, -0.2669, -0.0615, -0.4188, -0.3941, -0.2429, -0.2700, -0.6246, +0.0977, -0.0156, -0.6503, -0.3818, +0.2284, +0.2446, -0.2068, -0.0891, +0.1039, -0.5602, -0.0217, -0.0608, -0.0454, +0.0959, +0.4183, +0.2183, -0.3189, +0.1210, -0.0680, +0.1768, -0.3043, -0.2762, -0.8097, +0.4302, +0.1414, -0.6430, -0.1104, -0.3396, -0.4695, +0.4050, -0.1201, +0.0801, -0.1988, -0.0255, +0.1783, -0.0352, -0.4146, +0.1602, +0.0232, -0.4713, +0.2315],
-[ -0.2409, -0.2534, +0.3787, +0.8244, +0.0585, -0.1560, +0.3867, +0.4848, +0.0786, +0.3797, -0.4736, +0.1127, -0.1765, +0.4122, -0.0028, -0.0079, +0.4908, -0.2022, +0.0382, +0.3820, +0.1218, +0.4168, +0.0748, -0.0767, +0.1911, +0.1314, -0.3224, +0.2587, +0.2849, +0.3945, +0.0604, +0.0050, -0.3590, -0.7451, -0.3942, +0.2198, +0.2039, +0.2079, -0.3846, -0.0248, -0.4721, +0.1699, -0.0122, -1.2120, +0.4807, +0.0437, -0.1432, -0.0937, +0.3850, +0.0717, -0.6115, -0.1069, -0.3580, -0.7625, -0.1524, -0.5527, +0.0189, +0.2040, +0.1220, +0.4873, -0.3443, +0.1473, +0.2942, -1.2750],
-[ -0.0321, +0.0938, -0.1564, +0.0153, -0.0956, +0.0683, -0.1992, -0.8894, +0.0980, -0.0950, -0.5909, +0.1010, +0.0940, -0.7160, +0.0752, +0.5469, -0.6442, -0.0053, +0.2000, +0.3000, -0.3391, -0.1122, +0.3253, +0.1063, +0.1491, -0.0684, -0.0410, -0.3039, -0.6195, +0.2862, -0.1455, -0.8795, -0.3885, +0.0299, -0.0195, -0.1107, +0.0015, +0.4024, -0.9457, -0.4620, +0.0877, -0.2296, -0.0326, +0.2932, -0.2720, +0.4663, -0.0610, +0.1745, +0.1352, -0.5966, -0.1366, +0.2271, -0.4483, -0.4548, +0.0057, +0.2810, -0.4279, +0.0572, -0.8984, +0.1419, -0.1966, +0.0214, -0.5856, -0.4380],
-[ -0.2850, -0.4454, -0.0200, +0.1379, +0.1279, +0.1286, +0.5722, -0.0797, +0.1775, +0.0054, +0.3466, -1.1324, +0.0630, -0.0436, -0.9319, +0.0692, +0.1615, -0.1780, +0.1783, +0.0662, +0.2824, -0.0309, -0.1921, +0.2110, -0.2472, +0.0026, +0.3590, -0.1833, -0.0167, -0.6163, -0.1092, +0.2120, +0.4458, +0.0250, -0.8406, -0.0331, +0.3448, -0.5886, -0.0235, +0.0602, +0.3971, +0.4033, +0.3516, -0.1472, -0.2371, -0.8047, +0.1336, -0.1083, -0.5510, +0.3792, -0.4230, -0.1216, -0.7740, -0.4497, -0.2848, -0.3698, -0.0160, +0.5724, -0.4150, +0.3254, -0.2344, +0.4417, +0.0460, -0.0463],
-[ -0.1091, -0.0947, -0.3343, -0.8910, -0.0137, +0.1534, -0.3422, -0.5111, +0.0206, +0.2841, +0.2981, +0.3313, +0.2598, -0.0501, -0.5783, +0.3304, -0.2725, +0.1159, -0.2722, -0.5441, +0.2231, -0.0244, +0.3478, +0.1623, -0.2798, -0.0695, +0.3506, -0.1275, +0.2209, -0.3317, -0.2965, +0.4564, -0.2473, -0.3701, +0.4166, -0.1918, +0.0488, +0.5048, +0.4159, -0.1447, +0.0998, +0.0424, +0.0734, -0.3713, +0.3236, -0.4136, -0.2221, +0.1728, -0.6407, +0.2623, -0.4332, +0.4175, +0.2960, -0.3424, -0.5264, -0.5679, +0.2437, -0.6032, -0.5213, -0.0424, -0.5911, -0.0611, -0.1877, +0.2423],
-[ -0.0360, -0.4567, -0.1493, -0.0765, -0.2676, +0.1338, +0.1486, +0.3867, +0.2451, -0.2054, -0.1088, -1.5518, +0.2254, +0.0175, -0.1154, -0.3777, -0.6173, -0.8897, -0.1523, +0.1594, -0.1772, -0.3349, -0.1155, -1.1580, +0.2605, +0.0570, +0.1894, -0.0755, +0.2382, -0.1726, -0.0400, +0.4391, +0.2241, +0.0551, -0.1106, +0.0817, +0.0128, -0.1330, -0.0162, -0.3872, -0.2613, -0.2073, +0.0483, +0.0026, -0.1008, -0.0389, -0.6723, -0.0657, +0.1532, -0.0627, -0.2517, -0.1961, -0.0313, -0.2694, +0.1040, +0.2662, -0.3370, +0.2086, -0.2202, +0.2812, -0.9275, -0.0331, +0.1384, -0.4651],
-[ -0.0323, +0.5816, +0.2069, +0.1766, +0.8736, -0.1321, -0.5366, +0.4362, -0.9437, +0.5586, +0.8281, +0.1417, +0.4988, +0.2451, -0.1327, +0.3295, +0.1639, +0.2168, -0.5869, -0.9139, +0.3259, -1.2364, +0.0104, -0.4723, -0.2869, -0.0693, -0.1767, +0.0528, +0.3629, +0.0766, -0.2554, +0.7631, +0.0007, +0.3657, +0.2479, +0.0949, -0.1070, +0.2789, -0.6009, +0.3627, -0.1986, +0.3212, +0.5274, +0.2307, +0.1055, -0.8864, +0.4670, +0.0430, -0.2485, +0.0445, -0.0792, +0.0362, -0.7101, -0.1554, +0.4530, -0.5127, -1.0097, -0.4877, +0.1803, +0.1016, +0.2774, -0.7071, -0.2316, +0.1476],
-[ +0.0676, -0.2920, +0.4224, -0.1409, +0.0856, -0.0969, +0.2461, -0.7079, -0.4348, -0.8510, -0.2213, -0.0541, -0.0461, -0.2451, +0.2312, -0.0496, +0.3432, -0.1916, +0.1832, +0.4089, +0.1642, -0.0928, +0.1869, +0.2472, -0.9379, -0.0356, -0.2276, -0.1867, -0.1108, +0.3021, -0.7620, -0.0141, +0.3072, -0.0326, -0.1854, -0.0535, +0.3489, -0.3910, -0.8369, +0.5177, +0.3154, +0.6535, -0.4463, -0.4381, -0.2189, +0.2761, +0.1655, +0.1010, -0.0769, -0.5381, -0.4710, +0.1980, -0.0818, -0.3762, +0.0076, +0.1753, -0.0984, -0.5887, -0.0019, -0.4983, +0.2914, -0.7693, +0.1656, -0.6165],
-[ +0.2126, -0.3435, -0.2802, +0.0979, -0.9373, -0.7181, +0.2063, -0.2545, +0.3562, +0.0894, +0.5294, -0.3816, +0.5833, -0.2488, -0.4786, +0.2132, -0.3223, +0.2189, +0.2034, +0.0680, +0.3741, -0.2337, -0.2645, -0.2871, -0.3461, +0.3580, -0.7551, -0.4948, -0.4941, -0.1607, -0.0062, +0.3991, +0.5354, -0.1153, +0.4384, +0.2346, +0.0923, +0.6214, +0.2485, -0.2547, -0.2755, +0.3398, +0.2522, +0.0409, +0.1309, -1.1476, +0.4321, -1.6605, -0.6035, -0.5415, -0.0799, -0.1754, -0.5326, -0.1910, +0.1372, -0.4079, -0.3110, +0.0060, +0.0015, -0.7618, +0.5021, -0.3054, -0.1895, +0.4327],
-[ +0.1316, +0.1998, +0.0677, +0.2773, -0.2720, -0.8087, -0.0022, -0.2622, -1.0104, -0.4908, +0.4249, +0.0597, -0.5553, -0.4698, -0.0096, -0.1893, +0.1355, -0.6921, +0.0211, +0.3253, -0.0769, +0.0565, -0.6166, -0.7295, +0.0477, -0.0101, -0.5214, -0.6498, -0.7418, -0.8979, +0.0792, -0.1958, -0.5255, +0.1953, -0.6446, -0.0748, -0.3183, +0.1582, -0.3667, +0.2170, +0.2665, -0.0075, +0.0740, +0.2708, -0.1289, +0.0462, -0.6262, -0.4190, -0.1797, +0.3994, -0.8803, -0.4579, -0.3235, +0.2903, -1.3589, -0.5549, -0.6767, +0.0308, +0.0491, -0.3117, +0.2053, +0.1075, +0.2042, -0.4537],
-[ -0.9114, +0.3823, -0.2137, -0.0383, +0.0891, -0.5047, -0.3632, -0.0115, -0.3604, +0.2107, -0.4123, -0.1508, -0.3897, -0.1566, -0.3869, +0.0458, -0.3594, -0.6799, -1.0821, -0.2322, +0.1464, +0.2626, -0.1674, -0.5577, +0.0910, -0.1279, +0.4003, -0.1568, +0.0907, -0.1528, -0.0554, +0.4973, +0.3610, +0.3540, +0.3717, -0.2353, +0.1743, +0.2026, +0.8891, -0.5409, -0.3690, +0.1897, -1.1785, -0.0244, +0.0283, +0.0709, -0.9182, -0.1485, +0.3410, -0.3562, +0.1126, +0.3459, +0.0190, +0.4073, -0.0685, -0.0834, +0.1817, +0.3957, +0.3428, +0.2351, -0.2072, -0.2002, +0.0579, +0.2585],
-[ +0.0476, -0.7260, -0.2175, -0.8305, +0.3673, -0.1075, -0.7324, +0.1022, -0.1264, +0.0679, -0.2494, +0.2647, -0.7667, +0.1632, -0.1487, -0.1800, -0.4566, -0.4716, +0.3124, +0.4227, -0.2557, +0.1477, -0.0946, +0.0803, +0.0136, +0.0699, -0.6304, +0.5944, +0.1812, -0.0072, -1.2447, +0.7503, -0.7340, -0.6389, -0.0202, +0.1716, -0.0661, -0.7511, -0.6451, +0.4344, +0.2398, +0.9628, -0.2201, +0.1901, +0.6633, -0.0529, -0.3787, +0.3837, -0.4481, +0.1792, -0.2828, +0.7377, +0.6304, -0.9296, +0.1690, +0.5375, +0.3884, -0.3548, +0.0788, -0.7348, +0.2273, -0.5028, -0.4739, +0.1150],
-[ +0.1521, -0.0100, -0.1015, +0.1975, -0.5804, -0.0891, +0.4443, -0.0275, -0.3218, -0.3674, -1.0237, -0.9589, +0.1408, +0.1039, -0.4158, -0.3465, -0.2163, +0.3031, -0.0905, -1.1000, +0.0028, +0.1196, +0.1130, +0.4777, -0.0803, -0.3295, -1.5273, -0.4059, -0.2642, -0.6425, +0.1149, -0.0094, +0.1067, -0.6440, -0.0806, +0.2513, +0.2070, -0.0682, -0.0854, -0.4654, +0.0119, -0.2918, +0.0766, -0.0766, +0.0621, -0.5751, -0.7636, -0.4295, -0.1413, +0.0667, -0.0193, +0.0210, +0.1867, +0.1727, -0.0391, -0.5251, -0.0746, +0.0615, -0.0581, -0.4284, -0.2977, -0.0883, -0.1302, +0.1829],
-[ -0.1256, +0.0829, -0.5799, -1.0012, +0.3669, +0.2700, +0.2691, -0.2078, +0.6662, +0.4342, -0.7014, +0.1332, +0.0736, +0.5960, +0.1266, +0.4412, -0.3859, +0.0702, -0.7489, -0.1285, +0.1080, -0.0248, -0.0614, -0.2922, -0.1791, +0.2619, -0.2986, +0.1326, -0.1112, -0.4128, -0.3499, -0.2148, +0.0886, -0.3239, +0.1767, +0.2782, -0.1033, -0.1350, +0.0324, -0.2402, +0.2440, +0.2858, +0.0111, -0.6319, +0.3694, -0.5569, +0.0758, -0.5506, -0.8423, -0.6073, -0.0642, +0.0559, +0.3943, -0.1092, -0.3964, +0.0705, -0.3753, +0.2106, -0.0118, -0.2122, -0.0904, +0.3428, -0.2614, -0.0007],
-[ +0.3415, +0.4062, -0.4667, +0.2757, -0.5389, -0.1429, -0.0005, +0.1749, -0.1646, -0.9262, +0.1978, -0.3748, +0.3384, +0.1757, -0.0899, +0.1567, +0.3043, -0.0828, -0.7369, +0.2833, +0.2871, -0.0150, -0.0895, +0.2181, -0.3692, -0.2344, -0.3813, -0.4984, +0.2426, +0.3936, -0.3995, -0.0257, -0.2650, -0.5329, -0.6254, +0.0492, -0.0428, +0.3595, -0.1242, -0.3341, -0.1174, +0.2283, +0.3051, -0.0794, -0.0715, +0.2324, +0.1567, -0.4121, +0.0756, -0.6483, -0.7294, -0.0235, -0.5082, -0.1506, -0.0962, +0.1123, +0.1990, -0.5521, -0.8837, +0.2634, -0.6452, +0.0470, +0.0747, +0.0456],
-[ -1.2951, +0.1232, -0.8490, +0.2284, +0.3593, -0.9968, +0.1914, +0.3673, +0.1287, +0.0485, -0.6153, -0.6149, -0.2634, -0.7023, +0.2006, +0.2657, -0.0201, -0.6250, -0.1045, -0.5447, -0.2495, -0.0712, -0.2281, -0.1573, -0.0079, -0.4966, -0.5428, -1.5871, -0.0332, -0.3754, +0.0438, -0.2096, -0.0341, -0.2111, -0.1953, -0.1146, +0.0260, -0.0840, -0.9739, +0.0693, +0.1628, -0.6525, -0.9299, +0.1602, -0.0673, -1.1183, -1.1446, -0.0575, +0.0123, +0.0463, +0.0683, +0.0192, -0.7718, -0.1055, -0.1894, +0.3897, -0.8589, +0.2829, +0.0774, -0.1157, +0.0772, +0.0168, +0.3460, +0.2657],
-[ -0.3160, +0.3029, +0.2132, -0.2024, -0.0573, +0.2263, +0.3686, -0.2059, +0.2531, -0.4922, -0.4110, -0.0881, -0.0267, -0.3069, +0.2496, -0.2458, -0.0348, -0.4285, +0.0564, +0.5539, +0.3510, +0.0755, +0.2656, +0.5299, -0.0647, +0.0431, +0.3277, +0.0192, -0.3490, +0.2500, +0.2519, +0.2055, +0.2462, -0.2927, +0.2902, -0.1451, -0.0611, -0.3940, -0.6985, +0.0295, -0.1272, -0.0507, +0.0030, -0.0484, -0.4220, +0.3042, -0.1346, -0.4380, +0.0247, -0.2205, -0.1549, -0.7229, -0.1487, -0.1124, +0.2539, +0.1274, +0.6169, +0.3346, -0.1577, +0.4318, +0.1469, -0.0689, +0.0982, -0.3816],
-[ +0.4151, +0.1020, -0.3973, -0.1940, -0.0893, -0.5294, -0.0714, +0.1221, +0.2081, -0.1500, +0.0839, +0.0651, +0.1602, +0.1521, +0.3755, +0.4533, -0.0749, -0.1498, +0.0048, +0.2987, +0.3013, -0.2483, -0.8249, +0.1123, -0.2657, -0.0776, -0.8314, -0.0567, +0.4846, +0.1280, -0.4166, +0.2149, -0.5095, -0.2219, -0.6757, +0.5484, +0.2117, +0.1901, -0.3840, -0.0860, -0.0527, -0.8445, +0.1747, -0.7124, +0.3261, -0.0172, -0.4794, +0.2829, -0.9583, -0.3825, -0.2641, -0.1610, +0.0921, +0.0395, -0.7542, -0.4747, +0.0891, -0.5037, +0.4109, +0.2718, -0.1609, +0.3680, -0.2975, +0.0092],
-[ -0.2679, -0.2103, +0.1004, +0.2703, +0.0541, +0.4900, +0.1016, +0.0008, -0.0075, +0.0959, -0.2459, -0.4452, +0.1211, -0.0521, -0.5468, +0.2349, -0.0690, +0.0936, -0.3218, -0.0093, +0.0644, +0.4158, +0.1109, +0.2373, +0.3008, -0.2570, +0.2886, -0.1720, +0.3146, -0.6991, +0.2565, -0.1762, -0.0239, -0.6296, -0.8216, -0.8141, +0.0871, -0.5981, +0.2595, +0.2109, -0.3252, -0.2758, +0.2662, -0.1662, +0.0087, -0.3265, +0.2910, -0.3716, +0.3225, +0.0907, +0.0550, +0.4069, +0.3731, -0.0367, -0.0844, -0.7320, +0.3318, +0.0839, +0.1493, -0.1054, -0.4476, +0.0671, +0.3858, -0.3728],
-[ -0.0163, +0.4856, -0.1412, -0.0100, -0.2343, +0.1223, -0.5244, -0.4046, +0.1738, -0.0262, +0.0922, -0.6767, +0.2672, +0.1770, -0.4969, +0.3919, -0.1103, -0.3749, +0.2580, -0.0209, -0.2500, -0.1089, +0.0587, +0.4735, +0.2116, +0.0299, +0.1709, +0.0804, +0.8460, +0.1637, +0.1775, -0.3955, +0.2403, -0.1843, +0.0579, -0.3362, +0.1129, +0.2148, -0.0079, -0.0662, -0.1286, +0.1830, +0.0437, +0.0167, -0.0824, -0.1148, +0.2380, -0.3372, -0.0684, -0.3226, +0.2914, +0.0994, -0.1599, +0.0130, +0.1584, +0.0975, +0.2723, +0.1877, -0.4828, +0.1463, -0.2304, +0.3497, +0.0522, -0.0404],
-[ +0.3846, +0.3960, +0.0721, -0.5932, -0.6720, +0.3994, -1.1131, +0.0500, -0.0433, -0.5014, -0.2795, +0.0226, -0.0276, -0.3389, -0.1971, +0.3228, -0.3439, +0.5770, +0.5260, -0.2861, +0.3810, -0.0225, +0.3133, +0.1716, +0.0778, -0.1298, +0.0765, -0.1700, +0.5689, +0.2767, -0.5815, +0.2572, -0.7600, -0.1481, +0.2901, -0.4648, +0.1381, +0.2972, -0.4802, -0.6701, -0.6240, -0.0784, -0.0330, -0.5339, +0.1989, +0.2422, +0.0886, -0.1819, -0.2638, +0.0189, -0.1023, +0.3559, +0.2563, +0.0272, -0.1343, +0.2034, +0.6096, -0.2862, -0.2925, +0.1162, -0.5740, -0.4293, -0.1544, -0.3657],
-[ -0.1666, -0.5683, +0.3239, +0.0008, -0.0790, +0.0108, +0.1210, +0.2313, -0.0242, -0.3114, +0.1546, -0.0983, -0.1095, -0.5754, +0.1360, -0.7269, +0.0714, -0.9205, +0.2401, +0.0983, +0.1060, +0.0410, +0.2889, -0.7942, +0.3511, +0.1338, +0.1118, +0.1873, -0.4490, +0.2648, -0.1163, +0.1410, -0.0005, -0.0627, +0.2816, -0.0261, +0.0111, -0.3929, -0.3200, +0.3405, +0.1021, -0.0294, +0.2000, -0.2919, -0.2395, +0.1867, +0.1548, -0.0702, +0.0021, +0.5599, -0.2662, -0.4859, -0.1809, +0.2777, +0.2588, +0.1977, +0.0975, -0.3367, -0.1211, +0.1057, -0.0247, +0.4044, +0.4802, -0.4940],
-[ -0.3074, +0.2169, +0.0655, -0.3575, +0.2765, -1.0735, +0.3228, -0.7085, -0.1075, -0.1250, +0.1302, -0.2700, -0.6832, -0.0223, -0.5448, +0.3824, -0.5548, +0.2615, -0.4700, +1.0847, -0.0443, -0.9753, +0.1278, +1.0526, +0.7114, +0.2395, +0.1612, -0.3276, +0.3154, +0.4751, -0.3890, -0.2353, +0.6575, -0.1306, -0.4566, -0.3303, +0.6051, -0.1868, -0.9390, -0.3405, +0.3341, +0.5198, +0.0939, -0.6396, -0.0410, -0.0942, -0.4784, -0.6260, -0.0983, -0.3750, -0.1402, -0.0351, +0.0890, -0.5765, +0.3816, -0.5375, +0.6580, +0.0448, -0.3544, +0.1669, +0.0808, -0.4698, +0.0085, +0.5292],
-[ -0.1747, -0.5134, +0.1257, +0.6530, +0.3251, +0.0013, +0.8608, -0.6414, +0.3327, -0.3861, +0.5066, -0.8033, +0.1957, -0.2380, -0.1649, -0.0760, -0.3093, -0.3283, +0.0661, -0.1066, +0.3787, -0.3254, +0.5536, -0.4949, +0.1560, +0.1118, +0.1465, +0.3107, +0.5213, +0.1194, +0.2602, +0.0551, -0.0612, +0.1378, -0.1037, +0.5086, -0.3383, -0.2024, -0.1786, -0.2193, -0.3955, -0.0600, +0.4502, -0.0450, -0.3765, -0.9599, +0.2312, +0.0751, -0.1329, +0.1573, -0.2891, -0.0944, -0.4619, +0.3256, +0.2486, -0.2238, +0.2054, -0.1677, -1.2201, +0.2986, +0.5681, +0.0700, -0.0916, +0.3844],
-[ +0.5860, +0.1473, -0.3536, +0.1924, -0.1819, +0.3126, -0.3094, +0.4127, -0.3403, -0.3101, +0.4899, +0.3310, +0.3136, -0.1343, +0.1557, +0.0007, +0.0431, -0.0531, -0.3300, +0.3820, -0.3771, -0.6818, -0.4023, -0.1221, -0.0995, +0.1512, -0.2698, -0.0544, +0.0406, +0.0104, +0.2382, +0.0113, +0.5360, +0.3837, +0.0947, +0.4839, +0.0278, -0.4629, -0.1912, -0.7728, -0.0162, +0.5847, +0.1752, +0.1536, -0.3113, -0.4624, -0.2032, -0.2410, -0.0095, -0.3411, -0.2375, -0.3024, -0.0689, +0.0134, -0.2987, +0.2678, +0.1053, +0.3568, -0.3776, -0.0956, +0.1105, +0.1802, +0.3608, +0.2763],
-[ -0.0126, -0.1275, +0.1721, -0.1653, +0.0189, -0.0586, +0.1487, +0.2661, -0.0924, -0.1733, +0.0411, +0.1124, -0.0426, -0.0405, +0.0713, -0.1322, +0.1053, +0.2013, +0.2442, -0.4979, +0.3654, -0.2099, +0.0049, -0.6743, -0.1063, -0.1213, +0.2036, +0.2109, -0.2639, +0.1839, +0.3105, -0.0961, +0.3935, +0.1186, -0.0959, +0.5348, -0.3605, -0.6159, -0.3268, +0.1327, +0.5812, -0.4447, -1.8573, +0.1350, -0.0151, +0.1569, +0.0348, +0.2221, -0.6421, -0.2810, +0.1918, -0.1290, +0.0505, +0.0517, +0.0313, -0.0781, +0.1746, +0.0713, +0.2894, -1.0579, -0.1106, +0.3800, -0.6895, -1.1236]
+weights_dense1_b = np.array([
+ +0.0484, -0.2398, -0.1357, +0.0298, -0.3778, -0.2392, -0.0211, -0.1728,
+ +0.0154, -0.1052, -0.0235, -0.0825, -0.0137, -0.1951, +0.1408, -0.2835,
+ -0.4597, -0.2002, -0.1659, -0.2736, -0.0233, -0.2472, -0.0697, -0.1892,
+ -0.1340, -0.0051, -0.1712, -0.1986, -0.1902, -0.1213, -0.1363, -0.2731,
+ -0.0609, +0.0803, -0.1623, +0.0661, -0.0660, -0.1206, -0.2835, -0.1281,
+ -0.1008, -0.2377, -0.1436, -0.1027, -0.1816, -0.1699, -0.2476, -0.0886,
+ -0.1582, -0.1714, -0.1558, -0.2484, -0.1255, -0.1657, -0.0830, -0.0800,
+ -0.1293, -0.0594, +0.0174, +0.1097, -0.1769, -0.1648, -0.1995, -0.1082,
+ -0.1761, +0.0342, -0.1445, -0.0106, -0.2021, -0.1352, -0.2769, -0.1503,
+ +0.1171, -0.2275, -0.1514, -0.1064, -0.1877, +0.0308, -0.1081, -0.0229,
+ -0.1273, -0.0516, -0.0789, -0.1148, -0.0308, -0.1946, -0.3185, -0.1215,
+ -0.0605, -0.1876, -0.1192, -0.1545, -0.0148, -0.0218, -0.3640, -0.2230,
+ +0.1549, +0.0196, -0.2555, -0.1814, -0.3217, -0.1741, +0.0117, -0.1752,
+ -0.2445, -0.0863, +0.0041, +0.0058, -0.0948, -0.1010, -0.0595, +0.0182,
+ -0.0761, -0.0141, -0.1886, -0.0474, +0.0057, -0.1247, -0.3390, +0.0672,
+ -0.0612, -0.1059, +0.0219, -0.1802, -0.1265, -0.1287, +0.0565, -0.0502
])
-weights_dense2_b = np.array([ +0.1534, -0.0356, +0.0392, +0.0272, +0.0733, +0.2141, -0.0432, -0.0479, -0.1264, +0.1456, +0.2103, -0.0233, +0.2320, -0.0525, +0.1808, +0.1565, -0.0347, -0.0719, -0.2635, -0.1948, -0.1301, +0.0453, -0.0722, +0.0875, +0.3780, +0.1023, +0.1012, +0.3150, +0.1801, +0.1941, +0.2014, +0.1381, +0.1411, -0.0371, -0.0987, +0.1987, +0.1015, -0.2282, +0.0072, -0.0800, +0.0323, +0.1198, +0.2822, +0.0090, -0.1950, +0.0864, +0.2694, -0.0746, +0.2193, +0.1658, +0.0712, -0.1185, +0.1351, +0.1331, +0.3542, +0.1543, +0.1557, -0.0575, +0.0659, -0.0090, -0.1502, +0.0665, +0.1853, -0.0413])
+weights_dense2_w = np.array(
+ [[
+ +0.4072, -0.1577, +0.0300, -0.0725, +0.6609, -0.5568, +0.0820, -0.2073,
+ +0.3434, +0.0637, +0.0899, -0.1563, +0.1371, +0.7268, -0.4818, +0.0706,
+ -0.1386, +0.4026, +0.2577, -0.4374, +0.4362, +0.2120, +0.0860, +0.0373,
+ -0.5472, -0.4427, +0.0769, +0.3067, +0.3401, -0.0008, -0.7384, +0.0566,
+ -0.0583, -0.3481, -0.2953, -0.1032, -0.7956, -0.6262, -0.0733, -0.6908,
+ -0.4126, -0.2014, +0.6791, -0.5321, +0.5106, -0.1055, +0.0604, -0.5233,
+ -0.8984, -0.4227, -1.3192, +0.3693, +0.2789, -0.2774, +0.0132, -0.1824,
+ -0.0690, -1.6134, -0.2901, -0.1739, -0.5780, -0.3432, +0.0980, -0.3106
+ ],
+ [
+ -0.3167, -0.2520, +0.1710, +0.1912, +0.0268, -0.1353, +0.0637,
+ -0.3158, +0.3448, +0.4247, -0.2795, -0.6464, -0.5002, +0.1116,
+ -0.0497, -0.7619, -0.1402, +0.0142, -0.0314, -0.0418, -0.6087,
+ +0.1742, -0.2843, -0.3738, +0.0595, +0.2382, +0.7762, +0.4531,
+ -0.8817, -0.0971, -0.4319, +0.0168, -0.7739, -0.6792, +0.3594,
+ -0.2188, -0.7423, +0.2473, -0.2793, +0.0149, -0.2970, -0.0695,
+ +0.6082, -0.5475, -0.5990, +0.6079, +0.2662, +0.2195, -0.5335,
+ -0.1782, -0.1657, +0.0951, -0.1763, -0.3554, -0.1032, +0.3347,
+ -0.2818, -0.6144, -0.2387, -0.3771, -0.0378, +0.0776, -1.4711, -0.1353
+ ],
+ [
+ -0.2935, -0.8083, -0.1306, +0.1952, -0.1178, -0.4799, +0.0777,
+ -0.4029, -0.5699, -0.1755, -0.0172, +0.1791, -0.0261, -0.2480,
+ +0.0181, -1.0284, -0.2705, +0.4318, +0.1634, -0.2889, -0.0075,
+ -0.1050, +0.0859, +0.0544, -1.0494, +0.0273, -0.1991, -0.2565,
+ -0.3891, -0.1883, -0.4818, -0.2458, +0.2761, +0.1295, -0.2284,
+ -0.0114, +0.2609, -0.1632, -0.0384, +0.0558, -0.2330, -0.3149,
+ -0.1879, -0.0787, +0.2492, -0.1629, +0.3027, +0.5257, -0.4112,
+ -0.2063, -0.0745, +0.0864, -0.1151, -0.3392, +0.2214, +0.2084,
+ -0.1933, +0.0103, -0.0245, +0.0280, +0.0170, -0.1814, +0.0239, -0.6701
+ ],
+ [
+ +0.0470, -0.1471, -0.3533, -0.2277, +0.2617, -0.2955, -0.2491,
+ -0.1937, +0.2634, +0.0681, -0.2869, -0.1950, +0.1615, +0.2557,
+ -0.0025, +0.2327, -1.0104, +0.3358, +0.2386, -0.6202, -0.0829,
+ +0.3342, +0.0617, -0.0119, -0.6297, -0.2430, +0.2088, +0.0102,
+ +0.3480, -0.0119, -0.3172, +0.1668, -0.2217, +0.1130, -0.0817,
+ +0.0391, -0.0480, -0.1680, -0.1306, -0.4677, -0.1638, -0.3569,
+ -0.1594, +0.2110, +0.3875, -0.1732, -0.0210, -0.3070, -0.7983,
+ +0.2381, -0.0294, -0.2019, +0.1801, +0.2116, +0.2506, -0.0342,
+ -0.7177, -0.6430, +0.3333, -0.7577, -0.3507, -1.0563, -0.4578, +0.0739
+ ],
+ [
+ +0.0584, +0.2110, +0.2883, +0.4496, -1.4306, -0.3233, +0.1243,
+ -0.5887, +0.1677, -0.1064, -0.3807, -0.0439, -0.8551, -1.2286,
+ +0.2521, -0.0060, +0.6236, -0.1993, +0.3985, -0.2662, -0.0002,
+ +0.0486, -0.2869, -0.6390, -0.1125, -1.3003, +0.1867, -0.3180,
+ -0.7481, +0.1080, +0.3788, -0.3003, -0.1799, -0.4549, -0.0974,
+ -0.0827, +0.3762, +0.2356, -0.2579, +0.4377, -0.1295, -0.3391,
+ -0.7046, -0.1904, -0.1341, -0.0194, -0.2193, -0.3140, -0.1927,
+ -0.3742, +0.2955, +0.1099, -0.5704, +0.0968, -0.0678, -0.1847,
+ -0.0211, -0.3002, -0.4862, +0.4810, -0.0444, +0.4728, +0.1298, -0.0902
+ ],
+ [
+ +0.0349, +0.9685, -1.9391, -0.3447, -0.1261, -0.3633, -0.0598,
+ -0.6471, -0.8648, -0.7718, -0.4766, -0.8915, -0.5728, -0.5278,
+ +0.5933, -0.3178, +0.0116, +0.3050, +0.3750, -1.1527, -0.0571,
+ -0.2033, +0.4198, +0.2105, -0.7927, -0.6716, -1.0696, -0.7200,
+ -0.5883, -0.6538, -0.4865, -0.8737, +0.0426, +0.2175, -0.2165,
+ -0.0444, -0.1326, -0.0308, -0.1097, +0.0105, -0.1852, -0.3861,
+ -0.2117, -0.5265, +0.0367, -0.0218, +0.2472, -0.2354, -1.1444,
+ -0.3036, -1.6033, +0.1154, -0.3195, +0.3943, -0.8171, -0.0495,
+ -0.0950, -0.3764, -0.1523, -0.8749, +0.2594, +0.2451, -0.1734, -0.0927
+ ],
+ [
+ +0.4523, +0.0513, -0.0013, +0.1556, +0.2430, -1.2187, -0.3108,
+ -0.7597, -0.7845, -0.6297, -0.0224, +0.3207, +0.2222, -0.2645,
+ +0.1510, +0.1624, -0.0568, -0.8426, -0.3564, +0.0187, +0.2791,
+ +0.0447, -0.1822, -0.2627, +0.0078, -0.9392, +0.0805, +0.0339,
+ +0.3228, -0.0153, -1.4823, -0.0994, +0.2658, -0.0138, -0.1071,
+ +0.2001, -0.3299, -0.5982, -0.2859, -0.1269, +0.0496, -0.0371,
+ +0.3491, -0.3822, +0.1167, -0.2964, -0.4635, +0.0549, -0.6313,
+ -0.4994, -0.2447, +0.0584, +0.2663, -0.0663, -0.1714, -0.1748,
+ -0.5364, -0.3646, +0.1584, +0.0349, +0.1420, -0.6877, -0.3539, +0.2209
+ ],
+ [
+ -1.2158, -0.7080, +0.1037, -0.1613, +0.0811, -0.9051, -0.4186,
+ -0.6072, -0.6212, +0.0362, -0.3524, +0.2563, -0.7313, -0.2856,
+ +0.0658, -0.1271, -0.1249, -0.6959, -0.4723, +0.4467, -0.1244,
+ -0.0056, +0.5042, -0.5181, +0.0475, +0.2931, +0.3883, -0.2017,
+ -0.0388, +0.0403, +0.1562, -0.9404, +0.0620, -0.5598, -0.5657,
+ +0.0578, +0.0086, -0.5689, -0.9304, +0.3161, -0.1303, -0.4087,
+ -0.5053, -0.1267, +0.0123, -0.6312, -0.6991, -0.0800, -0.8634,
+ +0.2347, +0.1449, +0.3955, +0.4396, -0.0684, +0.2644, -0.7668,
+ -0.1511, +0.0324, +0.0823, -0.3579, +0.0592, +0.0904, +0.2380, +0.0873
+ ],
+ [
+ -0.6992, +0.1539, +0.4253, -0.2513, +0.1882, +0.6842, -0.6867,
+ -0.2942, -0.3434, +0.2486, -0.4180, -0.6950, +0.2628, +0.7324,
+ -0.2667, -0.1330, -1.3123, +0.0990, -0.1324, -0.0016, -0.0310,
+ +0.0778, -0.1325, +0.2886, -0.2052, +0.0094, +0.1791, +0.1105,
+ +0.4348, -0.6778, -0.3301, +0.1438, +0.1093, +0.0140, -0.1957,
+ -0.1226, +0.0676, +0.9343, -0.1993, +0.1818, -0.1565, +0.3443,
+ -0.1359, -0.5234, +0.2591, +0.3769, +0.4966, -0.6424, -0.0288,
+ +0.0357, -0.3554, -0.1676, -0.2453, -0.4502, -0.3745, -0.1692,
+ -0.2449, -0.2132, -0.0001, +0.0087, +0.3669, +0.3835, +0.0003, +0.6565
+ ],
+ [
+ +0.2329, -0.0695, +0.4082, -0.0004, +0.0059, +0.1418, +0.1081,
+ -0.3141, +0.2218, -0.0538, -0.0670, +0.0018, -0.1211, -0.0491,
+ -0.3059, -0.4239, -0.1665, +0.0700, +0.4327, -0.5063, +0.3045,
+ +0.7774, +0.4464, +0.2276, -0.3467, +0.5197, +0.1607, -0.1339,
+ -0.1663, +0.0881, +0.0232, -0.3337, +0.0157, -1.1305, -0.1427,
+ -0.7464, -0.3650, +0.2386, +0.2734, +0.5966, -0.4067, +0.3709,
+ +0.2986, -0.3682, -0.1436, +0.3259, +0.3393, -1.2748, -0.5180,
+ +0.1099, -0.0843, +0.0421, +0.1176, +0.0935, +0.3649, +0.1282,
+ +0.2074, -0.4244, -0.3379, -0.8103, -0.1238, -0.6615, -0.5262, -0.9899
+ ],
+ [
+ +0.2683, +0.0401, -0.2063, -0.0863, -1.1390, -0.1614, +0.4551,
+ -0.2386, -0.9135, -0.1037, +0.3364, +0.0943, +0.3665, -0.2748,
+ +0.2592, -0.0339, +0.4767, -0.1381, -0.2326, +0.0600, +0.1522,
+ -0.3524, +0.4203, -0.4977, -0.2533, -0.4959, +0.1211, -0.1722,
+ +0.0681, -0.2369, +0.2398, +0.2182, +0.0582, +0.4106, -0.2708,
+ +0.1474, +0.3402, +0.3310, +0.1319, -0.2479, +0.1749, +0.3886,
+ -0.1866, +0.0482, +0.2373, -0.4678, -0.1560, +0.4025, -0.3261,
+ +0.6000, -1.2795, +0.2571, -0.0926, -0.2927, +0.2793, -0.4958,
+ +0.0614, -0.0140, -0.1622, -0.4095, -0.1560, -0.2754, +0.1172, -0.1319
+ ],
+ [
+ -0.5295, -0.0999, +0.0220, +0.3271, +0.2059, -0.4296, +0.3921,
+ -0.0843, -0.4874, +0.3199, +0.4602, -0.8274, +0.2366, +0.6108,
+ -0.3201, +0.1853, +0.3175, +0.0078, -0.4971, +0.7472, +0.1544,
+ -0.3018, +0.2934, -0.2034, +0.3348, +0.3705, -1.3035, +0.2084,
+ +0.4699, +0.0053, -0.3233, -0.8634, -0.4203, -0.6225, -0.2153,
+ +0.5059, +0.1571, -0.7581, -0.9790, +0.1196, -0.6516, +0.1740,
+ +0.3164, -0.0439, -0.7366, -0.0850, +0.4464, -0.9298, +0.3098,
+ +0.6134, +0.0513, -0.1314, -0.7751, -0.4632, +0.2998, -0.2841,
+ -0.1156, +0.2272, -0.6840, +0.2023, +0.2771, +0.0181, +0.3241, +0.0077
+ ],
+ [
+ -0.0280, -1.3387, -0.3547, -0.0743, +0.1483, -0.0627, -0.3067,
+ -0.3430, +0.0588, +0.0807, +0.4038, +0.4257, +0.4200, -0.1636,
+ -0.6085, +0.0772, +0.3777, -0.0100, -0.5085, -0.4027, +0.1783,
+ +0.3648, +0.2458, -0.6546, -0.3100, -0.0142, +0.5146, +0.5179,
+ +0.3174, -0.0085, -0.5655, +0.6930, -0.0170, -0.0840, -0.4820,
+ +0.3951, +0.2091, -0.1006, -0.1043, -0.1592, +0.5631, +0.0762,
+ +0.0353, +0.3549, -0.5710, +0.6521, -0.5372, +0.5439, -0.6006,
+ -0.3861, -0.9696, +0.3836, +0.0144, -0.0445, +0.2625, +0.0893,
+ +0.3533, -0.0816, +0.3946, -0.1645, -1.0470, +0.4605, +0.2646, -0.0709
+ ],
+ [
+ +0.1597, -0.1930, +0.1695, +0.0883, +0.3863, -0.0690, -0.3626,
+ -0.0751, -0.2489, -0.2651, +0.3078, -0.0279, +0.0915, -0.3568,
+ +0.0135, +0.0301, +0.1845, +0.0936, +0.1046, -1.0295, -0.4317,
+ +0.0053, +0.3181, +0.1241, +0.1828, -0.1518, +0.3664, -0.0194,
+ -0.0056, -0.9545, -0.3588, +0.5326, -0.9760, -0.2063, +0.4710,
+ -0.7108, -0.0157, -1.2469, -0.3011, -0.2258, -0.1896, +0.0305,
+ +0.1823, +0.2524, +0.0734, -0.0195, +0.2741, +0.0458, -0.0258,
+ -0.1458, -0.0499, +0.2720, +0.2632, -0.1566, -0.3169, +0.4742,
+ -0.1019, -0.1814, +0.3763, +0.2875, +0.4905, -0.4019, +0.2122, -0.9641
+ ],
+ [
+ +0.3189, +0.1388, -0.3550, -0.3842, +0.0898, +0.0547, -0.7110,
+ -0.1182, +0.0259, +0.0704, +0.1494, -0.1821, -0.1159, +0.0213,
+ +0.2096, -0.4418, -0.6512, +0.1241, +0.0305, -0.1008, +0.0562,
+ +0.0968, +0.0081, +0.1199, +0.1381, -0.2673, -0.2059, -0.0357,
+ +0.3140, +0.2211, -1.0964, +0.1492, +0.1469, -0.5406, -0.0557,
+ +0.3461, -0.0567, +0.2042, +0.1409, -0.1752, -0.5634, -0.7240,
+ -0.0985, +0.4507, -0.0405, +0.1548, -0.0590, +0.2785, +0.0398,
+ -0.0766, +0.3026, -0.3093, -0.0211, +0.3418, -0.0372, +0.1007,
+ -0.1287, -0.1216, +0.1111, +0.0391, -0.4399, -0.1719, -0.7748, +0.0015
+ ],
+ [
+ -0.8898, +0.1587, -0.1158, -0.2147, +0.1854, +0.0673, -1.6078,
+ +0.3145, +0.1855, +0.0176, -0.6532, +0.1946, -0.2744, -0.2392,
+ +0.0001, -0.5411, -0.3275, -0.6474, -0.3419, +0.0351, -0.2511,
+ +0.2090, -0.1401, -1.2570, -0.3467, -0.1794, -0.0238, -0.3511,
+ +0.0885, +0.2340, -0.2762, +0.2349, -0.0718, -0.1801, -0.5107,
+ +0.1164, +0.2997, -0.1047, +0.1091, +0.1830, -0.0604, -0.5492,
+ +0.0451, +0.5144, -0.1682, -0.2848, -0.3148, -0.0800, -0.6753,
+ +0.8912, -0.3167, +0.1553, -0.1064, +0.4668, -0.1185, +0.0205,
+ +0.2634, -1.4268, -1.4053, +0.1865, -1.1680, -0.5715, -0.1411, -0.0048
+ ],
+ [
+ -1.1451, -0.8007, -0.7188, +0.2194, +0.0224, -0.3902, -1.0708,
+ +0.1315, -0.4508, -0.0171, -0.1646, -0.8523, +0.0246, -0.2483,
+ +0.2628, -0.0709, +0.1284, -0.0332, +0.2452, +0.6453, +0.0372,
+ +0.0580, -0.4814, -0.0367, -0.6464, -0.1864, -0.0876, -0.3798,
+ -0.1084, -0.2326, +0.3449, -1.0821, +0.3558, -0.2093, -0.1611,
+ +0.0181, -0.1593, -0.7092, -0.5308, +0.3392, -0.2771, -0.8510,
+ -0.0332, +0.1636, -0.1288, -0.1509, -0.0123, -0.3427, -0.2880,
+ -0.9719, -1.0379, -0.2061, -1.2064, +0.0703, +0.0296, -0.5942,
+ +0.1367, +0.2798, -0.9892, +0.2638, +0.6593, +0.3467, +0.2717, -0.2685
+ ],
+ [
+ -0.2935, -0.2457, -0.1847, -0.1120, +0.2738, -0.1316, -0.1218,
+ +0.1977, +0.2899, -0.2914, -0.9864, +0.4904, -0.1894, -0.0953,
+ +0.0076, -0.0067, -0.6684, -0.0314, +0.0872, +0.4462, +0.2811,
+ -0.1232, -0.3337, -0.7796, -0.7328, +0.0966, -0.1373, +0.4435,
+ +0.1715, +0.1189, -0.3743, +0.3548, -0.0802, -0.5682, -1.3086,
+ -0.0364, -0.2844, -0.3369, +0.3544, -0.0662, -0.1867, -0.3540,
+ -0.2038, -0.4980, +0.3799, -0.1018, -0.9164, +0.3697, -0.0067,
+ -0.5775, -0.1818, +0.0175, -0.1748, +0.4688, -0.5308, -0.4231,
+ +0.1482, -0.5617, -1.2285, +0.3348, +0.2546, +0.3433, -0.0552, -0.4434
+ ],
+ [
+ -0.5986, -0.0456, -0.0579, +0.0098, +0.5195, +0.2289, -0.0547,
+ +0.0712, +0.3579, +0.0200, -0.3965, +0.3115, -0.3113, -0.2659,
+ +0.2821, -0.0527, -0.1284, -0.5430, -0.6974, +0.0659, -0.4766,
+ -0.1915, -0.1467, -1.0685, -0.5390, +0.4510, +0.3700, +0.1105,
+ -0.1987, -0.0297, +0.0635, +0.2345, +0.1594, -0.0839, -0.1305,
+ -0.1000, +0.2680, +0.1591, -0.5661, +0.1602, -0.0069, -0.1623,
+ -1.4309, -0.1520, -0.0090, -0.3502, -0.6969, -0.0949, +0.0562,
+ -0.0869, -0.2017, +0.0475, +0.5724, +0.1771, -0.0398, -0.7070,
+ -0.1830, -0.0220, -0.1941, -0.9674, +0.0262, -0.1637, -0.0094, +0.4634
+ ],
+ [
+ -0.0007, -0.1887, +0.2479, +0.0483, +0.2260, -0.1202, -0.2455,
+ -0.5935, -0.0951, +0.2204, +0.2221, +0.3503, +0.0909, -0.2512,
+ +0.0191, -1.0021, -0.2003, +0.6241, +0.2894, -0.0605, -0.4665,
+ -0.2199, -0.1427, -1.2488, -0.1763, +0.3383, +0.4418, +0.2648,
+ -0.9742, +0.2356, +0.1240, +0.1305, -0.4167, +0.0351, +0.3759,
+ -0.2039, +0.0351, -0.6693, -0.8583, +0.0616, +0.2169, -0.4452,
+ -0.4786, -0.0808, +0.0579, -0.1770, +0.1975, -0.3272, -0.0747,
+ -0.3015, -0.0030, -0.3779, -0.1084, +0.0285, +0.2040, +0.0064,
+ -0.6207, +0.1540, +0.2691, -0.4465, +0.3775, -0.7416, +0.0563, -0.0898
+ ],
+ [
+ +0.1254, +0.4967, +0.1999, -0.2316, +0.2500, -0.0650, +0.5256,
+ -0.4156, -0.2651, +0.1705, +0.0690, -0.0314, -0.6562, +0.0699,
+ -0.8152, +0.1149, +0.0980, +0.6136, +0.2356, -0.4453, +0.3604,
+ +0.4151, +0.1505, -0.3277, -0.2119, +0.0359, -0.1290, -0.1692,
+ -0.0831, -0.0644, -0.1416, -0.0558, +0.0298, -0.0870, -0.1409,
+ -0.5095, -0.3006, -0.0250, +0.4266, -0.3381, -0.3222, +0.3626,
+ -0.0441, +0.2182, -0.1688, +0.0500, +0.2828, -0.2694, -0.0921,
+ +0.1291, -0.7688, +0.2200, +0.1006, -0.3204, -0.1588, -0.5138,
+ -0.6525, -0.3203, +0.5614, +0.1583, -0.3336, -0.6822, -0.0527, -0.0729
+ ],
+ [
+ +0.2401, -1.5531, -1.1594, +0.0219, -0.1680, -0.0307, -0.1397,
+ -0.4195, +0.2302, +0.2705, +0.0780, -0.3434, +0.2748, -0.1826,
+ -0.4300, -1.2819, -2.0983, +0.2545, +0.3414, +0.1059, +0.1937,
+ +0.0885, +0.3678, +0.0745, -0.2122, -0.2374, +0.2199, +0.1136,
+ +0.0291, -1.5077, -0.6176, +0.0825, +0.0813, -0.2417, -0.3546,
+ +0.2231, +0.3004, +0.0066, -0.0259, +0.5017, -0.6783, -0.5061,
+ +0.0575, -0.1790, -0.4460, -0.6383, -0.1353, -0.1327, +0.0067,
+ +0.2322, -0.0208, +0.2877, +0.1562, -0.5431, +0.0227, -0.1356,
+ +0.0365, -0.2004, -0.1343, +0.1730, -0.5527, +0.1656, +0.1991, -0.8294
+ ],
+ [
+ +0.4524, +0.7614, -0.1415, -0.0766, +0.1568, +0.0408, +0.0539,
+ -0.2856, +0.1050, -0.1615, -0.8484, +0.5459, +0.1695, +0.2730,
+ -0.0014, +0.6478, +0.1634, -0.0715, -0.0612, -0.1463, -0.1214,
+ -0.1158, +0.1563, +0.2598, +0.0758, -0.4645, -0.2913, -0.3810,
+ -0.7767, -0.3182, +0.1396, +0.1954, -0.0150, -0.1029, -0.2936,
+ -0.5085, -0.0514, +0.1485, -0.1216, -0.1714, -0.1193, +0.4209,
+ +0.0558, -0.4255, +0.2840, -0.5583, -0.3015, -0.2423, +0.0089,
+ -0.4503, +0.3085, +0.2502, +0.2749, +0.2995, -0.7768, -0.3364,
+ -0.5740, +0.0843, -0.2877, -0.5731, -0.3221, -0.2253, -0.3227, -0.0065
+ ],
+ [
+ +0.0540, -0.0224, -0.3116, -0.5707, -0.0632, -1.4873, +0.2964,
+ -0.4894, -0.2578, +0.2032, +0.0937, -0.4259, -0.0588, +0.4007,
+ +0.1099, -0.2633, -0.3422, +0.1973, -0.0170, +0.0451, +0.1670,
+ +0.4853, +0.2068, +0.2066, -0.1544, +0.0191, -0.0957, -0.9554,
+ -0.6965, -0.6022, +0.1666, +0.0026, +0.5176, -0.0584, -0.9679,
+ -0.2898, +0.2451, +0.2050, -0.2909, +0.0002, -0.0763, -0.2100,
+ -0.1929, +0.0985, -0.2612, -0.3684, +0.3190, -0.5681, +0.2765,
+ -0.1663, +0.0422, +0.3252, +0.2741, -0.2385, -0.1602, +0.2504,
+ -0.2370, +0.0891, -0.2204, +0.1525, +0.0444, +0.0188, +0.3538, -0.0313
+ ],
+ [
+ +0.0984, +0.2622, +0.1601, -0.3252, -0.2292, -0.0494, +0.2185,
+ +0.2202, +0.4945, -0.3545, -0.1730, -0.6882, -0.6645, -0.1178,
+ -0.2491, +0.2497, -0.1072, -0.2019, -0.0944, +0.2118, -0.2281,
+ +0.2338, +0.0924, +0.1178, +0.0920, +0.0422, +0.3113, -1.1795,
+ -0.8658, -0.6011, +0.0714, +0.0290, -0.5830, +0.2370, +0.3508,
+ -0.0178, -0.6966, +0.2269, -0.2966, -0.6947, +0.1769, +0.1461,
+ -1.0021, +0.0781, -0.3731, -0.0153, -0.2721, +0.0699, -0.2057,
+ +0.0791, -0.2055, -0.4152, +0.2414, +0.0939, -0.4560, -0.3566,
+ -0.0381, +0.1090, -0.5755, -0.4283, +0.2504, +0.0863, -0.6288, -0.9822
+ ],
+ [
+ -0.0122, -1.0238, +0.0346, -0.2412, -0.7928, -0.3765, -0.2889,
+ -0.0948, +0.1003, +0.7268, +0.2033, -0.6144, +0.4689, +0.2045,
+ +0.0799, +0.2687, -0.3528, +0.0560, +0.0682, +0.0874, -0.1901,
+ -0.0082, +0.3474, -1.0391, -0.4695, -0.0233, -0.0259, -0.0901,
+ -0.1084, -1.4681, +0.0081, -0.3583, -0.2599, -0.1273, -0.6221,
+ +0.2186, -0.1878, +0.4510, +0.0409, -0.1692, +0.1495, -0.3093,
+ -0.0192, -0.1835, -0.5964, +0.0327, -0.5086, +0.2446, -0.5980,
+ +0.1981, +0.0441, -0.1232, -0.4881, -0.6698, -0.0519, -0.0831,
+ -0.6186, -0.6176, +0.0503, +0.2250, +0.0662, -0.8334, -0.0077, -0.7196
+ ],
+ [
+ -0.2566, -0.7118, +0.2935, -0.1195, -0.1146, -0.0123, +0.1455,
+ +0.1784, -0.2927, +0.3859, +0.2592, -0.0991, -0.6787, -0.2469,
+ +0.1925, +0.0359, +0.2956, +0.2008, +0.0844, -0.3478, -0.2671,
+ -0.0078, +0.3483, -0.0814, +0.5766, +0.2134, +0.0878, +0.3362,
+ -0.1537, +0.3245, +0.2214, -0.2824, +0.1635, -0.5485, -0.1898,
+ -0.1885, -0.0076, -0.2640, -0.2163, +0.4214, -0.2781, +0.1793,
+ -0.1132, -0.3325, -0.3830, +0.1018, +0.0151, -0.7901, +0.1946,
+ +0.3539, -0.4104, -0.1557, +0.3991, -0.0178, +0.1242, +0.4661,
+ -0.0344, -0.4815, +0.1843, +0.6808, -0.0437, -0.3225, +0.2147, -0.4555
+ ],
+ [
+ -0.0638, -0.3322, -0.2387, +0.2534, -0.5326, -0.8410, -0.2301,
+ -0.8189, -1.0886, +0.2326, -0.6260, -0.4507, -0.1068, -0.7282,
+ +0.5187, +0.1134, +0.2561, +0.1038, +0.3431, -1.1889, +0.6843,
+ -0.7160, -0.6177, -0.2679, -0.0451, +0.0572, +0.0807, +0.6884,
+ +0.5089, +0.5436, +0.3386, -0.4832, +0.4377, +0.4794, -0.4475,
+ -0.6358, -0.0388, +0.3861, +0.1041, +0.0640, -0.0701, +0.0340,
+ +0.1640, -0.4543, -0.4830, -0.4003, -0.2349, +0.1010, -0.9351,
+ -0.2592, -0.2928, -0.1271, -1.0826, -0.1847, +0.1704, -0.4475,
+ -0.2948, +0.2068, -0.5627, -0.0093, +0.0881, -0.2164, -0.0049, +0.1603
+ ],
+ [
+ +0.1574, -0.0650, -0.2662, +0.1164, +0.4237, -0.6874, +0.4308,
+ +0.4112, -0.0215, -0.0763, +0.2667, -0.3433, -0.4008, +0.2368,
+ +0.1596, -0.1390, -0.4850, -0.0810, +0.1081, -0.1730, -0.8641,
+ -0.3173, -0.2085, +0.1296, +0.2189, -0.4631, -0.3093, +0.0174,
+ -0.0811, -0.4710, +0.0884, -0.5081, -0.2918, -0.0430, -0.1509,
+ +0.4783, -0.1912, -0.7071, -0.3763, +0.0781, +0.1794, -0.3923,
+ -0.9474, +0.3877, -0.2204, -0.2234, -0.0250, -0.3792, -0.6236,
+ +0.1750, -1.4279, -0.4849, -0.6417, +0.1128, -0.2395, -0.1343,
+ -0.5671, -0.1158, -0.1158, -0.3690, -0.1078, -0.2042, -0.3332, -0.2509
+ ],
+ [
+ +0.0333, -0.2800, -0.1392, +0.0001, +0.0705, -0.1369, -0.1756,
+ +0.1453, +0.3505, +0.3330, -0.1388, -0.7255, -0.4376, -0.0105,
+ +0.0049, -0.8412, -0.3385, -0.1028, -0.3672, -0.8725, -0.3093,
+ -0.0453, +0.0416, -0.1510, +0.3841, -0.2103, +0.0864, +0.1017,
+ -0.3006, -0.0184, +0.4379, +0.4946, +0.1351, +0.2742, -0.1733,
+ +0.1185, +0.0766, -0.7874, +0.3184, -0.5364, +0.1065, +0.1258,
+ -0.2782, +0.2434, +0.3819, -0.2390, +0.2471, +0.1067, +0.1810,
+ +0.0401, -0.4542, +0.1356, +0.1049, -0.1339, -0.1564, -0.0183,
+ +0.1957, -0.1304, -0.0602, -1.1445, -0.1470, -0.0536, -0.0504, +0.3606
+ ],
+ [
+ -0.4758, +0.1761, -0.4846, -1.0187, -0.1317, +0.4057, -0.7446,
+ -0.0029, -0.1074, +0.3271, +0.2986, -0.2398, -0.1716, +0.0999,
+ -0.3667, -0.3235, +0.0859, -0.2204, -0.0886, -0.3845, -0.1990,
+ -0.4520, -0.0453, +0.0367, +0.4391, -0.5058, -0.5205, +0.0438,
+ +0.0949, -0.2365, +0.0034, -0.0972, +0.2460, -0.3402, +0.2640,
+ +0.1962, +1.0076, -0.0240, -0.0881, +0.3680, +0.1796, -0.1007,
+ -0.7938, +0.1620, -0.2244, +0.1086, +0.0835, -0.6081, -0.0907,
+ -0.2010, +0.1411, -0.1199, +0.1650, +0.0291, -0.1783, -0.2652,
+ -0.1174, -0.4219, -0.2506, +0.0413, +0.0460, -0.6699, -1.2885, +0.1545
+ ],
+ [
+ +0.1129, -0.1235, -0.0860, -0.3039, +0.0470, +0.1649, -0.6282,
+ -0.0529, -0.0862, +0.2638, -0.0880, -0.9592, +0.3736, -0.1045,
+ +0.3156, -0.3239, -0.0977, +0.1138, +0.1028, +0.0075, -0.4383,
+ +0.0055, +0.1644, -0.5601, +0.0328, +0.2353, -0.1457, +0.0268,
+ -0.1316, +0.1369, +0.1295, -0.0454, -0.0704, -0.6862, -0.1434,
+ +0.1058, -0.0882, -0.2573, -0.1518, -0.0106, -0.1371, +0.3189,
+ +0.4066, -0.2663, -0.5477, +0.3918, +0.0601, -1.2816, +0.0213,
+ -1.0473, +0.2741, -0.0658, -0.3203, +0.0561, +0.2982, -0.0264,
+ +0.3706, +0.3083, +0.4189, -0.3125, +0.2324, -0.0699, -0.0653, +0.3647
+ ],
+ [
+ -0.0693, +0.4631, +0.0902, +0.3558, -0.1712, +0.1079, -0.0386,
+ +0.1094, -0.3096, -0.2886, -0.2315, -0.2787, -0.5874, -0.6247,
+ +0.5268, -0.1084, +0.7058, +0.1418, -0.5504, +0.0670, -0.0498,
+ +0.1770, -0.1857, -0.0256, +0.0751, +0.1447, +0.1853, -0.1040,
+ +0.0456, -0.5765, +0.0473, +0.1485, +0.3068, -0.2301, -0.2385,
+ +0.2792, -0.8568, -0.5057, -0.0070, +0.0129, +0.4641, -0.2125,
+ -0.6467, +0.0405, +0.0443, +0.0706, -1.0480, -0.2147, +0.1343,
+ +0.1673, +0.0443, +0.1780, -0.3776, +0.3203, -1.0370, -0.5205,
+ -0.0960, +0.4009, +0.2349, +0.1341, +0.0472, -0.1244, -0.1439, +0.0556
+ ],
+ [
+ +0.1598, -1.2782, +0.6361, -0.5370, -0.1456, -0.8548, -1.0428,
+ -0.8559, -0.2116, -0.3637, -0.4516, -0.0612, +0.0129, +0.0675,
+ -0.5432, +0.1841, -0.3792, +0.2158, +0.0596, -0.6030, +0.8449,
+ +0.4651, -0.2557, -1.2864, -0.2594, -0.0408, -0.4892, +0.3451,
+ +0.3054, +0.3925, -0.1913, -0.4430, -0.0513, +0.2399, -0.3757,
+ +0.4300, -0.5091, +0.3864, -0.5291, -0.4042, +0.1954, +0.5566,
+ +0.5156, +0.3129, -0.0074, -0.5308, -0.0965, +0.4685, -0.6602,
+ -0.5140, -0.0500, -0.0512, -0.0719, -0.2983, -0.0757, -1.4385,
+ -0.3450, -0.5004, -0.8424, +0.3685, -0.4302, -0.3252, +0.2352, -0.2397
+ ],
+ [
+ +0.2517, -0.0510, -0.8445, -0.0101, -0.2960, +0.3604, -0.0354,
+ -0.2369, +0.4843, -0.2510, -0.0606, -0.0558, +0.1601, +0.1233,
+ -0.0533, -0.6993, -0.1938, -0.0681, +0.1999, +0.1705, -0.3202,
+ -0.0766, +0.2753, -0.4941, +0.2154, +0.1077, +0.2094, -0.0723,
+ -0.1037, -0.0066, +0.0075, -0.0346, +0.2195, +0.1334, -0.1074,
+ +0.0879, -0.2654, +0.2319, -0.1298, -0.3219, +0.3351, -0.6852,
+ -0.5198, -0.2214, -0.0373, +0.2662, -0.2757, +0.0667, +0.1171,
+ +0.1987, +0.4252, -0.5109, -0.5771, -0.2238, -0.0016, -0.1032,
+ +0.2942, -0.4498, -0.1209, +0.0526, +0.0681, -0.0631, -0.2249, -0.5044
+ ],
+ [
+ +0.1015, -0.1221, -0.0457, -0.1632, +0.1805, -0.4646, +0.1515,
+ +0.3582, +0.0226, -0.1206, -1.2033, -0.5519, -0.7632, +0.1745,
+ +0.2149, -0.3880, +0.8417, +0.0764, +0.3466, -0.0296, -0.1456,
+ +0.0030, -0.4206, -0.6899, +0.1030, -0.4873, -0.1851, +0.2350,
+ -0.5323, -0.7947, -0.1631, -0.0664, -0.7279, +0.2869, -0.1196,
+ +0.3290, -0.3650, -0.2667, +0.0680, +0.0420, +0.0880, +0.0988,
+ -0.7243, +0.2308, +0.6681, -0.4614, -0.2574, +0.1210, +0.1116,
+ -0.0749, -0.8760, -0.2902, -0.0932, -0.0302, -0.4676, -0.0909,
+ -0.0998, -0.1058, -0.1159, -0.0889, +0.1690, +0.0106, -0.1399, -0.6091
+ ],
+ [
+ -0.3936, -0.2924, -0.0566, +0.0908, +0.1229, -0.4908, +0.2100,
+ +0.3042, -0.1919, -0.2383, -0.1356, -0.2715, +0.5147, -0.0937,
+ -0.2436, +0.2805, -0.4522, +0.1256, +0.0199, -0.2870, -0.1586,
+ -0.1113, -0.4221, +0.5571, +0.4612, +0.0522, +0.0469, +0.1000,
+ -0.3156, -0.2255, +0.0661, -0.8530, -0.1866, -0.0146, -0.2175,
+ -0.5078, -0.2589, -0.0452, -0.0606, -0.1495, -0.0759, -0.0676,
+ -0.4239, +0.1552, -0.3918, +0.2913, -0.1573, -0.1386, +0.4216,
+ +0.3134, -0.2761, -0.0822, +0.4101, -0.4691, -0.3533, -0.4907,
+ -0.6454, -0.6846, -0.5219, +0.2845, +0.0990, +0.5448, +0.0043, -0.1068
+ ],
+ [
+ +0.2038, +0.3592, -0.0381, -0.3525, -0.4154, -0.0967, +0.1296,
+ +0.0537, -0.0668, +0.1384, -0.3061, -0.3796, -0.0676, +0.2463,
+ +0.0337, +0.2712, +0.2327, +0.2747, -0.0390, -0.4290, -0.1667,
+ -0.2714, +0.0036, -0.2474, -0.0108, -0.5544, -0.3588, -1.0251,
+ -0.1637, -0.6376, +0.1074, -0.2695, -0.2931, +0.2847, -0.3638,
+ +0.2679, +0.3571, +0.3164, +0.0257, -0.1720, +0.0306, -0.0424,
+ -1.3316, -0.2671, +0.1664, -0.6751, -1.3701, -0.1609, -0.5226,
+ +0.2046, -0.2826, +0.0329, -0.1094, +0.0457, +0.2797, -0.3022,
+ -0.2398, -0.1309, +0.1237, -0.6917, -0.1042, -0.5504, +0.0599, -0.0993
+ ],
+ [
+ +0.2578, +0.2448, -0.3515, +0.2550, -0.4556, -0.1521, -0.0937,
+ +0.1082, +0.0064, -0.1935, -0.0986, -0.4707, -0.8805, +0.0902,
+ -0.2753, -0.1709, -0.0610, -0.5028, -0.2642, -0.5600, +0.0068,
+ +0.3170, +0.3340, -0.3805, +0.2661, -0.6105, -0.0338, -0.3294,
+ -0.5872, -1.0930, -0.0021, +0.0525, -0.4677, +0.2302, +0.2422,
+ +0.0805, -0.8454, -0.1925, +0.3445, -0.0826, +0.1550, -0.1808,
+ -0.9067, +0.1723, +0.0365, -0.2956, -0.0784, +0.2945, +0.0641,
+ +0.0239, -0.0561, +0.0630, -0.1646, +0.0403, -0.9467, -0.6385,
+ +0.1264, -0.2964, -0.1579, +0.2373, -0.0417, +0.1332, +0.4347, -0.2901
+ ],
+ [
+ -0.1863, -0.0242, -1.3175, -0.0210, +0.7122, -0.0967, +0.2298,
+ -0.2379, +0.0625, -1.0683, -0.5156, -0.2993, +0.3003, +0.2490,
+ -0.2035, +0.1202, -0.0714, -0.2515, +0.1050, -0.0244, -0.0323,
+ -0.0142, -0.3243, -1.0355, -0.1945, -0.6769, -0.1482, -0.6095,
+ -1.2543, -0.1212, +0.2109, +0.1281, -0.5586, -0.1869, -0.0505,
+ +0.3053, -1.4947, -0.4599, +0.3102, -0.0713, +0.0294, -0.3146,
+ +0.3229, +0.0378, +0.5098, +0.3752, -1.1693, +0.2510, +0.5305,
+ +0.0346, +0.4966, +0.1118, -0.1061, -0.2008, -0.8236, -0.3700,
+ +0.0883, -0.3168, -0.6185, +0.7089, -0.7464, +0.0953, +0.5762, -0.1075
+ ],
+ [
+ -0.0649, +0.0128, -0.1768, -0.6602, -0.1332, +0.2819, +0.2196,
+ -0.5156, +0.3175, +0.1690, +0.2806, -0.4787, -0.6439, +0.2791,
+ -0.2997, +0.1521, -0.1161, -0.0450, +0.3153, +0.2059, -0.0687,
+ +0.1672, +0.1408, +0.1332, -0.0993, +0.3110, +0.0697, +0.1563,
+ +0.1029, -0.9687, -0.0195, +0.2097, -0.1263, +0.0773, +0.0347,
+ +0.1860, -0.0304, -0.2414, -0.8054, +0.1562, +0.2249, -0.9248,
+ -0.8415, +0.3590, -0.1355, +0.3704, -0.4522, -0.3624, -0.7113,
+ +0.2271, -1.0906, -0.5597, +0.2343, -0.3852, -1.1641, -0.2844,
+ +0.3131, +0.0553, +0.1024, -1.8251, -0.7928, +0.1100, -0.1679, -0.9488
+ ],
+ [
+ -0.2144, -0.1724, -0.3429, +0.4875, +0.1602, +0.3609, +0.2947,
+ -0.0800, -0.1385, +0.1008, +0.0328, -0.4782, -0.0638, +0.1748,
+ +0.1134, -1.1389, -0.3115, -0.5365, -0.6607, -0.4707, -0.7305,
+ +0.1676, -0.0230, +0.2286, -0.6695, +0.0748, +0.1772, -0.2285,
+ -0.4459, +0.1489, -0.3056, -0.2268, -0.1158, +0.2677, -0.5665,
+ +0.2966, -0.1029, +0.0172, +0.5579, +0.2357, -0.2072, -0.3823,
+ -0.7458, +0.2185, -0.7836, -0.2562, -0.5589, -0.0523, -0.5152,
+ +0.1166, +0.2566, -0.4698, +0.1755, +0.2976, -0.2948, -0.0285,
+ -1.5112, +0.1225, -0.0690, -0.0911, +0.1124, -0.3546, +0.0632, +0.4610
+ ],
+ [
+ -0.1956, +0.0370, -0.0308, -0.1817, +0.1882, -0.1052, -0.0503,
+ +0.3709, -0.2240, -0.0828, -0.8304, +0.0044, +0.0459, +0.0761,
+ +0.0206, +0.1419, +0.4986, -0.0567, -0.3287, -0.7981, -0.2592,
+ -0.7543, -0.4157, -0.0182, -0.0886, -0.7827, +0.0057, -0.0465,
+ -0.3869, -1.4567, +0.2595, +0.0849, -0.8865, +0.0156, -0.1862,
+ +0.2267, +0.4277, +0.2811, -0.8963, -0.2927, +0.1019, -0.1663,
+ -0.8428, -0.2191, +0.4336, -0.9808, -0.8575, +0.1630, +0.0028,
+ -0.4473, +0.5544, -0.2155, +0.0422, +0.1349, -0.3771, -0.0671,
+ -0.0194, +0.2140, -0.3160, -0.5825, +0.3150, -0.0496, -0.0514, -0.2068
+ ],
+ [
+ +0.2710, +0.2079, -0.7397, -0.5588, -0.3865, -0.3099, +0.3502,
+ -0.0669, -0.0064, +0.1037, -0.8617, -0.3000, -0.2977, +0.2392,
+ -1.4580, +0.3477, +0.0329, -0.5653, -0.6458, -0.2955, +0.1288,
+ +0.1199, -0.5390, +0.1431, +0.1088, -0.5537, -0.0880, -0.3841,
+ +0.0801, -1.8213, -0.5604, -0.9688, +0.3403, +0.7033, +0.7676,
+ -0.0232, +0.1272, -0.0812, +0.0785, -0.0681, +0.3825, -0.1818,
+ +0.0268, +0.0546, +0.0451, -0.4763, -0.0513, -0.3287, +0.5841,
+ -0.1963, +0.1147, +0.1113, -0.5448, -0.3498, -0.0750, -0.0585,
+ -0.5094, +0.0116, +0.6219, -0.1440, -0.0742, -0.1261, +0.0572, +0.4366
+ ],
+ [
+ +0.0369, -0.3345, -0.0768, +0.4205, -0.1390, -0.2384, -0.1629,
+ +0.0786, +0.6107, -0.2725, +0.0444, +0.2727, +0.3295, +0.3000,
+ -0.4049, +0.1150, -0.7289, -0.5964, +0.1346, +0.0574, -0.1202,
+ -0.2461, -0.1504, -0.1282, +0.5685, -0.3631, +0.4576, +0.6880,
+ +0.2554, -0.1782, -0.2704, -0.5299, +0.0232, -0.4567, -0.1116,
+ -0.2672, +0.4286, -0.0448, +0.2230, +0.0236, -0.0343, -0.0985,
+ +0.8088, +0.2633, -0.7682, -0.0642, +0.0384, +0.0750, +0.0595,
+ +0.1717, +0.5152, +0.2972, +0.0325, +0.0450, +0.2534, -0.1186,
+ +0.1540, -0.0107, -1.5430, -0.1050, +0.4161, +0.0592, +0.0044, +0.0843
+ ],
+ [
+ +0.1402, +0.1111, +0.4706, +0.3944, -0.1486, +0.1623, -0.1863,
+ +0.0468, -0.4898, -0.0224, +0.2583, +0.1336, -0.1123, +0.0581,
+ -0.0853, -0.0288, +0.0372, -0.1358, -0.0016, -0.5055, -0.2581,
+ -0.3232, +0.0418, -0.5329, +0.0167, -0.1626, +0.0284, -0.8795,
+ +0.1812, +0.1044, +0.3439, -0.3482, -0.1301, +0.1099, -0.3284,
+ -0.3683, -0.0479, -0.2303, -0.2175, +0.2400, +0.4435, +0.0818,
+ +0.3271, -0.0304, -0.4587, -0.3401, +0.1851, +0.1210, +0.0699,
+ +0.2149, +0.3445, -0.3352, -1.0872, +0.1455, +0.2182, -0.7787,
+ -0.4760, +0.0306, -0.2152, +0.1286, +0.1384, -0.0821, +0.1290, -0.0055
+ ],
+ [
+ -0.3143, -0.1360, -0.4878, +0.1358, +0.5162, -0.0948, -0.1355,
+ +0.0911, +0.3592, +0.3475, -0.5666, -0.1593, +0.1584, +0.3172,
+ -0.0814, -0.1594, +0.1179, -0.6127, -0.3628, +0.1970, -0.6501,
+ +0.1911, +0.4294, -0.2048, +0.3984, -0.0478, +0.1101, -0.5869,
+ +0.4901, +0.2732, +0.1232, +0.4142, -0.1033, -0.7990, -0.2998,
+ -0.2509, +0.2344, -0.2567, -0.0217, -0.0533, +0.0065, +0.2979,
+ +0.1800, -0.0104, +0.1369, -0.0922, +0.0936, -0.7170, -0.0760,
+ +0.8108, -0.5491, +0.6483, -0.2240, +0.3839, +0.1498, -0.3039,
+ -0.1461, +0.6054, -0.2897, -0.0078, -0.5547, -0.2711, +0.0759, +0.3237
+ ],
+ [
+ +0.5616, +0.6020, +0.1514, -0.0995, -0.2372, +0.0439, +0.1131,
+ -0.4839, -0.0951, +0.0364, -0.5441, +0.4846, -1.2297, +0.0283,
+ +0.0222, -0.0880, -0.2479, -0.9553, -0.3495, -0.2920, +0.1952,
+ +0.1342, -0.0358, +0.0231, +0.2965, +0.1285, -0.6684, -0.1393,
+ +0.0285, -0.2817, +0.4368, +0.2012, -0.2838, +0.4132, +0.1914,
+ +0.0013, -1.7082, -0.0351, -0.4860, +0.7094, -0.2159, -0.1761,
+ -1.0276, -0.1694, -0.3221, +0.0570, -0.4394, -0.2167, +0.4231,
+ -0.1657, +0.6024, -0.2707, -0.8380, -0.3110, -0.2727, -0.0000,
+ +0.0231, -0.1633, -0.1836, -0.2276, -0.4032, +0.1383, -0.1814, +0.0089
+ ],
+ [
+ -0.5613, +0.4738, -0.0094, +0.1051, -0.1535, +0.4020, +0.1245,
+ -0.2956, -0.3178, +0.2353, -0.1440, -0.4745, +0.5712, -0.6119,
+ -0.2502, +0.1111, -0.2901, +0.1149, -0.2184, +0.0947, -0.2306,
+ +0.0607, +0.5822, +0.1520, +0.3781, +0.1310, -0.1419, -0.3509,
+ -0.0049, -0.1097, -0.0186, +0.1534, +0.0022, -0.0835, +0.1862,
+ -0.2482, -0.1495, +0.1222, +0.4941, +0.1029, -0.7218, -0.3025,
+ +0.1426, +0.5004, -0.0558, +0.2425, +0.0040, +0.1861, +0.2947,
+ +0.1472, -0.1007, +0.4316, +0.2087, +0.1794, -0.3261, +0.3879,
+ +0.3172, -0.1491, -0.2332, -0.1210, +0.1350, -0.6219, -0.1570, -0.3347
+ ],
+ [
+ -0.3358, -0.0382, -0.7346, +0.4532, +0.1010, +0.1139, +0.2213,
+ -0.1050, -0.0101, +0.3208, -0.0250, -0.7625, -0.2357, -0.4067,
+ +0.3186, -0.9441, -0.0734, +0.0728, +0.0527, -0.0968, -0.0641,
+ +0.2877, -0.0233, +0.0247, -0.1409, +0.1281, +0.0714, -0.0970,
+ -0.4026, -0.3684, +0.3176, -0.1875, +0.5452, +0.0015, -0.0651,
+ +0.1397, +0.1550, -0.2029, +0.1350, +0.5028, -0.4886, +0.0630,
+ +0.1046, +0.5003, -0.5631, -0.1724, +0.2490, -0.0635, +0.2186,
+ -0.6167, +0.2855, -0.0579, -0.3821, +0.0562, +0.3526, +0.1313,
+ -0.1232, +0.5154, +0.2603, -0.0256, -0.0428, -0.4523, +0.1544, +0.4509
+ ],
+ [
+ +0.4364, +0.1492, -0.8081, -0.7765, +0.6166, -0.1982, -1.1432,
+ +0.1429, -0.2398, +0.5563, +0.6239, -0.5039, +0.5798, +0.2796,
+ -0.1920, +1.1087, -1.2430, +0.3100, -0.1673, -0.2110, -0.1677,
+ -0.2675, -0.6310, +0.4756, -0.9587, +0.2184, -0.4932, +0.1294,
+ +0.3719, -0.4294, -0.5482, -0.0035, -0.8373, -0.8548, -0.3245,
+ -0.0418, -0.0565, +0.1039, +0.0908, -0.7536, -0.2366, +0.3019,
+ +0.2688, -0.5386, +0.1596, -0.1945, +0.6900, -0.8411, -0.2744,
+ -1.1320, +0.0096, +0.0270, +0.4991, -0.1475, -0.0282, -0.0996,
+ -0.1922, +0.1317, +0.0331, -0.1740, +0.0127, -0.5657, -0.0071, +0.3783
+ ],
+ [
+ -0.9835, -0.0852, +0.0673, +0.3608, -0.5972, -0.6473, +0.2292,
+ -0.8121, -0.2935, +0.3361, +0.1431, -0.9612, -0.4476, -0.3111,
+ -1.0042, -0.3003, +0.0550, -0.4980, -0.1894, -0.2824, +0.2057,
+ +0.4801, +0.2026, -0.0641, -0.5990, +0.2153, +0.1995, +0.2198,
+ -0.3514, -0.0224, -0.1561, -0.9427, +0.5208, +0.2935, +0.3871,
+ -0.1506, -0.0125, +0.6396, -0.0254, +0.4302, -0.3523, +0.0043,
+ -0.0100, +0.3120, -0.1009, -0.9246, +0.0267, -0.1770, -1.4509,
+ +0.0446, -0.3987, -0.0527, -0.3977, -0.8643, +0.0371, -0.2630,
+ -0.0853, +0.1048, +0.0452, -0.5723, -0.0805, -0.0452, -0.0489, +0.3637
+ ],
+ [
+ -0.1134, +0.1550, -0.0273, -0.5159, -0.1409, -0.0753, +0.3230,
+ -0.4589, +0.2979, +0.1357, +0.1507, -0.9132, -0.9848, -0.0549,
+ -0.1922, +0.1292, -0.2662, -0.0223, +0.1236, -0.1861, +0.1619,
+ +0.3042, +0.2029, -0.1568, +0.1171, +0.2165, +0.3397, +0.4358,
+ -0.0830, -1.0290, +0.2147, +0.1445, -0.0959, +0.4696, +0.1496,
+ +0.2696, -1.2499, +0.0610, -0.7221, -0.5853, +0.1479, -0.7158,
+ -0.9965, +0.4685, +0.1279, +0.2654, -0.2122, -0.2593, -0.0377,
+ +0.1686, +0.2055, -0.4425, -0.3739, -0.5889, -0.2026, +0.0867,
+ +0.1399, -0.2259, -0.1120, -0.7030, -0.2465, +0.1833, -0.4158, +0.2191
+ ],
+ [
+ -0.3483, +0.1839, +0.0828, -1.1050, -0.1233, +0.1977, +0.1525,
+ +0.4061, +0.5995, +0.0719, +0.2548, -0.7088, +0.0960, +0.8649,
+ -0.4205, +0.0785, -1.6571, +0.3270, +0.1325, -0.3489, -0.1474,
+ +0.4878, +0.6677, +0.1169, +0.0927, -0.7217, +0.2176, +0.4076,
+ +0.2830, +0.1905, +0.2715, +0.0414, +0.0528, +0.2191, -0.0137,
+ -0.6578, +0.0925, -0.0096, -0.0277, +0.3254, -0.1541, -0.1264,
+ +0.3611, +0.4325, -0.5513, +0.5342, +0.5277, +0.0938, +0.1011,
+ -0.3802, -0.3093, -0.3772, +0.2394, -0.0069, +0.2487, -0.0366,
+ -0.2062, -0.4031, +0.1757, +0.1664, -0.6083, -0.4812, +0.3686, -1.8912
+ ],
+ [
+ +0.4638, -0.6215, -0.9444, -0.2262, -0.0024, -0.1107, +0.2688,
+ -0.8943, +0.2925, +0.0938, -0.2213, -0.0040, +0.5671, +0.1933,
+ -0.1180, +0.8275, -0.4667, +0.4134, +0.2031, -0.7823, -0.2169,
+ -0.0449, -0.0460, +0.2337, -0.6242, +0.1746, +0.1719, -0.3266,
+ -0.0035, -2.0916, -0.9540, -0.4786, +0.1893, +0.0484, -0.2314,
+ +0.0707, +0.6548, +0.1558, -1.5931, -0.1063, -0.0078, -0.1189,
+ +0.2243, -0.4626, +0.9811, +0.0963, +0.3128, +0.2263, -0.1932,
+ +0.2922, -0.8837, +0.4654, +0.3331, -0.7873, -0.1036, +0.1652,
+ -0.3548, -0.6482, -0.3590, -0.4473, -0.5732, -0.6507, +0.0124, +0.3495
+ ],
+ [
+ +0.2305, -0.0983, -0.6019, +0.0341, -0.0379, -0.3943, +0.2129,
+ -0.1420, -0.4793, +0.1007, +0.0970, -1.2953, +0.1626, +0.1505,
+ -0.0289, -0.0156, -0.8020, -0.5636, -0.3583, -0.5833, -0.0779,
+ +0.0571, -0.6464, -0.3262, -0.0799, +0.1420, -0.2370, +0.2553,
+ -0.0499, +0.0923, -0.0051, +0.1285, +0.3178, +0.4984, -0.8847,
+ +0.0226, -0.0542, +0.0218, +0.1203, -0.3696, -0.1743, +0.2263,
+ -0.2901, +0.2136, -0.1456, -0.1032, -0.3173, +0.2449, +0.3368,
+ -0.0686, +0.2705, -0.3874, -0.0087, +0.1807, +0.1054, -0.5347,
+ -0.4611, -0.0363, +0.3767, -0.4282, +0.2581, -0.1649, +0.2136, +0.2720
+ ],
+ [
+ +0.0920, -0.0227, +0.2435, -0.0693, -0.1166, +0.4459, +0.0340,
+ +0.1341, +0.0651, -0.4839, -1.2283, -0.3406, -0.0625, -0.1543,
+ -0.5159, -0.1331, -0.1011, +0.1511, +0.1291, -0.3677, +0.1103,
+ +0.3123, -0.0555, +0.0921, +0.2083, -1.2922, +0.4564, +0.2563,
+ -0.3195, -1.2801, +0.2871, -0.2701, -1.0224, -0.4784, +0.2698,
+ +0.0970, -0.3113, -0.2468, -0.5107, -0.1610, -0.0608, -0.5730,
+ +0.0112, -0.3562, +0.0284, +0.3547, -0.1682, -0.4646, -0.5916,
+ +0.0556, -0.4088, +0.3740, +0.1835, +0.2922, -0.2365, -0.0748,
+ +0.3475, -0.1332, -0.0565, -0.6135, -0.2440, -0.0980, +0.0177, +0.2084
+ ],
+ [
+ +0.5078, +0.2882, -0.1070, -0.2375, +0.1945, -0.1556, -0.1868,
+ +0.4579, -0.1407, -0.3003, +0.5034, -0.1413, -0.1191, +0.5198,
+ -0.0995, +0.2052, -0.6323, +0.3269, +0.1478, -0.9499, -0.0894,
+ -0.5471, -1.0356, -1.0237, +0.1626, +0.0408, -1.5120, +0.5972,
+ -0.2106, -0.1963, -0.2037, +0.4696, +0.0170, +0.3471, +0.6302,
+ +0.3234, +0.0171, +0.2163, -0.2019, -0.8498, -0.7691, +0.0792,
+ +0.1790, -0.2880, +0.1583, -0.2802, +0.3539, -0.2478, +0.2920,
+ -0.8338, +0.3591, -0.6136, -0.0626, +0.5065, +0.3065, -0.3856,
+ -0.7768, +1.0600, -0.3624, +0.4283, +0.6014, -0.2987, -0.5462, +0.5388
+ ],
+ [
+ -0.1657, +0.2175, +0.1502, +0.1590, +0.2511, -0.1747, +0.0322,
+ +0.0047, -0.1304, +0.1304, -0.2217, +0.2689, -0.0998, +0.0495,
+ +0.5198, -0.4353, +0.3513, -0.3965, -0.7116, +0.1963, -0.2455,
+ +0.1669, +0.0317, +0.0209, -0.9937, +0.0478, -0.1112, +0.0802,
+ -0.0946, +0.2395, -0.4575, +0.2455, -0.0041, +0.2040, -0.1288,
+ +0.4845, -0.0935, +0.1073, -0.1772, -0.0717, +0.1100, -1.2535,
+ -0.4555, +0.1200, +0.0925, +0.2260, -0.3057, +0.1682, -0.7064,
+ +0.0541, +0.2077, -0.6310, +0.1636, +0.4050, +0.0783, -0.2254,
+ -0.5860, +0.0542, -0.1233, +0.0088, -0.1021, -0.4150, -0.5846, +0.0780
+ ],
+ [
+ +0.0137, +0.1261, +0.2534, +0.0314, +0.1516, +0.2854, -0.2887,
+ -0.0637, -0.1735, +0.0230, -0.2352, -0.2550, -0.4087, -0.1375,
+ +0.5831, -0.4667, -0.1422, -0.0267, -0.1625, -0.4943, +0.0660,
+ -0.0611, -0.2226, -0.1747, +0.2218, +0.0342, -0.0662, -0.5225,
+ -0.2543, -0.3675, +0.2921, -0.5501, -0.6124, -1.0240, -0.0340,
+ +0.3921, +0.0436, -0.1442, +0.1874, +0.3041, -0.1329, +0.0904,
+ -0.4785, -0.1100, +0.7130, -0.9416, -0.3120, -0.3972, -0.0667,
+ -0.2238, +0.5337, +0.2120, -0.3086, +0.1386, +0.0945, -0.0784,
+ +0.0060, +0.3076, +0.1153, -0.8886, +0.2775, -0.3114, +0.1672, +0.2318
+ ],
+ [
+ +0.0146, -0.1282, -1.1506, +0.1754, +0.0246, -0.4277, +0.1070,
+ -0.5093, -0.0829, -0.9763, -1.5423, +0.0999, +0.1235, -0.5906,
+ -0.0747, +0.0536, -0.0421, +0.0307, +0.2496, +0.1554, -0.0956,
+ +0.2644, +0.0617, -0.0836, -0.8209, +0.2670, -0.0349, -0.7920,
+ -0.0636, -0.5876, -0.5698, -0.2682, -0.3274, +0.2240, -0.0315,
+ -0.3318, -0.1250, -0.1955, -0.2965, +0.2306, -0.0729, -0.2693,
+ -0.2185, +0.1496, +0.1656, +0.2526, -0.3052, -0.1906, -0.3483,
+ -1.2051, +0.3049, -0.1922, -0.3015, -0.4155, -0.3547, +0.0109,
+ -0.4658, -0.7525, -0.4770, -0.5124, +0.1414, -0.1773, -0.5394, +0.0918
+ ],
+ [
+ -0.9757, +0.5451, -0.1582, -0.0760, +0.2780, +0.0088, -0.5886,
+ +0.7647, +0.0055, +0.2014, +0.2445, -1.4211, -0.0321, +0.2212,
+ +0.4337, -0.5242, -0.2517, +0.1777, -0.0283, -0.4325, -0.0527,
+ -0.3353, -0.1614, -0.7283, +0.6176, -0.4128, -0.2551, +0.1218,
+ -0.2137, -0.5500, +0.2138, -0.5199, +0.1999, +0.5070, +0.8055,
+ +0.4022, -0.0963, -0.0710, -0.6852, -0.1077, +0.1993, -0.0105,
+ +0.1279, +0.0083, -0.2906, -0.6892, -0.5177, -0.5738, -0.0834,
+ -0.1992, -0.2419, +0.5335, -0.1230, +0.1839, -0.2993, +0.4106,
+ -0.7241, +0.3990, +0.1751, +0.2938, +0.0499, -1.0744, -0.2422, -0.4619
+ ],
+ [
+ -0.4866, -0.3855, -0.1042, -0.1423, +0.2359, +0.2600, -0.1206,
+ -0.1596, -0.0135, -0.7623, +0.8498, -0.4058, -0.2221, -0.2718,
+ -0.2202, -0.0022, -0.3595, -0.5880, -0.2412, -0.0803, +0.2923,
+ +0.0932, -0.0245, +0.0494, -0.0914, +0.0065, -0.1044, +0.2288,
+ -0.2645, +0.1512, -0.7647, +0.4264, +0.5612, -0.1165, +0.0498,
+ +0.2486, -0.4278, -0.5425, +0.2555, -0.2089, +0.1553, +0.2537,
+ +0.6342, -0.6339, -0.3252, +0.4005, +0.3177, -1.0503, -0.0484,
+ -0.6869, -1.2052, +0.0518, -0.2127, +0.6565, +0.1174, -0.0542,
+ +0.0330, -0.3769, -0.8160, -0.3341, +0.5011, -0.2296, -0.0582, +0.2720
+ ],
+ [
+ -0.2740, -0.4031, +0.1220, +0.2121, -0.2756, -1.1033, -0.7286,
+ -0.1866, +0.3279, +0.2347, -0.6916, +0.0782, -0.3519, +0.5791,
+ -0.0632, -1.1896, -0.5604, -0.2738, +0.2529, +0.0344, -0.0932,
+ -0.1923, -0.1518, -0.0706, +0.1075, +0.2185, -0.3537, -0.3668,
+ -0.5451, +0.7531, -0.2921, +0.9216, -0.6654, -0.4376, +0.0435,
+ -0.4269, +0.0265, -0.4000, -0.5693, -0.2149, +0.0681, -0.1618,
+ -0.1684, -0.1539, -0.0432, +0.0356, +0.1934, +0.1132, -0.8665,
+ -0.2111, -0.0802, +0.0847, +0.2886, -0.2710, -0.1154, -0.1229,
+ +0.0220, -0.2838, -0.2988, +0.2642, -0.1269, +0.0378, -0.0577, +0.2332
+ ],
+ [
+ -0.0167, -0.2866, -0.5837, -0.3393, -0.2001, -0.2052, -0.0069,
+ -0.0557, +0.0957, -0.0296, -1.2254, +0.6089, -0.7623, +0.2794,
+ -0.1563, -0.5299, -0.2602, +0.3578, +0.2024, -1.1151, -0.7019,
+ -0.3572, -0.2302, -0.0681, +0.1533, -0.3679, +0.3212, -0.0854,
+ -0.3797, -1.4589, +0.2442, -0.7591, -0.5560, -0.1719, -0.4811,
+ +0.0760, +0.2026, -0.0090, +0.3387, +0.5250, -0.3101, -0.5067,
+ +0.6807, -0.2780, +0.1402, +0.0732, -0.0141, -0.5621, -0.5418,
+ -0.1793, -0.1043, -0.1398, -0.2086, +0.0398, +0.5175, -0.0853,
+ +0.2001, +0.0463, +0.0370, -0.1317, -0.5319, +0.1052, -0.3744, -0.0245
+ ],
+ [
+ -0.2261, +0.1322, +0.2244, +0.0686, +0.6216, +0.2085, -0.2037,
+ -0.6063, -0.1096, -0.3126, +0.4351, +0.3109, -0.1477, -0.0571,
+ +0.4007, -0.3581, +0.3124, +0.2700, +0.3172, -0.5340, +0.2530,
+ +0.1908, +0.0630, +0.4039, +0.2531, +0.1035, +0.5428, +1.0849,
+ -0.6678, -0.1461, +0.1677, +0.6444, -0.1607, +0.0921, +0.0428,
+ -0.4171, +0.0052, -0.6449, +0.5795, +0.3778, -0.2117, +0.6219,
+ +0.4147, -0.2854, +0.0800, +0.2086, +0.1057, +0.0211, +0.1335,
+ +0.0754, -1.0412, +0.3630, -0.3308, -0.0163, +0.3209, +0.6749,
+ +0.1818, +0.0622, +0.0631, -0.0780, -0.2003, +0.0502, -0.1801, +0.1226
+ ],
+ [
+ -0.5705, -0.4520, -0.2005, -0.1099, +0.0716, +0.1710, -0.5488,
+ -0.0350, +0.3769, +0.5694, +0.2142, -0.2680, +0.3770, +0.0675,
+ +0.1544, -0.1849, -0.1091, -0.8965, +0.2643, +0.0145, -0.1163,
+ +0.0022, +0.0120, +0.4676, +0.0786, +0.0047, -0.0236, +0.2523,
+ -0.0296, -0.1272, -0.1784, -0.0316, -0.1040, -0.0833, -0.5759,
+ +0.1137, +0.1781, -0.1794, -0.7452, +0.2339, -0.2118, -0.0421,
+ +0.1374, -0.7774, +0.0419, +0.2437, -0.1457, -0.3050, -0.5618,
+ -0.8883, +0.3731, +0.1214, +0.2160, -0.2766, +0.2474, -0.0136,
+ -0.0689, +0.2249, +0.4861, +0.3022, +0.0187, +0.4610, +0.0144, -0.0760
+ ],
+ [
+ +0.0452, -0.0096, +0.0093, +0.3166, +0.0104, -0.8211, +0.0320,
+ -0.9130, -0.9762, +0.3912, +0.0517, -0.0086, -0.1364, -0.5440,
+ +0.3999, -0.8466, +0.1587, +0.3064, -0.0849, -1.0372, -0.3295,
+ -0.0011, +0.0702, +0.0558, -0.3068, -0.0579, +0.1683, +0.1862,
+ -0.3232, +0.0126, -0.0197, +0.3761, +0.3451, +0.1456, -0.1702,
+ +0.3671, +0.2129, +0.1910, -0.4390, -0.2298, +0.2539, -0.2647,
+ -0.0812, +0.1049, +0.0182, +0.0124, +0.1412, +0.7550, +0.1466,
+ +0.0842, -0.2089, -0.1244, -0.1409, -0.0448, +0.4329, +0.2906,
+ +0.1276, +0.0849, +0.1483, -0.1114, +0.1040, -0.1841, +0.0504, +0.0628
+ ],
+ [
+ -0.7229, -0.2299, +0.3797, +0.2634, +0.1779, +0.1996, -0.0516,
+ +0.1889, -0.0321, -0.0180, +0.1005, -0.1224, -0.7053, -0.1657,
+ +0.2718, -0.1325, -0.3542, -0.0817, +0.0660, -0.3473, -0.1094,
+ +0.3669, +0.0287, +0.4202, +0.5254, +0.3843, +0.2454, -0.1032,
+ -0.2225, +0.1151, +0.2620, -0.2615, +0.1377, -0.0886, +0.1253,
+ -0.2241, +0.2043, -0.6399, -0.0001, +0.2756, -0.5004, +0.0097,
+ +0.1577, +0.1704, -0.4630, +0.0586, +0.1950, -0.2765, +0.3850,
+ +0.1792, -0.0390, +0.0853, +0.0609, +0.3052, +0.1366, +0.4978,
+ -0.0320, -0.0238, -0.2433, +0.1354, -0.3672, +0.1638, +0.3015, +0.0190
+ ],
+ [
+ -0.5652, -0.5404, +0.3047, +0.2983, +0.0327, -0.2695, +0.3298,
+ +0.0245, -0.8883, -0.2214, +0.0148, +0.2319, -0.4585, -0.4131,
+ +0.1738, -0.0687, +0.2266, -0.0930, -0.0778, +0.0594, -0.7182,
+ -0.5207, -0.1110, -0.6784, +0.1840, +0.4566, +0.0854, -0.0213,
+ -0.4181, +0.1902, +0.3848, -0.3574, +0.0339, +0.0642, +0.2140,
+ +0.2387, +0.1925, -0.4425, -0.1289, +0.0003, +0.4367, -0.1658,
+ -0.6550, +0.0966, -0.2929, -0.0290, +0.0821, +0.0917, +0.0588,
+ +0.0215, +0.2516, -0.6177, -0.3127, +0.1305, +0.1058, -0.2301,
+ -0.1769, +0.3145, +0.0931, +0.0435, +0.2786, +0.4412, +0.1732, -0.1200
+ ],
+ [
+ -0.0996, -0.6608, -0.0364, +0.3340, +0.0165, +0.3010, +0.0927,
+ +0.1056, -0.2970, -0.1835, +0.0571, +0.2240, +0.0030, -0.6368,
+ +0.2202, -0.1890, +0.4696, -0.0632, -0.0631, +0.0907, -0.1202,
+ -0.3129, -0.0065, -0.2858, +0.5460, +0.2200, +0.2605, +0.0594,
+ -0.2014, +0.3389, +0.3456, -0.0752, +0.0585, -0.0157, +0.0157,
+ +0.0445, +0.3628, -0.4249, -0.3869, -0.0149, +0.3033, -0.2029,
+ +0.3068, +0.2245, -0.3317, +0.5013, +0.2260, +0.0021, +0.5501,
+ +0.0470, +0.0281, -0.4652, -0.5074, +0.0623, +0.2559, +0.1474,
+ +0.3211, +0.3766, -0.0389, +0.3026, +0.0087, +0.4048, +0.4947, -0.1758
+ ],
+ [
+ +0.1554, -0.1069, +0.0311, +0.1231, +0.1511, -0.5720, -0.2430,
+ +0.0702, -0.3883, +0.0351, -0.4604, +0.2486, -0.1264, +0.0224,
+ -0.4056, -0.0509, -0.2476, +0.4460, +0.3992, -1.0177, -0.4811,
+ -0.0661, -0.4349, +0.0118, -0.3434, -0.0266, -0.4486, -0.2416,
+ -0.2670, -0.2086, -0.6751, +0.0134, -0.0306, +0.1693, -0.1759,
+ +0.2342, +0.0876, +0.0606, +0.5759, -0.6247, -0.0825, +0.8001,
+ -0.4028, -0.3971, +0.4740, -0.7486, -0.1452, +0.0966, -1.1183,
+ -1.7440, +0.3747, -0.2859, -0.4128, +0.0351, -0.1834, +0.2799,
+ -0.5416, +0.1614, -0.1525, +0.5196, +0.1470, +0.2015, -0.0209, +0.4493
+ ],
+ [
+ +0.4452, +0.3101, -0.1846, -0.2601, +0.0557, -0.1652, +0.2796,
+ -0.2789, -0.3574, +0.7659, -0.0928, -0.1773, +0.2040, +0.3471,
+ +0.0277, +0.1219, +0.1127, +0.2735, -0.0420, -0.3129, -0.8266,
+ -0.0287, -0.1716, +0.0738, -1.1224, -0.2538, -0.1206, +0.4969,
+ +0.5520, -0.9201, -0.4422, -0.4078, -0.2800, +0.0784, -0.1056,
+ -0.1181, -0.6464, +0.1835, -0.1094, -0.0400, +0.3895, -0.4687,
+ +0.7645, +0.1850, +0.8089, -0.0632, +0.3379, -0.1370, -1.2702,
+ -0.1647, -0.0076, -0.3014, +0.5104, -0.8770, -0.1667, +0.0547,
+ -0.9042, -0.7874, +0.4112, -0.6015, +0.1230, -0.3193, -0.3689, +0.7722
+ ],
+ [
+ -0.1760, +0.0806, +0.0633, +0.1495, -0.2089, -0.1720, +0.3683,
+ -0.7910, -0.1092, -0.0286, -0.2381, -0.3570, -0.3146, -0.4156,
+ -0.4463, +0.2495, +0.1315, -0.4987, -0.0444, -0.3366, +0.4729,
+ +0.5814, +0.2111, +0.5879, -0.4906, -0.2095, +0.1884, -0.8830,
+ +0.0099, -0.5141, -0.0253, +0.0638, -0.5014, -0.6889, +0.4109,
+ -0.3437, -0.5957, -0.3521, +0.4051, +0.1513, +0.0929, +0.2743,
+ -0.5853, -0.0101, +0.0543, +0.0796, +0.0171, -0.1006, -0.8329,
+ +0.3093, -0.7488, -0.1443, +0.4323, -0.3448, -0.6281, +0.4770,
+ +0.4202, -0.8632, -0.3805, -1.1830, -0.7543, -0.5576, -0.5449, +0.2612
+ ],
+ [
+ -0.7124, +0.0296, -0.0180, +0.1221, +0.3492, -0.1979, +0.1803,
+ -0.6664, -0.4365, +0.0834, +0.0055, +0.2783, +0.2842, -0.3726,
+ -0.1905, -0.3562, +0.4659, +0.5841, +0.2670, +0.3766, +0.2223,
+ -0.2560, -1.2231, +0.3688, -0.6143, -0.4259, -0.0066, -0.6308,
+ -0.0026, -0.4631, -0.1651, -0.3861, +0.1432, +0.3695, +0.3812,
+ +0.1687, -0.0687, +0.6742, -0.1006, -0.0740, +0.3388, -0.1572,
+ +0.3848, +0.1060, -0.3427, -0.0441, +0.1701, -0.9669, -0.6756,
+ -0.7418, -0.4919, +0.1873, -0.0749, -0.0006, -0.2966, -0.3439,
+ +0.1329, +0.1904, -0.4898, -0.7065, +0.3420, -0.1842, +0.2152, -0.0524
+ ],
+ [
+ -0.0034, +0.0550, -1.2687, -0.0799, +0.3824, -0.1359, +0.2033,
+ -0.0635, -0.1804, -0.0437, +0.1483, -0.5138, -0.7083, -0.4176,
+ +0.4133, -0.9608, -0.1535, +0.2607, +0.1512, +0.0048, +0.1409,
+ +0.0624, -0.2070, -0.6507, -0.1054, -0.1554, -0.9355, +0.1028,
+ +0.6517, -0.1690, -0.0253, -0.6379, -0.4949, -0.0544, -0.0154,
+ +0.2114, -0.2261, +0.6168, +0.0140, +0.0834, +0.2390, -0.4280,
+ -0.5701, -0.3384, +0.3953, -0.0290, -0.0415, +0.1204, +0.0763,
+ -0.5635, -0.6979, -0.2972, +0.1168, +0.0858, +0.5719, +0.0460,
+ -0.1850, +0.3278, +0.2367, -0.1745, +0.3339, +0.2345, -0.7674, +0.2316
+ ],
+ [
+ -0.7640, +0.4325, -0.7808, -0.8599, +0.0685, +0.1389, -0.4254,
+ +0.1816, +0.5504, +0.5307, -0.3181, -0.6939, -0.4922, +0.2190,
+ -0.0280, +0.0948, -0.0696, +0.2561, -0.3489, +0.1103, +0.2562,
+ -0.0775, -0.4995, -0.3639, +0.4419, -0.0798, +0.1815, -0.4532,
+ +0.0092, -0.3042, -0.5383, +0.2354, -0.0964, -0.3795, +0.6289,
+ -0.0032, +0.8141, +0.1504, +0.3532, +0.4816, -0.4394, -0.2215,
+ -0.2689, +0.6740, -0.1720, +0.0399, -1.3940, -0.0466, -0.6636,
+ -0.7952, +0.2715, +0.1412, +0.1164, +0.1355, -0.4197, -0.1231,
+ +0.0225, +0.1704, -0.6381, -0.1786, +0.1951, +0.7547, +0.0585, -0.9978
+ ],
+ [
+ +0.2424, +0.1429, -0.5942, -0.8311, -0.4039, +0.0123, -0.5286,
+ -0.1538, +0.1444, -0.2057, +0.1541, +0.3277, +0.0325, -0.1216,
+ -0.2855, -0.3571, -1.2245, +0.5472, +0.8566, -0.4063, -0.0020,
+ +0.0161, -0.0828, +0.1365, -0.3165, +0.1856, +0.4180, +0.3827,
+ +0.4085, +0.1363, -0.5951, +0.2136, +0.4635, -0.3175, -0.0179,
+ -0.1298, +0.3717, +0.3155, +0.7539, -0.3723, -0.9288, -0.0145,
+ +0.2546, -0.1112, +0.0629, +0.1843, +0.3677, -0.3291, -0.4158,
+ -0.4757, -0.6994, +0.1739, +0.2550, -0.2444, +0.1263, +0.2426,
+ +0.2999, -0.1290, -0.3900, +0.3528, +0.1145, +0.2559, -0.0819, -0.4488
+ ],
+ [
+ -0.4228, -0.1394, -0.2091, -0.0344, +0.4417, -0.0600, -0.5085,
+ +0.2543, -0.0523, +0.3243, +0.0854, +0.2292, +0.0820, -0.0431,
+ +0.0678, -0.0514, -0.0348, -0.0160, +0.5653, +0.1224, +0.2047,
+ -0.1892, -0.9762, -1.0318, -0.9600, +0.2571, +0.0527, +0.2796,
+ -0.0836, +0.0239, -0.6415, +0.2080, +0.3183, +0.1883, -1.2626,
+ +0.2661, +0.1099, -0.3269, -0.3931, -0.2218, -0.0774, -0.1932,
+ -0.2984, -0.2962, -0.0536, -0.4651, -0.2370, -0.1265, -0.1956,
+ -0.5390, -0.5313, -0.4435, -0.0816, +0.1992, -0.2242, -0.5927,
+ -0.0626, +0.1441, +0.0228, -0.1464, +0.1223, -0.0883, +0.2199, +0.1578
+ ],
+ [
+ +0.3977, +0.0629, -0.0984, -0.4987, +0.4269, -0.1940, -0.1254,
+ +0.2561, +0.2799, -0.2491, -0.1810, +0.2404, +0.5219, +0.0879,
+ -0.2920, +0.3293, +0.0132, +0.0919, -0.1286, +0.5001, +0.1045,
+ -0.1544, -0.5092, -0.2277, +0.1893, -0.6046, +0.1304, +0.9889,
+ +0.1189, +0.2228, -0.3941, -0.0629, -0.3580, -1.2052, -0.3574,
+ -0.5456, -0.2044, -0.3054, -0.0874, -0.7163, +0.0782, +0.4724,
+ +0.4832, -1.0618, +0.2777, -0.3273, +0.0845, +0.0028, +0.1905,
+ +0.3128, +0.1351, +0.1499, -0.1993, +0.0798, +0.0308, -0.8532,
+ +0.0118, -0.2095, -0.0387, +0.1203, +0.1096, -0.0137, +0.1436, -0.2861
+ ],
+ [
+ -0.2417, -0.0439, +0.1189, +0.2369, -0.2781, +0.3031, +0.0773,
+ +0.6085, +0.0232, -0.1423, -0.6961, -0.8309, -0.6136, -0.2563,
+ +0.0283, -0.1212, -0.4166, -0.0050, +0.0318, +0.0260, -0.2687,
+ -0.1907, -0.2317, -0.6242, +0.4980, -0.2121, -0.2454, -0.8505,
+ -0.6092, -1.1722, +0.5666, +0.1006, -0.1905, -0.0702, +0.0700,
+ +0.0617, +0.1817, -0.2282, +0.0176, -0.2242, +0.1264, -0.2623,
+ -0.7171, -0.1821, -0.3619, -0.1819, -0.2828, -0.2249, -0.0303,
+ +0.0185, +0.2609, -0.0549, -0.0996, +0.4723, -0.3633, +0.0846,
+ +0.0765, +0.3280, -0.2451, +0.1041, -0.0034, +0.2080, +0.1936, -0.4749
+ ],
+ [
+ -0.4080, +0.0101, +0.4896, +0.2650, -0.0713, -0.4852, -0.4725,
+ -0.1664, +0.1746, -0.1745, +0.1742, +0.0886, -0.0533, -0.2693,
+ -0.1717, -0.1211, -0.5343, -0.2970, -0.2407, -0.0890, +0.2510,
+ +0.1665, -0.0280, -0.5085, -0.0720, +0.0815, +0.0286, -1.0586,
+ -0.0480, +0.6197, -0.1686, -0.0971, -0.0590, -0.0530, -0.5561,
+ +0.2351, -0.8316, -0.4513, -0.0833, +0.3241, -0.2440, +0.0885,
+ -0.0566, -0.0628, +0.0390, +0.0530, +0.1303, +0.2249, +0.3535,
+ -0.1897, -0.0028, -0.4503, -0.4608, -0.4771, +0.0547, +0.1368,
+ -0.0396, -0.0574, -0.7205, -0.0545, +0.3713, -0.1449, +0.0460, -0.2573
+ ],
+ [
+ +0.1729, +0.3328, -0.0483, +0.3430, -0.8166, -0.7130, -0.1524,
+ -0.8914, -0.0284, +0.3845, +0.3261, -0.2930, -0.1704, -0.0667,
+ -0.0761, -1.0040, +0.5002, +0.0138, +0.0480, -0.1500, -0.1398,
+ +0.1682, +0.4195, -0.2878, -0.4181, -0.5565, +0.1091, -0.2138,
+ -0.0314, -0.9147, -0.2513, +0.0348, -0.1134, -0.1961, +0.5464,
+ +0.2765, +0.0357, -0.5474, -0.6593, -0.0637, -0.5578, +0.0965,
+ -0.3782, -0.0283, +0.1986, -0.7640, -0.2243, +0.1620, -0.4975,
+ +0.4370, -0.0027, -0.4728, -0.5417, +0.1895, +0.4871, -0.7267,
+ -0.0884, -0.4895, -0.3184, -0.2400, +0.5365, -0.6006, -0.0316, -0.2627
+ ],
+ [
+ -0.1250, -0.2274, -0.4734, -0.8212, -0.8737, -0.2582, -0.1367,
+ +0.0765, +0.1154, -0.0014, +0.1208, -0.0270, -0.0425, +0.3288,
+ -0.1526, +0.3159, -0.3454, +0.3237, +0.0894, -0.5365, +0.1782,
+ -1.0302, +0.0365, -0.2069, +0.1498, -0.5999, -0.2724, -0.1894,
+ +0.4306, -0.3260, -0.3904, -0.0550, -0.2776, -0.2343, +0.4672,
+ -0.1577, -0.2296, +0.2996, -0.6247, -0.2263, -0.4007, -0.2281,
+ -0.0291, -0.6503, +0.3853, -0.7961, +0.3894, -0.0580, -1.3425,
+ -0.2164, -0.1007, +0.1227, -0.4520, +0.1167, +0.1217, +0.1238,
+ +0.0792, -1.1752, +0.1036, +0.0568, -0.3924, +0.0349, -0.5209, +0.3545
+ ],
+ [
+ +0.0287, -0.3782, +0.1962, -0.1268, +0.3571, -0.0019, -0.0362,
+ -0.0845, +0.3061, +0.2659, -0.5059, -0.1129, -0.4579, +0.2661,
+ +0.0929, +0.0436, +0.0056, +0.2657, +0.3845, -0.5530, +0.1714,
+ +0.4608, +0.2531, +0.3154, +0.0426, +0.5664, +0.2775, -0.1081,
+ +0.2637, -0.1573, -0.2128, +0.0684, -0.4874, -0.0263, -0.0327,
+ -0.0933, -0.1256, -0.7359, -0.0188, +0.5449, -0.1793, +0.2461,
+ +0.1168, +0.1503, +0.4420, +0.0875, -0.4102, +0.0356, -0.2893,
+ +0.2913, -0.8194, +0.4889, +0.0413, +0.3302, -0.2903, +0.0952,
+ +0.0212, +0.3041, +0.1542, -0.4005, -0.2331, -1.3377, +0.1470, -0.7202
+ ],
+ [
+ -0.9282, -0.1059, -0.0082, -0.1766, -1.3977, -1.3125, +0.3087,
+ -0.3368, -0.6917, +0.0534, +0.0881, -0.7281, -0.4862, +0.0312,
+ -0.8796, -0.0374, -0.0516, -0.3584, -0.9422, -0.8726, +0.0645,
+ +0.0442, -0.2800, -0.3980, -0.1358, +0.4521, +0.1079, -0.1224,
+ +0.1390, -0.5237, -0.2044, -0.8309, +0.2561, +0.4951, -0.7866,
+ -0.1615, -0.2310, -0.2373, +0.0514, +0.2622, -0.4641, -0.1833,
+ -0.1839, -0.0406, -0.3321, -0.2933, -0.0421, +0.1813, -0.2127,
+ -0.1382, -0.0012, -0.6567, -1.4080, -0.3627, +0.3178, -1.2242,
+ -0.9392, -0.1510, +0.2459, -0.0221, +0.4568, -0.4586, -0.0793, +0.3680
+ ],
+ [
+ -0.3041, +0.2604, -0.2652, +0.6025, +0.0916, +0.0136, -0.2971,
+ +0.3269, +0.0725, -0.2456, -0.3518, +0.2903, +0.1801, -0.6663,
+ +0.3020, +0.1644, +0.3541, -0.2844, -0.5166, -0.1280, -0.0661,
+ +0.5309, +0.2226, +0.0688, -0.1076, -0.0739, +0.1466, +0.5006,
+ -0.0508, -0.1852, +0.0641, +0.0069, -0.6020, -0.2326, -0.1071,
+ -0.1683, +0.1069, +0.3673, -0.1795, -0.3418, -0.0471, +0.2649,
+ +0.0608, -0.9008, +0.1314, +0.0451, -0.4691, -0.1016, -0.5714,
+ +0.0841, +0.1224, +0.1867, -0.0598, -0.1693, -0.3963, +0.0738,
+ +0.5359, +0.3494, +0.1235, +0.4378, -0.0009, +0.5538, +0.4332, -0.0908
+ ],
+ [
+ -0.5524, +0.2589, +0.1305, -0.4090, -0.0750, +0.1026, +0.5287,
+ +0.2289, +0.4169, -0.0428, -0.3602, -0.1625, +0.0370, -0.4344,
+ -0.2947, -0.0240, +0.1273, -0.0985, -1.3586, -0.7712, -0.2291,
+ -0.4270, +0.4181, +0.3414, +0.1665, +0.0272, +0.3223, -0.1411,
+ -0.0644, -0.7001, +0.1848, +0.3318, -0.4295, -0.7952, -0.0880,
+ -0.4895, +0.2159, -0.1718, -0.3125, +0.0386, -0.6332, -0.3036,
+ -0.5912, -0.4327, -0.0451, -0.5203, -0.0132, -0.1439, -0.1113,
+ +0.0051, +0.0134, -0.0185, -0.0601, -0.0629, -0.2407, -0.4088,
+ +0.0155, -0.2293, -1.0280, +0.0067, +0.1398, -0.1448, +0.3806, +0.2182
+ ],
+ [
+ +0.0648, -0.0437, -0.0942, -0.2744, -0.4381, -0.2502, +0.1999,
+ -0.1825, +0.3736, -0.5487, -0.2808, -0.8762, -0.0995, -0.7099,
+ -0.1731, -0.0471, +0.0135, +0.3748, -0.4082, -0.2058, +0.5860,
+ +0.4465, +0.2315, +0.1135, -0.3129, -0.8307, +0.1438, -0.6274,
+ +0.0895, -0.1950, -0.0484, -0.2457, +0.1510, -0.8775, -0.9142,
+ -0.1708, -0.0972, -0.6048, +0.2905, +0.5451, -0.2202, -0.3213,
+ -0.0398, -0.3397, +0.0215, -0.1846, +0.1132, -0.0441, -0.4064,
+ -0.2330, -0.5510, +0.4083, +0.0116, -0.1033, -0.0460, +0.1744,
+ +0.1322, -0.7649, -0.5508, +0.6277, +0.0331, -0.4214, +0.2977, +0.3355
+ ],
+ [
+ -0.1351, -0.2439, +0.3468, +0.2800, -0.0715, +0.0273, +0.0259,
+ +0.2220, -0.1142, -0.2086, +0.1733, -0.3081, -0.0993, +0.0308,
+ -0.8777, +0.2663, -0.0156, -0.0179, +0.3093, +0.2105, -0.1656,
+ -0.3246, -0.0365, -0.4435, +0.3391, -0.0303, +0.2684, -0.6413,
+ -0.0021, -0.7990, +0.1877, -0.3394, +0.2103, +0.0907, +0.0610,
+ +0.0687, +0.2747, -0.3606, +0.1065, +0.0569, +0.2614, +0.1773,
+ -0.8595, +0.0669, -0.1244, -0.4618, -0.3705, -0.0510, +0.2129,
+ +0.1995, +0.0395, -0.0747, -0.2724, +0.1117, -0.3345, -0.3311,
+ +0.0042, +0.3678, +0.3423, +0.2525, -0.0849, +0.3778, +0.4023, -0.1001
+ ],
+ [
+ +0.1241, -0.0503, -0.0182, -0.2132, -0.2386, -0.3724, -0.2412,
+ -0.1737, -0.1700, +0.3160, -0.0092, +0.2899, -1.5977, +0.1411,
+ -0.7268, -0.0835, +0.5029, +0.1386, -0.0634, -0.4580, +0.1020,
+ -0.4675, +0.5110, -0.2398, +0.3636, -0.5651, -0.1730, +0.1509,
+ +0.3955, -1.8248, -0.0228, -0.4183, -0.2963, +0.1007, +0.4309,
+ +0.0637, -0.0066, -0.0472, -0.1385, +0.0819, +0.0202, -0.3139,
+ -0.0896, +0.5357, -0.7048, -0.0429, -0.1733, -0.6343, -0.2395,
+ +0.2319, +0.1909, -0.3611, -0.0093, +0.0513, +0.2180, -0.2943,
+ +0.1112, -0.1285, -0.6500, +0.4892, +0.0203, -1.1220, -0.0724, +0.4504
+ ],
+ [
+ +0.1112, -0.0448, -0.6431, +0.1884, +0.3960, -0.1572, +0.1121,
+ -0.1994, -0.0486, -0.2115, -0.0936, -1.5022, -0.2118, -0.6693,
+ +0.3676, -0.2709, -0.3703, +0.3534, -0.0593, +0.2411, -0.3764,
+ +0.2110, +0.2070, -0.3406, -0.2990, +0.4268, -0.0408, +0.1984,
+ -0.3161, +0.3869, -0.3141, -0.4338, +0.0395, -0.3092, +0.2746,
+ -0.2975, -1.0016, +0.0616, -0.2120, +0.0863, -0.0899, -0.3227,
+ -0.1391, +0.2368, -0.5746, +0.3478, +0.0162, +0.8646, -0.4043,
+ -1.0257, +0.3557, -0.1569, +0.1722, -0.1626, +0.2160, +0.4056,
+ -0.7633, -0.3259, -0.2412, -0.0411, -0.0130, -0.1054, -0.6206, -0.3220
+ ],
+ [
+ +0.4052, -1.3239, +0.1395, +0.1058, -0.1199, -0.1038, +0.1456,
+ +0.3265, -0.3059, -0.7138, -0.0618, +0.3480, +0.5171, +0.0254,
+ -0.2988, +0.2774, +0.0976, -1.0849, +0.3354, -0.0790, +0.2007,
+ -0.1853, -0.5298, +0.0797, -0.0231, -0.7360, +0.0341, -0.2407,
+ -0.0900, -0.2925, -0.3616, +0.1548, -0.2782, -0.0473, +0.0645,
+ -0.1320, +0.1575, +0.0137, +0.1537, -0.3346, -0.0175, +0.1294,
+ +0.2803, +0.2576, -0.1722, -0.4272, +0.1171, +0.0722, +0.1484,
+ -0.6063, +0.0117, -0.1859, -0.8487, +0.4184, -0.0151, +0.1533,
+ +0.1805, +0.0843, -0.2879, +0.1382, -0.2115, -0.0440, +0.0444, -0.0504
+ ],
+ [
+ +0.2015, -0.0965, -0.1258, +0.1679, -0.1030, -0.0350, -0.6746,
+ -0.3363, +0.0040, -0.4968, -0.5428, +0.0732, +0.1692, -0.2251,
+ -0.1405, -0.8176, -0.8816, -0.2601, -1.5304, +0.1403, +0.0187,
+ +0.2748, -0.3534, -0.5089, -0.3561, +0.0367, -0.1690, -0.1544,
+ +0.0946, -0.2731, -1.0779, -0.0782, +0.0202, +0.2626, -0.1983,
+ -0.0035, +0.0846, +0.2907, +0.3259, -0.2063, -0.2135, -2.0981,
+ -0.0221, +0.0993, +0.0145, +0.1018, -1.0300, +0.1958, -0.4191,
+ -0.1791, -1.3965, -0.0060, -0.2669, +0.1638, -0.2012, +0.1843,
+ +0.0784, +0.2943, -0.7675, +0.2927, -1.4470, +0.0775, -0.3201, -0.3827
+ ],
+ [
+ +0.0769, +0.5498, -1.0880, -0.2418, -0.2665, -0.2998, -0.1256,
+ -0.6255, -0.3412, -1.4133, -0.0203, -0.0106, -0.3917, -0.8333,
+ +0.4150, -0.3510, -0.5165, -0.4994, -0.7379, +0.3555, -0.0781,
+ +0.0691, +0.6025, -0.1950, -0.5176, -1.1022, -0.2531, +0.1358,
+ -0.7036, -0.2015, -0.3584, -1.2470, -0.1838, -0.2505, -0.1474,
+ -0.4272, +0.2569, -0.5964, -0.9194, -0.0551, +0.3572, -0.0710,
+ +0.1742, -0.4531, -0.3903, -0.3115, -0.1155, -0.2580, -0.7872,
+ +0.2532, -0.1176, -0.1610, -0.7792, -0.6183, -0.4232, +0.3920,
+ -0.2407, -0.8548, +0.3624, +0.3435, -0.8205, -0.2136, -0.2942, -0.8762
+ ],
+ [
+ -0.0060, -0.1489, -0.0067, -0.0177, +0.2215, -0.0389, -0.5227,
+ -0.2337, -0.2741, +0.0386, -0.3261, -0.0032, -1.0200, -0.1971,
+ -0.2788, +0.1595, -0.2238, +0.0137, -0.0144, -0.2236, -0.2323,
+ +0.2903, +0.3488, -0.2384, +0.1007, +0.2121, +0.3509, -0.4017,
+ +0.0860, -0.7740, +0.0739, -0.8059, -0.0612, -0.0426, +0.2213,
+ +0.2794, -0.1782, -0.0981, +0.0738, -0.1360, +0.0495, +0.1766,
+ -1.0368, +0.0651, -0.1478, -0.3529, +0.6294, -0.0024, +0.0441,
+ -0.2223, +0.2321, +0.5418, -0.3990, -0.1180, +0.2173, +0.0073,
+ +0.0535, +0.0381, +0.0572, +0.1349, +0.1543, -0.0255, -0.0671, -0.3958
+ ],
+ [
+ +0.0025, +0.2615, +0.2055, -0.3618, +0.2058, -0.0355, +0.2262,
+ +0.1584, -0.2848, +0.3526, -0.1021, +0.4582, -0.2301, +0.8823,
+ -0.3449, +0.7340, -0.2356, -0.1065, -0.1333, +0.1678, +0.0023,
+ -0.5715, +0.0944, -0.2364, -0.0328, -0.1789, -0.7771, +0.0033,
+ +0.6611, +0.1509, -0.0369, -0.1838, -0.0900, +0.0302, +0.4032,
+ +0.3461, -0.3497, +0.3714, -0.2241, +0.3681, -0.1810, +0.1401,
+ +0.4326, -0.3580, +0.1228, -0.5266, +0.1445, -0.1295, -0.7390,
+ -0.0307, +0.2383, -0.3647, +0.8082, -0.2832, -0.1272, -0.6293,
+ -0.0267, +0.0772, +0.5436, -0.4430, +0.2039, -0.0094, -0.4602, +0.3507
+ ],
+ [
+ +0.4441, -0.5284, -0.3247, -0.1185, +0.1127, +0.2549, -0.1608,
+ +0.0508, -0.1256, +0.1456, +0.0630, -0.3331, +0.2147, -0.1859,
+ -0.1065, -0.8297, -0.8537, -0.5747, -0.2079, -0.2383, -0.0755,
+ +0.2487, +0.4479, +0.2179, -0.4586, -0.0045, +0.0736, +0.0240,
+ -0.1013, +0.1411, -0.3923, +0.0215, -0.2443, -0.9218, -0.0136,
+ +0.2523, -0.3079, +0.2825, +0.4820, -0.0487, -0.4192, +0.3460,
+ +0.2341, -0.1544, -0.1730, +0.1748, +0.4015, -0.0670, -0.4138,
+ -0.7546, -0.0984, -0.1398, -0.1484, +0.2143, +0.3287, +0.3576,
+ -0.1715, -0.4426, -0.1114, +0.2873, -0.1759, -0.2131, -0.3125, +0.2399
+ ],
+ [
+ -0.3040, -0.7858, -0.0431, +0.2444, -0.4689, +0.5505, -0.0415,
+ -0.2255, +0.4772, -0.9782, -1.3075, -0.7475, -0.2918, -0.4632,
+ -0.4139, -0.2807, -0.9729, +0.0464, +0.2641, -0.0045, +0.2904,
+ +0.2615, -0.4323, -0.2294, +0.4595, -0.4169, +0.2735, -0.7092,
+ -0.8494, -0.9467, +0.0363, -1.6053, -0.0743, +0.1101, +0.2005,
+ -0.1111, -0.2316, +0.3037, -0.0224, +0.4787, -0.1178, -0.2842,
+ -0.1521, +0.0089, +0.0149, +0.2476, -0.3097, +0.4197, -0.0513,
+ -0.3052, -0.1770, +0.0698, -0.0028, -0.7217, -0.0423, +0.0789,
+ +0.0522, -0.4582, -0.0321, +0.8307, +0.2203, -0.0733, +0.3136, +0.0570
+ ],
+ [
+ +0.1303, +0.0891, -1.0181, -1.4978, +0.0734, +0.1124, +0.2199,
+ +0.0153, +0.4390, -0.4317, -0.5141, -0.4691, +0.0737, +0.3579,
+ -0.1853, -0.0772, -0.8077, -0.6385, -0.4633, +0.4321, +0.5496,
+ +0.2986, -0.1555, -0.1559, +0.0699, -0.3715, -0.2052, -0.2325,
+ +0.3984, -0.4306, -0.6361, -0.3066, -0.4227, -0.7002, -0.5833,
+ -0.0950, -0.2275, -0.2462, -0.2574, +0.3585, -0.2933, -0.1192,
+ +0.4343, -0.5342, +0.1994, +0.3493, -0.7433, +0.0396, -0.2139,
+ -0.7354, -1.5901, +0.2998, +0.2103, -0.2378, -0.3848, -0.1763,
+ +0.5698, -0.8950, -1.7041, +0.2384, -0.1701, +0.1376, +0.3842, -0.8876
+ ],
+ [
+ -0.1219, +0.3198, -0.2701, +0.1497, -0.1258, +0.3358, -0.4570,
+ -0.4552, +0.5140, -0.1106, -0.5427, -1.0853, -0.1620, +0.1679,
+ -0.7057, -0.5208, -1.5624, -0.6301, -0.6283, +0.0699, -0.1598,
+ -0.1935, +0.0253, +0.1096, +0.0912, -0.0082, +0.0710, -0.9496,
+ -0.0222, -0.3077, -0.4092, -0.1090, -0.1891, -0.0032, +0.4414,
+ -0.4561, -1.1972, +0.4971, -0.0040, +0.0863, -1.3692, -0.1463,
+ -0.1298, +0.3283, -0.2834, -0.0431, +0.0177, +0.0811, -0.2410,
+ -0.0614, +0.2315, +0.3008, -0.6321, -0.8940, -1.5395, -0.6845,
+ -0.5164, +0.5963, -0.1694, +0.0239, +0.3146, +0.5295, -0.1202, -0.2046
+ ],
+ [
+ -0.4515, -0.5445, -0.4470, +0.1876, -0.0639, -0.2497, +0.2629,
+ +0.2056, +0.4504, +0.1000, -0.1992, -0.1178, +0.5982, +0.1020,
+ +0.2526, -0.5141, -0.3257, +0.2873, +0.2843, +0.0204, -0.0355,
+ +0.4963, -0.0575, -0.2666, -0.6928, -0.0279, -0.4045, +0.4385,
+ -0.1725, +0.2043, -1.0905, +0.3458, +0.2299, -0.1574, -0.6403,
+ +0.4463, -0.4436, -0.0591, -0.8299, -0.2485, +0.3504, -0.2333,
+ +0.1834, +0.0245, +0.0756, -0.0047, -1.1088, -0.0788, -1.0611,
+ -0.2504, +0.2807, +0.1821, -0.1618, +0.0871, -0.1961, -0.0566,
+ -0.8393, -0.2867, -0.5395, -0.7387, -0.9088, +0.1558, -0.0021, +0.1817
+ ],
+ [
+ +0.2262, -0.0991, -0.7318, +0.0777, +0.0829, +0.1066, +0.0909,
+ +0.0586, -0.1002, +0.2647, +0.3763, +0.2981, +0.2813, +0.1898,
+ +0.2196, +0.1406, -0.2669, -0.0615, -0.4188, -0.3941, -0.2429,
+ -0.2700, -0.6246, +0.0977, -0.0156, -0.6503, -0.3818, +0.2284,
+ +0.2446, -0.2068, -0.0891, +0.1039, -0.5602, -0.0217, -0.0608,
+ -0.0454, +0.0959, +0.4183, +0.2183, -0.3189, +0.1210, -0.0680,
+ +0.1768, -0.3043, -0.2762, -0.8097, +0.4302, +0.1414, -0.6430,
+ -0.1104, -0.3396, -0.4695, +0.4050, -0.1201, +0.0801, -0.1988,
+ -0.0255, +0.1783, -0.0352, -0.4146, +0.1602, +0.0232, -0.4713, +0.2315
+ ],
+ [
+ -0.2409, -0.2534, +0.3787, +0.8244, +0.0585, -0.1560, +0.3867,
+ +0.4848, +0.0786, +0.3797, -0.4736, +0.1127, -0.1765, +0.4122,
+ -0.0028, -0.0079, +0.4908, -0.2022, +0.0382, +0.3820, +0.1218,
+ +0.4168, +0.0748, -0.0767, +0.1911, +0.1314, -0.3224, +0.2587,
+ +0.2849, +0.3945, +0.0604, +0.0050, -0.3590, -0.7451, -0.3942,
+ +0.2198, +0.2039, +0.2079, -0.3846, -0.0248, -0.4721, +0.1699,
+ -0.0122, -1.2120, +0.4807, +0.0437, -0.1432, -0.0937, +0.3850,
+ +0.0717, -0.6115, -0.1069, -0.3580, -0.7625, -0.1524, -0.5527,
+ +0.0189, +0.2040, +0.1220, +0.4873, -0.3443, +0.1473, +0.2942, -1.2750
+ ],
+ [
+ -0.0321, +0.0938, -0.1564, +0.0153, -0.0956, +0.0683, -0.1992,
+ -0.8894, +0.0980, -0.0950, -0.5909, +0.1010, +0.0940, -0.7160,
+ +0.0752, +0.5469, -0.6442, -0.0053, +0.2000, +0.3000, -0.3391,
+ -0.1122, +0.3253, +0.1063, +0.1491, -0.0684, -0.0410, -0.3039,
+ -0.6195, +0.2862, -0.1455, -0.8795, -0.3885, +0.0299, -0.0195,
+ -0.1107, +0.0015, +0.4024, -0.9457, -0.4620, +0.0877, -0.2296,
+ -0.0326, +0.2932, -0.2720, +0.4663, -0.0610, +0.1745, +0.1352,
+ -0.5966, -0.1366, +0.2271, -0.4483, -0.4548, +0.0057, +0.2810,
+ -0.4279, +0.0572, -0.8984, +0.1419, -0.1966, +0.0214, -0.5856, -0.4380
+ ],
+ [
+ -0.2850, -0.4454, -0.0200, +0.1379, +0.1279, +0.1286, +0.5722,
+ -0.0797, +0.1775, +0.0054, +0.3466, -1.1324, +0.0630, -0.0436,
+ -0.9319, +0.0692, +0.1615, -0.1780, +0.1783, +0.0662, +0.2824,
+ -0.0309, -0.1921, +0.2110, -0.2472, +0.0026, +0.3590, -0.1833,
+ -0.0167, -0.6163, -0.1092, +0.2120, +0.4458, +0.0250, -0.8406,
+ -0.0331, +0.3448, -0.5886, -0.0235, +0.0602, +0.3971, +0.4033,
+ +0.3516, -0.1472, -0.2371, -0.8047, +0.1336, -0.1083, -0.5510,
+ +0.3792, -0.4230, -0.1216, -0.7740, -0.4497, -0.2848, -0.3698,
+ -0.0160, +0.5724, -0.4150, +0.3254, -0.2344, +0.4417, +0.0460, -0.0463
+ ],
+ [
+ -0.1091, -0.0947, -0.3343, -0.8910, -0.0137, +0.1534, -0.3422,
+ -0.5111, +0.0206, +0.2841, +0.2981, +0.3313, +0.2598, -0.0501,
+ -0.5783, +0.3304, -0.2725, +0.1159, -0.2722, -0.5441, +0.2231,
+ -0.0244, +0.3478, +0.1623, -0.2798, -0.0695, +0.3506, -0.1275,
+ +0.2209, -0.3317, -0.2965, +0.4564, -0.2473, -0.3701, +0.4166,
+ -0.1918, +0.0488, +0.5048, +0.4159, -0.1447, +0.0998, +0.0424,
+ +0.0734, -0.3713, +0.3236, -0.4136, -0.2221, +0.1728, -0.6407,
+ +0.2623, -0.4332, +0.4175, +0.2960, -0.3424, -0.5264, -0.5679,
+ +0.2437, -0.6032, -0.5213, -0.0424, -0.5911, -0.0611, -0.1877, +0.2423
+ ],
+ [
+ -0.0360, -0.4567, -0.1493, -0.0765, -0.2676, +0.1338, +0.1486,
+ +0.3867, +0.2451, -0.2054, -0.1088, -1.5518, +0.2254, +0.0175,
+ -0.1154, -0.3777, -0.6173, -0.8897, -0.1523, +0.1594, -0.1772,
+ -0.3349, -0.1155, -1.1580, +0.2605, +0.0570, +0.1894, -0.0755,
+ +0.2382, -0.1726, -0.0400, +0.4391, +0.2241, +0.0551, -0.1106,
+ +0.0817, +0.0128, -0.1330, -0.0162, -0.3872, -0.2613, -0.2073,
+ +0.0483, +0.0026, -0.1008, -0.0389, -0.6723, -0.0657, +0.1532,
+ -0.0627, -0.2517, -0.1961, -0.0313, -0.2694, +0.1040, +0.2662,
+ -0.3370, +0.2086, -0.2202, +0.2812, -0.9275, -0.0331, +0.1384, -0.4651
+ ],
+ [
+ -0.0323, +0.5816, +0.2069, +0.1766, +0.8736, -0.1321, -0.5366,
+ +0.4362, -0.9437, +0.5586, +0.8281, +0.1417, +0.4988, +0.2451,
+ -0.1327, +0.3295, +0.1639, +0.2168, -0.5869, -0.9139, +0.3259,
+ -1.2364, +0.0104, -0.4723, -0.2869, -0.0693, -0.1767, +0.0528,
+ +0.3629, +0.0766, -0.2554, +0.7631, +0.0007, +0.3657, +0.2479,
+ +0.0949, -0.1070, +0.2789, -0.6009, +0.3627, -0.1986, +0.3212,
+ +0.5274, +0.2307, +0.1055, -0.8864, +0.4670, +0.0430, -0.2485,
+ +0.0445, -0.0792, +0.0362, -0.7101, -0.1554, +0.4530, -0.5127,
+ -1.0097, -0.4877, +0.1803, +0.1016, +0.2774, -0.7071, -0.2316, +0.1476
+ ],
+ [
+ +0.0676, -0.2920, +0.4224, -0.1409, +0.0856, -0.0969, +0.2461,
+ -0.7079, -0.4348, -0.8510, -0.2213, -0.0541, -0.0461, -0.2451,
+ +0.2312, -0.0496, +0.3432, -0.1916, +0.1832, +0.4089, +0.1642,
+ -0.0928, +0.1869, +0.2472, -0.9379, -0.0356, -0.2276, -0.1867,
+ -0.1108, +0.3021, -0.7620, -0.0141, +0.3072, -0.0326, -0.1854,
+ -0.0535, +0.3489, -0.3910, -0.8369, +0.5177, +0.3154, +0.6535,
+ -0.4463, -0.4381, -0.2189, +0.2761, +0.1655, +0.1010, -0.0769,
+ -0.5381, -0.4710, +0.1980, -0.0818, -0.3762, +0.0076, +0.1753,
+ -0.0984, -0.5887, -0.0019, -0.4983, +0.2914, -0.7693, +0.1656, -0.6165
+ ],
+ [
+ +0.2126, -0.3435, -0.2802, +0.0979, -0.9373, -0.7181, +0.2063,
+ -0.2545, +0.3562, +0.0894, +0.5294, -0.3816, +0.5833, -0.2488,
+ -0.4786, +0.2132, -0.3223, +0.2189, +0.2034, +0.0680, +0.3741,
+ -0.2337, -0.2645, -0.2871, -0.3461, +0.3580, -0.7551, -0.4948,
+ -0.4941, -0.1607, -0.0062, +0.3991, +0.5354, -0.1153, +0.4384,
+ +0.2346, +0.0923, +0.6214, +0.2485, -0.2547, -0.2755, +0.3398,
+ +0.2522, +0.0409, +0.1309, -1.1476, +0.4321, -1.6605, -0.6035,
+ -0.5415, -0.0799, -0.1754, -0.5326, -0.1910, +0.1372, -0.4079,
+ -0.3110, +0.0060, +0.0015, -0.7618, +0.5021, -0.3054, -0.1895, +0.4327
+ ],
+ [
+ +0.1316, +0.1998, +0.0677, +0.2773, -0.2720, -0.8087, -0.0022,
+ -0.2622, -1.0104, -0.4908, +0.4249, +0.0597, -0.5553, -0.4698,
+ -0.0096, -0.1893, +0.1355, -0.6921, +0.0211, +0.3253, -0.0769,
+ +0.0565, -0.6166, -0.7295, +0.0477, -0.0101, -0.5214, -0.6498,
+ -0.7418, -0.8979, +0.0792, -0.1958, -0.5255, +0.1953, -0.6446,
+ -0.0748, -0.3183, +0.1582, -0.3667, +0.2170, +0.2665, -0.0075,
+ +0.0740, +0.2708, -0.1289, +0.0462, -0.6262, -0.4190, -0.1797,
+ +0.3994, -0.8803, -0.4579, -0.3235, +0.2903, -1.3589, -0.5549,
+ -0.6767, +0.0308, +0.0491, -0.3117, +0.2053, +0.1075, +0.2042, -0.4537
+ ],
+ [
+ -0.9114, +0.3823, -0.2137, -0.0383, +0.0891, -0.5047, -0.3632,
+ -0.0115, -0.3604, +0.2107, -0.4123, -0.1508, -0.3897, -0.1566,
+ -0.3869, +0.0458, -0.3594, -0.6799, -1.0821, -0.2322, +0.1464,
+ +0.2626, -0.1674, -0.5577, +0.0910, -0.1279, +0.4003, -0.1568,
+ +0.0907, -0.1528, -0.0554, +0.4973, +0.3610, +0.3540, +0.3717,
+ -0.2353, +0.1743, +0.2026, +0.8891, -0.5409, -0.3690, +0.1897,
+ -1.1785, -0.0244, +0.0283, +0.0709, -0.9182, -0.1485, +0.3410,
+ -0.3562, +0.1126, +0.3459, +0.0190, +0.4073, -0.0685, -0.0834,
+ +0.1817, +0.3957, +0.3428, +0.2351, -0.2072, -0.2002, +0.0579, +0.2585
+ ],
+ [
+ +0.0476, -0.7260, -0.2175, -0.8305, +0.3673, -0.1075, -0.7324,
+ +0.1022, -0.1264, +0.0679, -0.2494, +0.2647, -0.7667, +0.1632,
+ -0.1487, -0.1800, -0.4566, -0.4716, +0.3124, +0.4227, -0.2557,
+ +0.1477, -0.0946, +0.0803, +0.0136, +0.0699, -0.6304, +0.5944,
+ +0.1812, -0.0072, -1.2447, +0.7503, -0.7340, -0.6389, -0.0202,
+ +0.1716, -0.0661, -0.7511, -0.6451, +0.4344, +0.2398, +0.9628,
+ -0.2201, +0.1901, +0.6633, -0.0529, -0.3787, +0.3837, -0.4481,
+ +0.1792, -0.2828, +0.7377, +0.6304, -0.9296, +0.1690, +0.5375,
+ +0.3884, -0.3548, +0.0788, -0.7348, +0.2273, -0.5028, -0.4739, +0.1150
+ ],
+ [
+ +0.1521, -0.0100, -0.1015, +0.1975, -0.5804, -0.0891, +0.4443,
+ -0.0275, -0.3218, -0.3674, -1.0237, -0.9589, +0.1408, +0.1039,
+ -0.4158, -0.3465, -0.2163, +0.3031, -0.0905, -1.1000, +0.0028,
+ +0.1196, +0.1130, +0.4777, -0.0803, -0.3295, -1.5273, -0.4059,
+ -0.2642, -0.6425, +0.1149, -0.0094, +0.1067, -0.6440, -0.0806,
+ +0.2513, +0.2070, -0.0682, -0.0854, -0.4654, +0.0119, -0.2918,
+ +0.0766, -0.0766, +0.0621, -0.5751, -0.7636, -0.4295, -0.1413,
+ +0.0667, -0.0193, +0.0210, +0.1867, +0.1727, -0.0391, -0.5251,
+ -0.0746, +0.0615, -0.0581, -0.4284, -0.2977, -0.0883, -0.1302, +0.1829
+ ],
+ [
+ -0.1256, +0.0829, -0.5799, -1.0012, +0.3669, +0.2700, +0.2691,
+ -0.2078, +0.6662, +0.4342, -0.7014, +0.1332, +0.0736, +0.5960,
+ +0.1266, +0.4412, -0.3859, +0.0702, -0.7489, -0.1285, +0.1080,
+ -0.0248, -0.0614, -0.2922, -0.1791, +0.2619, -0.2986, +0.1326,
+ -0.1112, -0.4128, -0.3499, -0.2148, +0.0886, -0.3239, +0.1767,
+ +0.2782, -0.1033, -0.1350, +0.0324, -0.2402, +0.2440, +0.2858,
+ +0.0111, -0.6319, +0.3694, -0.5569, +0.0758, -0.5506, -0.8423,
+ -0.6073, -0.0642, +0.0559, +0.3943, -0.1092, -0.3964, +0.0705,
+ -0.3753, +0.2106, -0.0118, -0.2122, -0.0904, +0.3428, -0.2614, -0.0007
+ ],
+ [
+ +0.3415, +0.4062, -0.4667, +0.2757, -0.5389, -0.1429, -0.0005,
+ +0.1749, -0.1646, -0.9262, +0.1978, -0.3748, +0.3384, +0.1757,
+ -0.0899, +0.1567, +0.3043, -0.0828, -0.7369, +0.2833, +0.2871,
+ -0.0150, -0.0895, +0.2181, -0.3692, -0.2344, -0.3813, -0.4984,
+ +0.2426, +0.3936, -0.3995, -0.0257, -0.2650, -0.5329, -0.6254,
+ +0.0492, -0.0428, +0.3595, -0.1242, -0.3341, -0.1174, +0.2283,
+ +0.3051, -0.0794, -0.0715, +0.2324, +0.1567, -0.4121, +0.0756,
+ -0.6483, -0.7294, -0.0235, -0.5082, -0.1506, -0.0962, +0.1123,
+ +0.1990, -0.5521, -0.8837, +0.2634, -0.6452, +0.0470, +0.0747, +0.0456
+ ],
+ [
+ -1.2951, +0.1232, -0.8490, +0.2284, +0.3593, -0.9968, +0.1914,
+ +0.3673, +0.1287, +0.0485, -0.6153, -0.6149, -0.2634, -0.7023,
+ +0.2006, +0.2657, -0.0201, -0.6250, -0.1045, -0.5447, -0.2495,
+ -0.0712, -0.2281, -0.1573, -0.0079, -0.4966, -0.5428, -1.5871,
+ -0.0332, -0.3754, +0.0438, -0.2096, -0.0341, -0.2111, -0.1953,
+ -0.1146, +0.0260, -0.0840, -0.9739, +0.0693, +0.1628, -0.6525,
+ -0.9299, +0.1602, -0.0673, -1.1183, -1.1446, -0.0575, +0.0123,
+ +0.0463, +0.0683, +0.0192, -0.7718, -0.1055, -0.1894, +0.3897,
+ -0.8589, +0.2829, +0.0774, -0.1157, +0.0772, +0.0168, +0.3460, +0.2657
+ ],
+ [
+ -0.3160, +0.3029, +0.2132, -0.2024, -0.0573, +0.2263, +0.3686,
+ -0.2059, +0.2531, -0.4922, -0.4110, -0.0881, -0.0267, -0.3069,
+ +0.2496, -0.2458, -0.0348, -0.4285, +0.0564, +0.5539, +0.3510,
+ +0.0755, +0.2656, +0.5299, -0.0647, +0.0431, +0.3277, +0.0192,
+ -0.3490, +0.2500, +0.2519, +0.2055, +0.2462, -0.2927, +0.2902,
+ -0.1451, -0.0611, -0.3940, -0.6985, +0.0295, -0.1272, -0.0507,
+ +0.0030, -0.0484, -0.4220, +0.3042, -0.1346, -0.4380, +0.0247,
+ -0.2205, -0.1549, -0.7229, -0.1487, -0.1124, +0.2539, +0.1274,
+ +0.6169, +0.3346, -0.1577, +0.4318, +0.1469, -0.0689, +0.0982, -0.3816
+ ],
+ [
+ +0.4151, +0.1020, -0.3973, -0.1940, -0.0893, -0.5294, -0.0714,
+ +0.1221, +0.2081, -0.1500, +0.0839, +0.0651, +0.1602, +0.1521,
+ +0.3755, +0.4533, -0.0749, -0.1498, +0.0048, +0.2987, +0.3013,
+ -0.2483, -0.8249, +0.1123, -0.2657, -0.0776, -0.8314, -0.0567,
+ +0.4846, +0.1280, -0.4166, +0.2149, -0.5095, -0.2219, -0.6757,
+ +0.5484, +0.2117, +0.1901, -0.3840, -0.0860, -0.0527, -0.8445,
+ +0.1747, -0.7124, +0.3261, -0.0172, -0.4794, +0.2829, -0.9583,
+ -0.3825, -0.2641, -0.1610, +0.0921, +0.0395, -0.7542, -0.4747,
+ +0.0891, -0.5037, +0.4109, +0.2718, -0.1609, +0.3680, -0.2975, +0.0092
+ ],
+ [
+ -0.2679, -0.2103, +0.1004, +0.2703, +0.0541, +0.4900, +0.1016,
+ +0.0008, -0.0075, +0.0959, -0.2459, -0.4452, +0.1211, -0.0521,
+ -0.5468, +0.2349, -0.0690, +0.0936, -0.3218, -0.0093, +0.0644,
+ +0.4158, +0.1109, +0.2373, +0.3008, -0.2570, +0.2886, -0.1720,
+ +0.3146, -0.6991, +0.2565, -0.1762, -0.0239, -0.6296, -0.8216,
+ -0.8141, +0.0871, -0.5981, +0.2595, +0.2109, -0.3252, -0.2758,
+ +0.2662, -0.1662, +0.0087, -0.3265, +0.2910, -0.3716, +0.3225,
+ +0.0907, +0.0550, +0.4069, +0.3731, -0.0367, -0.0844, -0.7320,
+ +0.3318, +0.0839, +0.1493, -0.1054, -0.4476, +0.0671, +0.3858, -0.3728
+ ],
+ [
+ -0.0163, +0.4856, -0.1412, -0.0100, -0.2343, +0.1223, -0.5244,
+ -0.4046, +0.1738, -0.0262, +0.0922, -0.6767, +0.2672, +0.1770,
+ -0.4969, +0.3919, -0.1103, -0.3749, +0.2580, -0.0209, -0.2500,
+ -0.1089, +0.0587, +0.4735, +0.2116, +0.0299, +0.1709, +0.0804,
+ +0.8460, +0.1637, +0.1775, -0.3955, +0.2403, -0.1843, +0.0579,
+ -0.3362, +0.1129, +0.2148, -0.0079, -0.0662, -0.1286, +0.1830,
+ +0.0437, +0.0167, -0.0824, -0.1148, +0.2380, -0.3372, -0.0684,
+ -0.3226, +0.2914, +0.0994, -0.1599, +0.0130, +0.1584, +0.0975,
+ +0.2723, +0.1877, -0.4828, +0.1463, -0.2304, +0.3497, +0.0522, -0.0404
+ ],
+ [
+ +0.3846, +0.3960, +0.0721, -0.5932, -0.6720, +0.3994, -1.1131,
+ +0.0500, -0.0433, -0.5014, -0.2795, +0.0226, -0.0276, -0.3389,
+ -0.1971, +0.3228, -0.3439, +0.5770, +0.5260, -0.2861, +0.3810,
+ -0.0225, +0.3133, +0.1716, +0.0778, -0.1298, +0.0765, -0.1700,
+ +0.5689, +0.2767, -0.5815, +0.2572, -0.7600, -0.1481, +0.2901,
+ -0.4648, +0.1381, +0.2972, -0.4802, -0.6701, -0.6240, -0.0784,
+ -0.0330, -0.5339, +0.1989, +0.2422, +0.0886, -0.1819, -0.2638,
+ +0.0189, -0.1023, +0.3559, +0.2563, +0.0272, -0.1343, +0.2034,
+ +0.6096, -0.2862, -0.2925, +0.1162, -0.5740, -0.4293, -0.1544, -0.3657
+ ],
+ [
+ -0.1666, -0.5683, +0.3239, +0.0008, -0.0790, +0.0108, +0.1210,
+ +0.2313, -0.0242, -0.3114, +0.1546, -0.0983, -0.1095, -0.5754,
+ +0.1360, -0.7269, +0.0714, -0.9205, +0.2401, +0.0983, +0.1060,
+ +0.0410, +0.2889, -0.7942, +0.3511, +0.1338, +0.1118, +0.1873,
+ -0.4490, +0.2648, -0.1163, +0.1410, -0.0005, -0.0627, +0.2816,
+ -0.0261, +0.0111, -0.3929, -0.3200, +0.3405, +0.1021, -0.0294,
+ +0.2000, -0.2919, -0.2395, +0.1867, +0.1548, -0.0702, +0.0021,
+ +0.5599, -0.2662, -0.4859, -0.1809, +0.2777, +0.2588, +0.1977,
+ +0.0975, -0.3367, -0.1211, +0.1057, -0.0247, +0.4044, +0.4802, -0.4940
+ ],
+ [
+ -0.3074, +0.2169, +0.0655, -0.3575, +0.2765, -1.0735, +0.3228,
+ -0.7085, -0.1075, -0.1250, +0.1302, -0.2700, -0.6832, -0.0223,
+ -0.5448, +0.3824, -0.5548, +0.2615, -0.4700, +1.0847, -0.0443,
+ -0.9753, +0.1278, +1.0526, +0.7114, +0.2395, +0.1612, -0.3276,
+ +0.3154, +0.4751, -0.3890, -0.2353, +0.6575, -0.1306, -0.4566,
+ -0.3303, +0.6051, -0.1868, -0.9390, -0.3405, +0.3341, +0.5198,
+ +0.0939, -0.6396, -0.0410, -0.0942, -0.4784, -0.6260, -0.0983,
+ -0.3750, -0.1402, -0.0351, +0.0890, -0.5765, +0.3816, -0.5375,
+ +0.6580, +0.0448, -0.3544, +0.1669, +0.0808, -0.4698, +0.0085, +0.5292
+ ],
+ [
+ -0.1747, -0.5134, +0.1257, +0.6530, +0.3251, +0.0013, +0.8608,
+ -0.6414, +0.3327, -0.3861, +0.5066, -0.8033, +0.1957, -0.2380,
+ -0.1649, -0.0760, -0.3093, -0.3283, +0.0661, -0.1066, +0.3787,
+ -0.3254, +0.5536, -0.4949, +0.1560, +0.1118, +0.1465, +0.3107,
+ +0.5213, +0.1194, +0.2602, +0.0551, -0.0612, +0.1378, -0.1037,
+ +0.5086, -0.3383, -0.2024, -0.1786, -0.2193, -0.3955, -0.0600,
+ +0.4502, -0.0450, -0.3765, -0.9599, +0.2312, +0.0751, -0.1329,
+ +0.1573, -0.2891, -0.0944, -0.4619, +0.3256, +0.2486, -0.2238,
+ +0.2054, -0.1677, -1.2201, +0.2986, +0.5681, +0.0700, -0.0916, +0.3844
+ ],
+ [
+ +0.5860, +0.1473, -0.3536, +0.1924, -0.1819, +0.3126, -0.3094,
+ +0.4127, -0.3403, -0.3101, +0.4899, +0.3310, +0.3136, -0.1343,
+ +0.1557, +0.0007, +0.0431, -0.0531, -0.3300, +0.3820, -0.3771,
+ -0.6818, -0.4023, -0.1221, -0.0995, +0.1512, -0.2698, -0.0544,
+ +0.0406, +0.0104, +0.2382, +0.0113, +0.5360, +0.3837, +0.0947,
+ +0.4839, +0.0278, -0.4629, -0.1912, -0.7728, -0.0162, +0.5847,
+ +0.1752, +0.1536, -0.3113, -0.4624, -0.2032, -0.2410, -0.0095,
+ -0.3411, -0.2375, -0.3024, -0.0689, +0.0134, -0.2987, +0.2678,
+ +0.1053, +0.3568, -0.3776, -0.0956, +0.1105, +0.1802, +0.3608, +0.2763
+ ],
+ [
+ -0.0126, -0.1275, +0.1721, -0.1653, +0.0189, -0.0586, +0.1487,
+ +0.2661, -0.0924, -0.1733, +0.0411, +0.1124, -0.0426, -0.0405,
+ +0.0713, -0.1322, +0.1053, +0.2013, +0.2442, -0.4979, +0.3654,
+ -0.2099, +0.0049, -0.6743, -0.1063, -0.1213, +0.2036, +0.2109,
+ -0.2639, +0.1839, +0.3105, -0.0961, +0.3935, +0.1186, -0.0959,
+ +0.5348, -0.3605, -0.6159, -0.3268, +0.1327, +0.5812, -0.4447,
+ -1.8573, +0.1350, -0.0151, +0.1569, +0.0348, +0.2221, -0.6421,
+ -0.2810, +0.1918, -0.1290, +0.0505, +0.0517, +0.0313, -0.0781,
+ +0.1746, +0.0713, +0.2894, -1.0579, -0.1106, +0.3800, -0.6895, -1.1236
+ ]])
-weights_final_w = np.array([
-[ +0.5409, +0.1061, +0.1214, +0.0961, -0.0304, +0.2028],
-[ +0.3719, +0.0252, -0.1683, +0.1448, +0.0874, -0.0254],
-[ -0.1174, +0.2622, -0.1514, -0.2936, -0.1060, -0.5701],
-[ +0.0623, +0.0379, -0.0004, -0.3542, -0.0684, -0.2670],
-[ +0.0487, +0.0638, -0.5099, -0.1448, -0.0639, +0.1894],
-[ -0.3975, -0.1887, +0.2938, -0.0159, +0.1679, +0.5848],
-[ +0.1560, -0.0012, -0.0360, -0.2195, -0.3875, +0.0259],
-[ -0.0942, -0.0268, -0.1722, -0.0594, -0.0527, +0.5528],
-[ +0.1087, -0.3823, -0.1868, -0.0919, +0.2626, +0.2375],
-[ +0.0054, -0.1016, -0.3405, +0.4056, +0.0899, +0.0129],
-[ -0.0055, +0.1361, +0.2055, +0.6780, +0.0250, -0.0961],
-[ +0.0586, +0.7423, -0.0014, +0.1401, +0.4564, +0.5103],
-[ -0.1461, +0.1129, +0.2607, +0.3828, +0.2286, +0.0225],
-[ -0.0789, +0.0790, -0.1576, +0.3564, +0.4390, +0.2671],
-[ +0.2657, +0.0888, -0.2312, -0.1819, -0.1583, -0.1158],
-[ -0.0429, +0.1533, -0.0649, +0.1670, +0.5324, +0.2681],
-[ +0.1750, +0.0582, -0.1742, +0.7826, -0.0295, -0.0646],
-[ +0.1563, +0.0241, -0.4052, +0.5419, +0.0212, -0.1529],
-[ +0.1667, -0.0708, +0.0750, +0.0286, +0.2312, -0.2932],
-[ -0.0755, +0.3814, -0.3422, -0.3412, +0.0820, -0.6145],
-[ -0.0485, -0.1721, -0.1366, -0.0866, +0.0972, +0.4096],
-[ -0.0026, -0.3586, -0.0705, -0.0509, +0.0127, +0.3078],
-[ +0.1658, -0.2918, -0.4419, -0.1099, -0.1852, -0.0318],
-[ +0.3883, -0.1925, -0.3671, -0.3079, -0.1405, -0.6695],
-[ -0.3967, -0.1212, +0.2062, -0.4248, +0.2445, +0.5061],
-[ +0.2296, +0.0054, +0.1389, +0.1225, -0.2944, -0.3264],
-[ -0.3366, -0.1053, +0.1004, +0.0522, -0.2441, -0.1599],
-[ +0.3214, +0.3230, -0.3416, +0.1735, -0.0354, +0.0172],
-[ -0.0715, -0.0971, +0.2212, +0.0870, +0.4960, +0.0409],
-[ +0.6941, +0.1916, +0.4534, -0.3305, -0.1206, +0.2755],
-[ -0.0466, +0.2676, -0.2066, -0.2910, +0.0603, +0.1708],
-[ +0.3716, +0.1599, -0.1473, +0.0362, -0.0572, +0.4125],
-[ +0.0225, -0.1431, +0.3085, -0.1022, -0.3053, -0.3167],
-[ +0.1484, +0.3096, +0.2186, -0.2676, +0.2821, -0.0416],
-[ +0.2600, -0.1355, +0.1571, -0.4409, +0.1009, +0.1011],
-[ +0.2334, +0.3423, -0.0794, +0.0448, -0.0112, -0.0245],
-[ -0.3402, +0.1981, -0.0945, +0.1727, -0.0363, -0.1486],
-[ -0.4074, -0.1319, +0.0434, +0.4359, -0.2658, -0.3302],
-[ +0.2756, -0.2130, -0.2856, -0.1436, -0.4224, +0.1142],
-[ -0.1194, +0.2529, -0.2741, -0.0691, -0.2947, -0.0033],
-[ -0.0449, +0.4437, -0.0389, +0.1377, +0.1102, -0.1049],
-[ +0.4368, +0.1699, +0.3433, -0.4160, -0.3043, +0.1180],
-[ -0.1328, -0.6681, +0.4017, +0.3457, +0.1843, -0.0134],
-[ +0.0630, +0.2032, +0.2331, -0.1384, -0.1024, +0.3183],
-[ +0.1946, +0.1460, -0.1598, -0.2830, +0.2411, +0.3073],
-[ +0.4296, -0.2071, +0.3769, +0.0840, -0.0062, -0.1579],
-[ -0.0790, -0.1186, +0.0962, +0.4871, -0.2901, +0.6272],
-[ -0.2573, +0.3325, +0.1097, -0.2340, -0.0787, +0.1208],
-[ -0.4469, -0.3637, -0.1740, -0.4408, +0.0512, +0.5575],
-[ +0.1426, -0.3975, -0.0685, -0.0452, -0.4517, +0.4320],
-[ -0.5925, +0.3324, -0.1968, -0.2537, +0.6491, -0.2922],
-[ -0.2201, -0.3118, -0.3722, +0.0216, +0.1670, -0.1343],
-[ +0.0638, -0.2374, -0.1480, +0.4090, +0.2347, +0.1456],
-[ -0.0656, +0.1516, -0.3281, -0.2661, +0.0645, +0.0550],
-[ +0.3725, +0.2281, +0.3031, +0.0774, -0.3138, +0.0967],
-[ +0.3016, +0.0322, +0.0556, -0.0571, -0.1177, -0.2442],
-[ -0.2769, -0.5119, -0.0336, -0.1588, +0.0503, -0.2331],
-[ +0.1518, +0.4363, +0.0093, -0.3960, -0.1347, +0.2931],
-[ +0.1897, -0.0655, +0.1977, +0.4321, +0.6998, -0.0863],
-[ +0.0391, -0.0305, +0.3576, -0.4996, -0.0640, -0.0039],
-[ +0.2922, +0.3815, +0.2834, +0.1990, -0.0568, +0.2077],
-[ -0.5371, +0.2796, +0.2952, +0.1182, +0.0523, -0.2151],
-[ -0.5111, +0.2231, -0.1034, +0.0479, -0.0543, +0.0605],
-[ +0.0822, -0.4530, -0.0345, +0.1621, -0.2487, +0.1516]
+weights_dense2_b = np.array([
+ +0.1534, -0.0356, +0.0392, +0.0272, +0.0733, +0.2141, -0.0432, -0.0479,
+ -0.1264, +0.1456, +0.2103, -0.0233, +0.2320, -0.0525, +0.1808, +0.1565,
+ -0.0347, -0.0719, -0.2635, -0.1948, -0.1301, +0.0453, -0.0722, +0.0875,
+ +0.3780, +0.1023, +0.1012, +0.3150, +0.1801, +0.1941, +0.2014, +0.1381,
+ +0.1411, -0.0371, -0.0987, +0.1987, +0.1015, -0.2282, +0.0072, -0.0800,
+ +0.0323, +0.1198, +0.2822, +0.0090, -0.1950, +0.0864, +0.2694, -0.0746,
+ +0.2193, +0.1658, +0.0712, -0.1185, +0.1351, +0.1331, +0.3542, +0.1543,
+ +0.1557, -0.0575, +0.0659, -0.0090, -0.1502, +0.0665, +0.1853, -0.0413
])
-weights_final_b = np.array([ +0.1367, +0.1107, -0.0148, +0.1158, -0.0820, +0.3047])
+weights_final_w = np.array(
+ [[+0.5409, +0.1061, +0.1214, +0.0961, -0.0304, +0.2028],
+ [+0.3719, +0.0252, -0.1683, +0.1448, +0.0874, -0.0254],
+ [-0.1174, +0.2622, -0.1514, -0.2936, -0.1060, -0.5701],
+ [+0.0623, +0.0379, -0.0004, -0.3542, -0.0684, -0.2670],
+ [+0.0487, +0.0638, -0.5099, -0.1448, -0.0639, +0.1894],
+ [-0.3975, -0.1887, +0.2938, -0.0159, +0.1679, +0.5848],
+ [+0.1560, -0.0012, -0.0360, -0.2195, -0.3875, +0.0259],
+ [-0.0942, -0.0268, -0.1722, -0.0594, -0.0527, +0.5528],
+ [+0.1087, -0.3823, -0.1868, -0.0919, +0.2626, +0.2375],
+ [+0.0054, -0.1016, -0.3405, +0.4056, +0.0899, +0.0129],
+ [-0.0055, +0.1361, +0.2055, +0.6780, +0.0250, -0.0961],
+ [+0.0586, +0.7423, -0.0014, +0.1401, +0.4564, +0.5103],
+ [-0.1461, +0.1129, +0.2607, +0.3828, +0.2286, +0.0225],
+ [-0.0789, +0.0790, -0.1576, +0.3564, +0.4390, +0.2671],
+ [+0.2657, +0.0888, -0.2312, -0.1819, -0.1583, -0.1158],
+ [-0.0429, +0.1533, -0.0649, +0.1670, +0.5324, +0.2681],
+ [+0.1750, +0.0582, -0.1742, +0.7826, -0.0295, -0.0646],
+ [+0.1563, +0.0241, -0.4052, +0.5419, +0.0212, -0.1529],
+ [+0.1667, -0.0708, +0.0750, +0.0286, +0.2312, -0.2932],
+ [-0.0755, +0.3814, -0.3422, -0.3412, +0.0820, -0.6145],
+ [-0.0485, -0.1721, -0.1366, -0.0866, +0.0972, +0.4096],
+ [-0.0026, -0.3586, -0.0705, -0.0509, +0.0127, +0.3078],
+ [+0.1658, -0.2918, -0.4419, -0.1099, -0.1852, -0.0318],
+ [+0.3883, -0.1925, -0.3671, -0.3079, -0.1405, -0.6695],
+ [-0.3967, -0.1212, +0.2062, -0.4248, +0.2445, +0.5061],
+ [+0.2296, +0.0054, +0.1389, +0.1225, -0.2944, -0.3264],
+ [-0.3366, -0.1053, +0.1004, +0.0522, -0.2441, -0.1599],
+ [+0.3214, +0.3230, -0.3416, +0.1735, -0.0354, +0.0172],
+ [-0.0715, -0.0971, +0.2212, +0.0870, +0.4960, +0.0409],
+ [+0.6941, +0.1916, +0.4534, -0.3305, -0.1206, +0.2755],
+ [-0.0466, +0.2676, -0.2066, -0.2910, +0.0603, +0.1708],
+ [+0.3716, +0.1599, -0.1473, +0.0362, -0.0572, +0.4125],
+ [+0.0225, -0.1431, +0.3085, -0.1022, -0.3053, -0.3167],
+ [+0.1484, +0.3096, +0.2186, -0.2676, +0.2821, -0.0416],
+ [+0.2600, -0.1355, +0.1571, -0.4409, +0.1009, +0.1011],
+ [+0.2334, +0.3423, -0.0794, +0.0448, -0.0112, -0.0245],
+ [-0.3402, +0.1981, -0.0945, +0.1727, -0.0363, -0.1486],
+ [-0.4074, -0.1319, +0.0434, +0.4359, -0.2658, -0.3302],
+ [+0.2756, -0.2130, -0.2856, -0.1436, -0.4224, +0.1142],
+ [-0.1194, +0.2529, -0.2741, -0.0691, -0.2947, -0.0033],
+ [-0.0449, +0.4437, -0.0389, +0.1377, +0.1102, -0.1049],
+ [+0.4368, +0.1699, +0.3433, -0.4160, -0.3043, +0.1180],
+ [-0.1328, -0.6681, +0.4017, +0.3457, +0.1843, -0.0134],
+ [+0.0630, +0.2032, +0.2331, -0.1384, -0.1024, +0.3183],
+ [+0.1946, +0.1460, -0.1598, -0.2830, +0.2411, +0.3073],
+ [+0.4296, -0.2071, +0.3769, +0.0840, -0.0062, -0.1579],
+ [-0.0790, -0.1186, +0.0962, +0.4871, -0.2901, +0.6272],
+ [-0.2573, +0.3325, +0.1097, -0.2340, -0.0787, +0.1208],
+ [-0.4469, -0.3637, -0.1740, -0.4408, +0.0512, +0.5575],
+ [+0.1426, -0.3975, -0.0685, -0.0452, -0.4517, +0.4320],
+ [-0.5925, +0.3324, -0.1968, -0.2537, +0.6491, -0.2922],
+ [-0.2201, -0.3118, -0.3722, +0.0216, +0.1670, -0.1343],
+ [+0.0638, -0.2374, -0.1480, +0.4090, +0.2347, +0.1456],
+ [-0.0656, +0.1516, -0.3281, -0.2661, +0.0645, +0.0550],
+ [+0.3725, +0.2281, +0.3031, +0.0774, -0.3138, +0.0967],
+ [+0.3016, +0.0322, +0.0556, -0.0571, -0.1177, -0.2442],
+ [-0.2769, -0.5119, -0.0336, -0.1588, +0.0503, -0.2331],
+ [+0.1518, +0.4363, +0.0093, -0.3960, -0.1347, +0.2931],
+ [+0.1897, -0.0655, +0.1977, +0.4321, +0.6998, -0.0863],
+ [+0.0391, -0.0305, +0.3576, -0.4996, -0.0640, -0.0039],
+ [+0.2922, +0.3815, +0.2834, +0.1990, -0.0568, +0.2077],
+ [-0.5371, +0.2796, +0.2952, +0.1182, +0.0523, -0.2151],
+ [-0.5111, +0.2231, -0.1034, +0.0479, -0.0543, +0.0605],
+ [+0.0822, -0.4530, -0.0345, +0.1621, -0.2487, +0.1516]])
+
+weights_final_b = np.array(
+ [+0.1367, +0.1107, -0.0148, +0.1158, -0.0820, +0.3047])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HopperBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HopperBulletEnv_v0_2017may.py
index 367e80299..a58b79411 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HopperBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HopperBulletEnv_v0_2017may.py
@@ -2,285 +2,1889 @@
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], 128)
- assert weights_dense2_w.shape == (128, 64)
- assert weights_final_w.shape == (64, 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 __init__(self, observation_space, action_space):
+ assert weights_dense1_w.shape == (observation_space.shape[0], 128)
+ assert weights_dense2_w.shape == (128, 64)
+ assert weights_final_w.shape == (64, 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 main():
- env = gym.make("HopperBulletEnv-v0")
- env.render(mode="human")
-
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
- env.reset()
- while 1:
- frame = 0
- score = 0
- restart_delay = 0
- #disable rendering during reset, makes loading much faster
- obs = env.reset()
-
- while 1:
- time.sleep(1./60.)
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- score += r
- frame += 1
+ env = gym.make("HopperBulletEnv-v0")
+ env.render(mode="human")
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ env.reset()
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ #disable rendering during reset, makes loading much faster
+ obs = env.reset()
- 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
+ while 1:
+ time.sleep(1. / 60.)
+ a = pi.act(obs)
+ obs, r, done, _ = env.step(a)
+ score += r
+ frame += 1
-weights_dense1_w = np.array([
-[ +0.6734, +1.1364, +0.6117, +0.5185, +0.5099, -0.2038, -0.0045, -0.1448, +0.5081, +1.1685, -0.7904, -0.4623, +0.0027, -0.0473, -0.1144, +0.5095, -0.1913, +0.2021, +0.3485, +0.1104, -0.4992, +0.5207, -0.1013, -0.6947, +0.1624, +0.3533, -0.2485, -0.0012, +0.1674, +0.1253, +1.5485, +0.3576, +0.8236, +0.7361, +0.6604, -0.0834, +0.1212, -0.8404, -0.8337, +0.3709, -0.4218, -0.1011, -1.1418, -0.0554, +0.6676, +0.4739, -0.2105, +0.3187, -0.4321, -0.7018, +0.1845, +0.2525, +0.0205, +0.9391, +0.6123, +0.6868, +0.5116, +0.3483, +0.1148, +0.6747, -0.1590, +0.1879, +0.4836, +0.1997, +0.5105, -0.2695, +0.0645, +0.5566, +0.0502, +0.2292, -0.4234, -0.3778, -0.7639, -0.6084, -0.0375, -0.4799, +0.6465, -0.4097, +0.1091, -0.0681, -0.1813, +0.3625, +0.6067, +0.1837, +0.1600, -0.1706, +0.0531, -0.3710, +0.1320, +0.5035, +0.1106, +0.9955, -0.2657, +0.6051, -0.2525, -0.9118, -0.6031, +0.2025, -0.2774, +0.3985, -0.0809, +0.3601, -0.0410, -0.5067, +0.4987, +0.4126, -0.1393, -0.6596, +0.8182, -0.2352, -0.9337, +0.1438, +0.3871, -0.1844, -0.4010, -0.3338, +0.1597, +0.2381, -0.4403, +0.5105, +1.0354, -0.1503, +0.2731, +0.6555, +0.2048, +0.4932, -0.0067, +0.0413],
-[ -0.0031, -0.2183, +0.2275, -0.4836, +0.1347, +0.3581, +0.0921, +0.1900, -0.1721, +0.0150, -0.2146, +0.5346, +0.2407, -0.0791, +0.5115, -0.0763, +0.2025, +0.2792, +0.4087, +0.2082, +0.0086, -0.2742, +0.3703, +0.4297, -0.3141, -0.3896, +0.4101, -0.3967, -0.2173, -0.0532, +0.2521, +0.3938, -0.3727, +0.6136, +0.0902, -0.4617, -0.3266, -0.2273, +0.0031, +0.4605, +0.1221, +0.3603, -0.1018, +0.1839, +0.3198, -0.1404, -0.1751, -0.1030, -0.5847, +0.2526, -0.1280, +0.1644, +0.2988, -0.1793, -0.2120, +0.3398, -0.4582, +0.0758, -0.2848, -0.1537, -0.2718, -0.2207, +0.0109, +0.1374, -0.0281, -0.0494, -0.0093, +0.0098, +0.2691, +0.1589, +0.2483, +0.1394, +0.2531, +0.3884, +0.0740, -0.4444, +0.1441, +0.0768, +0.2154, +0.4015, -0.2109, -0.0985, -0.1066, -0.0167, -0.0204, -0.2345, +0.3131, +0.1026, +0.1873, +0.2644, +0.2253, -0.0173, +0.1014, +0.0781, +0.0455, -0.0489, -0.3541, -0.1257, -0.1248, +0.4402, -0.0682, -0.3045, +0.1751, +0.0397, -0.3392, -0.2758, +0.1542, -0.0460, -0.0622, +0.2255, +0.2442, +0.2070, +0.3175, -0.0913, -0.2772, +0.7036, -0.0876, +0.0907, +0.3794, +0.4784, -0.5111, +0.0982, -0.0145, +0.0397, -0.3429, -0.2727, -0.1384, +0.0512],
-[ +0.2192, +0.0688, -0.1092, +0.1436, -0.2598, -0.0012, -0.2220, -0.2450, -0.0783, -0.0078, +0.3065, +0.1604, -0.0593, -0.0759, -0.4101, -0.1819, +0.4160, +0.0141, +0.0059, -0.2494, -0.0616, -0.3100, -0.3231, -0.3935, +0.1965, -0.0352, -0.0119, +0.3883, -0.5905, -0.0536, -0.0617, -0.2884, +0.1134, +0.1539, +0.2002, -0.3158, -0.5476, -0.4131, -0.1966, +0.1083, -0.3329, +0.1219, +0.2977, -0.7132, -0.1963, -0.2359, -0.4734, +0.0130, -0.1034, -0.1376, -0.1824, +0.1999, -0.3775, -0.0697, +0.1875, -0.0673, -0.0673, -0.0555, -0.3243, +0.2020, +0.1416, +0.1995, -0.1931, -0.6125, -0.3465, +0.0640, +0.3529, -0.4684, +0.2335, -0.0449, -0.1216, +0.1921, +0.0636, -0.0420, +0.1371, -0.1246, -0.2963, +0.0264, +0.3962, -0.3106, -0.2107, -0.2983, +0.0386, -0.0458, -0.3277, -0.1686, -0.3064, +0.2433, +0.3454, +0.0046, +0.0885, -0.2479, +0.2886, -0.0804, +0.0110, -0.1369, -0.1210, +0.1901, +0.0001, -0.1155, +0.2887, -0.0943, -0.1167, +0.1746, +0.0379, +0.0964, -0.2615, -0.0209, -0.0680, +0.0031, -0.0905, -0.0618, -0.5630, -0.0664, -0.1976, -0.2367, -0.2360, -0.2243, +0.2448, +0.2446, -0.0012, -0.6920, -0.0880, -0.4630, -0.5512, +0.0312, +0.1522, -0.1278],
-[ -0.2378, +0.2783, +0.0848, -0.3973, -0.5359, +0.2541, +0.1616, +0.1856, +0.6054, +0.0894, +0.2599, -0.0082, -0.5433, -0.3567, -0.1134, -0.2706, -0.9177, +0.1949, +0.4099, -0.3198, +0.3856, -0.0285, -0.0692, +0.0882, -0.1052, -0.0122, -0.0271, -0.4122, -0.0921, -0.2014, +0.0314, -0.0638, -0.0986, +0.1912, +0.6157, -0.0856, +0.0450, +0.3492, -0.0958, -0.1261, +0.1242, +0.0930, +0.1372, -0.1914, +0.4377, +0.0586, +0.2271, -0.1985, -0.1012, -0.2074, +0.2934, -0.2271, -0.4235, -0.0077, -0.2304, -1.1012, -0.1832, -0.1528, -0.4307, -0.4059, -0.4289, +0.1290, -0.1688, -0.0446, +0.2036, -0.5397, -0.3280, +0.3672, -0.3012, -0.1896, +0.0923, +0.1472, -0.0703, -0.0328, -0.1597, -0.3102, -0.4221, +0.3261, +0.4840, +0.0083, +0.2617, -0.2548, -0.5314, -0.4192, +0.6303, +0.2605, -0.6675, -0.0837, -0.8402, -0.4546, +0.2169, +0.0480, +0.2543, +0.0004, +0.2982, -0.2037, -0.4812, +0.0583, -0.8738, +0.0586, -0.3745, -0.5477, -0.2971, -0.1551, -0.4880, -0.1060, +0.2188, -0.4043, -0.0349, -0.1349, -0.4093, -0.4371, +0.3101, +0.5219, -0.0655, -0.2546, -0.6408, +0.2019, +0.1351, +0.0971, -0.4105, +0.1299, -0.6688, -0.0550, -0.2388, -0.4246, +0.1126, -0.5573],
-[ +0.3232, -0.0110, -0.0201, -0.2022, +0.1144, -0.2510, -0.3709, +0.4360, -0.4248, +0.1316, -0.5286, -0.0186, +0.2077, +0.2049, +0.2458, -0.3234, -0.0890, +0.2950, +0.0363, +0.0579, -0.0995, +0.1529, -0.0182, -0.2339, +0.0239, -0.3706, +0.2179, +0.1782, +0.1137, +0.3492, -0.1769, +0.1565, +0.2168, -0.0898, +0.4457, +0.4303, +0.3227, +0.1329, -0.0832, +0.0037, -0.1080, -0.1041, +0.0529, +0.2101, -0.1206, +0.1770, -0.1607, -0.2222, -0.3057, +0.0691, -0.1493, -0.1024, +0.1907, +0.0748, +0.3616, -0.5097, -0.4243, +0.1401, -0.4711, -0.4066, -0.4260, -0.3973, -0.3461, +0.2407, +0.1542, -0.3836, -0.2245, -0.0567, +0.3746, -0.3234, +0.4039, +0.0513, -0.1164, +0.3607, -0.1126, +0.0400, +0.2217, +0.1035, +0.0252, -0.1768, -0.4746, -0.3228, -0.3284, -0.0242, +0.0163, -0.2037, +0.0809, -0.0400, -0.0311, +0.3103, -0.1519, +0.0303, +0.3008, +0.1998, -0.1943, +0.2562, +0.5656, -0.0671, +0.3937, +0.4006, +0.3835, -0.0457, +0.5424, +0.2108, -0.0296, -0.1178, -0.0066, -0.5670, -0.1310, +0.2254, +0.0798, +0.0547, -0.0507, -0.2947, +0.0727, -0.4834, +0.0126, +0.2459, +0.2963, +0.2442, +0.1020, +0.0645, +0.6951, -0.4037, -0.1358, +0.4485, -0.1978, -0.0996],
-[ +0.3579, +0.4973, -0.5223, +0.4582, -0.3209, -0.1405, -0.3946, +0.4934, -0.2217, +0.4501, +0.2339, -0.5480, +0.0177, -0.7866, -0.0221, +0.0816, -0.6471, +0.2561, -0.0114, +0.7428, -0.0908, +0.1886, -0.0973, +0.3981, -0.2908, +0.3556, -1.2527, -0.7678, -0.1662, -0.0463, +0.8122, -0.7603, +0.8625, -0.3672, -0.0821, +0.4161, +0.6106, +0.3156, -0.3068, +0.9691, +0.4397, +0.2930, -0.3802, -0.0977, -0.2970, -0.5699, +0.3788, +1.1378, -0.6848, -1.0195, +0.2025, +1.3364, -0.0277, -0.2723, -0.5642, +0.3973, -0.1903, +0.6823, -0.2150, +0.6972, -0.0855, -0.1414, +0.7036, -1.0000, -0.1264, -0.1947, +0.9226, +0.1346, -0.4493, -0.3550, -1.0708, +0.2620, +0.0332, -0.3827, -1.0002, +0.9836, +0.2433, -1.1610, +0.3742, -0.0695, -0.5658, -0.2597, +0.3667, +1.2486, -0.5875, -0.1238, +0.9558, +0.6116, -0.4355, +0.3359, -1.2784, +0.1217, -0.0572, -0.4791, -0.5930, -1.4577, -0.6798, +0.6478, -0.4734, +1.3337, +0.0625, -0.1462, -0.4832, -0.2721, -0.3731, +1.0106, -0.5080, -0.7930, +0.3208, -0.5621, +0.3719, +0.0714, +0.1665, +0.0678, -0.0667, -0.0222, +0.3113, -0.8660, +0.9910, -0.3596, -0.9364, -0.2329, -0.0983, -0.0231, -0.9173, -0.4387, -0.1335, +0.0457],
-[ +0.3956, -0.3152, +0.2209, +0.5020, -0.1946, +0.1046, +0.2062, +0.3388, +0.0394, -0.3347, +0.0989, -0.3360, -0.5885, -0.2084, -0.0802, +0.1041, +0.4200, -0.5033, +0.2403, +0.3485, -0.1897, +0.1247, -0.3015, -0.5448, -0.2833, -0.2345, +0.3037, -0.0964, -0.0418, +0.4569, +0.5159, +0.1612, -0.1066, -0.1735, +0.1562, -0.1419, +0.0397, -0.5056, +0.5741, +0.1335, -0.5054, +0.2876, +0.2772, -0.4229, +0.3375, +0.1689, -0.0673, -0.1658, -0.0537, +0.0839, +0.0286, +0.2321, +0.0324, -0.3339, +0.3598, +0.2639, -0.1830, +0.0786, +0.0150, -0.5155, -0.2999, -0.3272, -0.1231, +0.0314, -0.2119, -0.2094, +0.1294, -0.1965, +0.0588, -0.6383, -0.0198, -0.1309, +0.5456, +0.1369, +0.5467, +0.1478, +0.0873, +0.0337, -0.1971, -0.4118, +0.2234, +0.3570, -0.0030, -0.4428, +0.2950, +0.0275, -0.0361, -0.2056, +0.1671, -0.5099, +0.1179, -0.0046, -0.3599, +0.2915, -0.1620, -0.4229, +0.0425, -0.2419, +0.5708, +0.2975, +0.2598, -0.5877, -0.2703, -0.1468, -0.5714, +0.1464, -0.3119, -0.0598, +0.4885, -0.0556, -0.2712, +0.1269, -0.3214, -0.2681, -0.1313, -0.0982, -0.1379, -0.0300, -0.1540, -0.3185, -0.0519, -0.2397, -0.0479, -0.2774, +0.3924, -0.2064, -0.1053, +0.4871],
-[ -0.1492, +0.3323, -0.4775, -0.5605, -0.8677, +0.7841, +0.7171, +0.8697, +0.2130, +0.4039, +0.9357, -0.8427, +0.0227, +0.2223, -0.4140, -0.7540, -0.2611, +0.5574, +0.2121, -0.3201, +0.0518, +0.3469, +0.3044, +0.6718, +0.4063, +0.9037, +0.2910, -0.5208, +0.2262, +0.5543, -0.1615, -0.2219, -0.7828, +0.0647, +0.2140, +0.9491, +0.0749, +0.2561, +0.2599, -0.2359, +0.4074, -0.2257, +0.0635, +0.1117, +0.5031, -0.2702, -0.0526, +0.1067, -0.1765, +0.0509, +0.2734, -0.2659, -1.0558, -0.3635, +0.4609, +0.0294, -0.6205, +1.3626, -0.1060, +0.2375, -0.4266, +0.6304, -0.9487, -0.2076, +0.3588, -0.2924, +0.2451, +0.5756, -0.1227, +0.1409, -0.2573, +0.8268, -0.3649, +0.7991, -0.2339, -0.2500, -0.2263, +0.0482, +0.9563, -0.2986, +0.5015, +0.2141, -0.3226, +0.3428, +1.1022, +0.3828, -0.1544, +0.4925, -0.0866, +0.2472, -0.0740, -0.0906, +0.6950, +0.4435, -0.2513, +0.0544, +0.1793, +0.9038, +0.3841, -0.3180, -0.2950, +0.0953, +0.4973, -0.3028, -0.0141, +0.0051, +0.9349, +0.0603, -0.1071, +0.2711, +0.0975, +0.6570, +0.1094, +0.1404, +0.9337, -0.2258, -0.5518, +0.0847, +0.8611, +0.0640, -0.3152, +0.3464, -0.2628, +0.2387, -0.1313, -0.3580, +1.7605, -0.7844],
-[ -0.1598, -0.0421, -0.4126, -0.4364, -0.2147, +0.4256, -0.0339, -0.3245, -0.4184, +0.0827, -0.5233, -0.3281, -0.3892, -0.5833, -0.0462, -0.5472, +0.0374, +0.0243, -0.3826, -0.1234, -0.6757, -0.2869, -0.2674, +0.0504, +0.2552, +0.0059, -0.0716, -0.0678, -0.2011, +0.1214, -0.0007, +0.2210, -0.3461, +0.0562, -0.5642, +0.1014, -0.5826, -0.1434, -0.1884, -0.4357, -0.0456, -0.1590, -0.3123, -0.1467, -0.2865, +0.2239, -0.1522, -0.4315, -0.0772, +0.2507, -0.6389, -0.3853, -0.1505, +0.5287, +0.1969, +0.3432, +0.1255, +0.3163, -0.3674, +0.3488, +0.0463, +0.2907, -0.2616, -0.1169, -0.0705, +0.3281, +0.0255, +0.2221, -0.0777, -0.3293, -0.3078, -0.6078, -0.1859, -0.2359, -0.1811, -0.3349, -0.1777, -0.0656, -0.6531, -0.3420, -0.3709, -0.1240, -0.2513, +0.1877, +0.0152, +0.0720, +0.1846, -0.1148, -0.1539, +0.0653, +0.0752, -0.7600, -0.0605, +0.0614, -0.5569, -0.2471, -0.0556, -0.6890, -0.2103, -0.2875, -0.2620, +0.0966, -0.4809, +0.2514, +0.0813, -0.4869, -0.1030, -0.3295, -0.0645, -0.3906, -0.0294, +0.0987, -0.0403, -0.8376, -0.4490, -0.1942, -0.0488, -0.6031, -0.2849, -0.3964, +0.3836, -0.2380, -0.0565, -0.0857, +0.3379, -0.1756, +0.1558, -0.0667],
-[ -0.6008, -0.1594, -1.3237, -0.1536, +1.9008, -0.6173, -0.1694, -0.5906, -0.9055, +0.0241, -0.5906, +1.1458, +0.2310, +0.1497, -0.8268, +0.4505, +1.4660, -0.6533, +0.7903, -0.0505, -0.3790, -0.1951, -0.2461, +0.1151, +1.0092, -0.2464, -0.0728, +1.2368, -0.0530, -0.4323, -0.4228, -0.4808, +0.1259, +0.3584, -0.7628, +0.4720, +0.0326, +0.3357, +0.5799, +0.0110, -0.6230, -0.9810, +0.2532, +0.7874, -0.8300, +0.0061, +0.0040, -0.0170, +0.2485, +0.8276, +0.6964, +0.1540, +0.0615, +0.7226, -0.6115, +0.6827, +0.5075, +1.0073, +0.5858, -0.6826, -0.1033, -0.0188, -0.6122, -0.7580, +0.2348, +1.5513, -0.0221, -0.2869, -0.2070, -0.4511, -0.2812, -1.5290, +1.2652, -0.6644, +0.8840, +0.9897, -0.4561, -0.0053, -1.3338, +0.8146, -0.2168, -0.1642, -0.3823, -0.7818, -0.6392, -0.1877, -0.4944, -0.4896, -0.7634, +0.5820, +0.4216, -0.8257, -0.0432, -0.1807, -0.3475, -0.4825, +1.3182, -1.1372, -1.3308, +0.4233, +0.5569, +0.2234, +0.0889, +0.9940, +0.4986, -1.1977, -0.5440, +1.1946, +0.1312, +0.2419, +0.2770, +0.3172, +0.8566, +0.4982, -1.1142, +0.5097, -0.2901, -0.5129, -0.4256, +0.1067, +0.6052, +0.0384, +0.4465, +0.5017, +0.0892, +0.0556, -0.3456, +0.6560],
-[ +0.3583, +1.0694, +1.0793, +0.1956, +0.9347, -0.1516, +0.2906, -0.0810, +1.0637, +0.6084, -0.5063, -0.0255, +1.2826, +0.2770, -0.5689, +0.2976, +0.7089, +0.1910, -0.3054, +0.9237, -0.8452, +0.5122, -0.0839, -0.9952, -0.5889, +0.8015, +0.0731, -0.2068, +0.3829, +0.3838, +0.4355, +0.2167, +0.3566, -0.2521, +0.9746, -0.8775, +0.1110, -1.1838, -0.8276, -0.4934, -1.3759, -0.0209, -1.5168, -0.3727, +0.1119, +1.3367, +0.4088, +0.3294, -0.5456, +0.2210, +0.6118, +0.2596, -1.0670, +1.3099, +1.0417, +0.9949, +0.8502, +0.9434, -0.2738, +0.4274, +0.4289, +0.2027, +1.1081, +0.1081, +1.6702, +0.4582, +0.2781, -0.2702, -0.3890, -0.4782, -0.3262, -0.6193, +0.4284, -0.8390, +0.1704, -0.8469, -0.1431, +0.8059, +0.0640, -1.1101, +1.0580, +1.1130, +1.0080, -0.0662, +0.9241, -0.1041, +0.1315, -0.4465, +0.2591, +0.2863, +0.1199, -0.2631, +0.3084, +0.8540, +0.2204, -0.7237, -0.2178, +0.6342, -0.0101, +0.5942, -0.5495, +0.3994, +0.5621, -0.2694, +0.9952, +0.0877, +0.0722, +0.6375, -0.4122, -0.2261, +0.2578, -0.1989, +0.4453, +0.0418, -0.6586, -0.0630, +0.1367, +0.0375, -0.3982, +0.6956, +0.4349, +0.7847, +0.9856, -0.2118, -0.1211, +0.2099, +0.6343, -0.2238],
-[ +0.2576, +0.1708, +0.5942, -0.8994, -0.0868, +0.7046, +0.8070, +0.3142, +0.4562, +0.5703, -0.5525, +0.0864, +0.2016, -0.9636, +0.7642, -0.4136, +0.3538, +0.0215, -0.0008, -0.4398, +0.5139, +0.4963, -0.8291, +0.6681, +0.2463, +0.1906, -0.0195, -0.1146, -0.0489, -1.0220, +0.3947, +0.0897, +0.3557, -0.0899, +0.7004, +0.0732, +0.4142, -0.5701, -0.1690, +0.0402, -0.3416, -0.9773, +0.0455, -0.1412, -0.8012, -0.3097, -0.9837, +0.4047, -0.7972, -0.2902, -0.3245, +0.0464, -0.2058, +0.6175, +0.9464, +0.2569, -0.5419, -0.0480, +0.4761, +0.4906, -1.0051, -0.0336, +0.1762, +0.7865, +0.5313, +0.2276, +0.3898, -0.5483, -0.7494, -0.5172, -0.6968, -0.7780, +0.6258, -0.1979, -0.3625, +0.0796, -0.5390, -0.2714, +0.4319, -0.9952, +0.1555, +0.7258, +0.3754, -0.5892, -0.0937, +0.9012, +1.3195, -0.2689, -1.6369, +0.4650, +0.1741, -0.2305, -0.7181, -0.3967, +1.0093, +0.1660, +0.0568, +0.1924, +0.0595, +0.4189, -1.1472, -0.9761, -0.4957, +0.0854, +0.8852, +0.2884, +0.2345, -0.1550, +0.9522, -0.1306, -0.1394, -1.3291, +0.0207, +0.3611, -0.0699, -0.0948, +1.7921, +0.1665, -0.5039, -0.4613, -0.1789, +0.4391, -0.5099, -0.5557, -0.2059, +0.1237, +0.0259, -0.1886],
-[ +0.2817, -0.0454, +0.1386, -0.1673, +0.2426, -0.0467, -0.1203, +0.3156, -0.0052, +0.3391, +0.1706, +0.1125, -0.1778, -0.5539, +0.2748, -0.0129, -0.2321, +0.5550, +0.1019, -0.9796, -0.2074, -1.3227, -0.7212, +0.4632, +0.0566, -0.4680, -0.5681, -0.5756, -1.4594, -0.3052, +0.2753, -0.6632, +0.0368, +0.2291, -0.0578, +0.3663, -0.1122, +0.0024, +0.5366, -0.3653, +0.2721, -0.0873, -0.1185, -0.3832, -0.5141, -0.0425, -0.0007, +0.2201, -0.0954, -0.4895, -0.3387, +0.5406, +0.1037, +0.0756, -0.2258, +0.1772, +0.1323, +0.2892, -0.5137, +0.2084, -0.1640, -0.7629, +0.4224, +0.3344, -0.5014, +0.1077, -0.4575, +0.3734, +0.2012, -0.2691, -0.3532, +0.5112, +0.2323, +0.2361, -0.6075, +0.0756, -0.6252, -0.2803, +0.1436, +0.1922, +0.1045, +0.2936, +0.0511, +0.0997, +0.1260, -0.7201, +0.2040, -0.6068, -0.2572, -1.1220, -0.4336, +0.1953, +0.2289, +0.0583, -0.0825, +0.0174, +0.2520, +0.3962, +0.1735, -0.1254, -0.2769, -0.0927, -0.8869, +0.2688, +0.0637, -0.0104, +0.1743, +0.6607, +0.3604, +0.0411, +0.6830, -0.2192, +0.6120, +0.5902, -0.0692, +0.0640, -0.4776, -0.3384, +0.3360, -0.2106, -0.2018, -0.1111, +0.4084, -1.0131, +0.1918, +0.1225, +0.1328, -0.1810],
-[ -0.5625, +0.6491, -0.2732, +0.4952, -0.1584, +0.2908, -0.6854, -0.4982, -0.0942, -0.2324, +0.2329, +0.3380, +0.4047, +0.8220, +0.1344, +0.2586, -0.2234, +0.1572, -0.5163, +0.5888, +0.3405, -0.3463, +0.9772, +0.1675, -0.6181, +0.4957, +0.6584, -0.1368, -0.1735, +0.4557, +0.6991, -0.0403, +0.2271, +0.2258, +0.2296, -0.0160, -0.4586, -0.4367, +0.5504, +0.5095, -0.0341, +0.4141, +0.0418, -0.2047, +0.3971, +0.3569, +0.6946, +0.1311, +0.3614, -0.0544, +0.7212, +0.0162, +0.0360, -0.3230, +0.4143, -0.2461, +0.1784, -0.2672, -0.7151, +0.0920, +0.2453, -0.1601, -0.1728, +0.0921, +0.3203, +0.1281, +0.7218, -0.2275, +0.6779, -0.4679, +0.2388, -0.2174, +0.1108, -0.2124, +0.1118, +0.1878, +0.6509, -0.2355, -0.3070, -0.1175, -0.8563, +0.7712, +0.7216, +0.2705, -0.3359, +0.0834, +0.3364, -0.9102, -0.0050, -0.2038, -0.3887, -0.0003, +0.3009, +0.5568, +0.4128, -0.1470, -0.4033, +0.4556, -0.0164, +0.6296, -0.6479, -0.6349, -0.4118, -0.1700, +0.5044, +0.6149, +0.5285, +0.2198, -0.5983, +1.1778, +0.1033, -0.1016, +0.5921, -0.3015, -0.4725, -0.1732, -0.0215, +0.7037, +0.5043, -0.7740, -0.4181, -0.1432, +0.4241, +0.5390, -0.8923, +0.8941, -0.2442, -0.1354],
-[ -0.3359, -0.1083, -0.8409, +0.2590, +0.3363, +0.1838, -0.3840, +0.3864, +0.2034, -0.3445, +0.0949, -0.1383, +0.3539, -0.5850, -0.0659, +0.4438, +0.3457, -0.7643, +0.0728, -0.0271, +0.1040, -0.1681, +0.3348, +0.5446, -0.6685, +0.4041, -0.0872, -0.2793, +0.2181, +0.0853, -0.0353, -0.5413, -0.1816, -0.1187, +0.1640, -0.2443, +0.1492, -0.2037, -0.0081, +0.0258, +0.2739, +0.0343, -0.1295, +0.0078, +0.0392, +0.4218, +0.3354, +0.6948, +0.0345, -0.7231, +0.8704, +0.1680, -0.1541, -0.5035, -0.0281, +0.0994, +0.3783, +0.2794, -0.4267, -0.6257, -0.2330, -0.3536, -0.1162, -0.0411, +0.1763, +0.1975, +0.1464, +0.0609, -0.2487, +0.3408, -0.7077, +0.0542, -0.3465, +0.0497, +0.1247, +0.1681, -0.4003, -0.2574, +0.1809, -0.0013, -0.1649, -0.3992, +0.3628, +0.0089, +0.3263, -0.3100, +0.2304, -0.2072, -0.2944, -0.4202, -0.0603, -0.0752, -0.2653, +0.2389, +0.6501, +0.0928, -0.8089, +0.1342, +0.3140, -0.2359, -0.3699, +0.0832, -0.4305, -0.5970, +0.3982, +0.7136, +0.3347, -0.1750, -0.5559, +0.1141, +0.0591, -0.1708, -0.3083, -0.4088, +0.5476, -0.0705, -0.1452, +0.2297, +0.1725, -0.4675, -0.2641, +0.2952, +0.2449, -0.3262, -0.2343, -0.2551, +0.2011, +0.3487]
-])
+ 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_b = np.array([ +0.0032, +0.0591, +0.1871, -0.0873, +0.0194, -0.1684, -0.0091, +0.0135, -0.0694, -0.3312, +0.0673, -0.1489, +0.1365, +0.0575, -0.1155, -0.0904, -0.1321, +0.0492, -0.2257, -0.2418, -0.0204, -0.1910, -0.0512, -0.0482, -0.2969, -0.3574, -0.1852, -0.1644, -0.2957, -0.1906, -0.0170, -0.0760, +0.0006, -0.1286, -0.0746, +0.0039, -0.1005, -0.0535, +0.0375, -0.2162, -0.1251, -0.0368, +0.0101, -0.3220, -0.1152, -0.3656, -0.2491, +0.0638, -0.0312, +0.0054, -0.2318, -0.2900, -0.1189, -0.0725, +0.0490, -0.0679, +0.0117, +0.0926, -0.0824, +0.0479, +0.0756, -0.0462, +0.1529, +0.0081, -0.0984, -0.1227, -0.0247, -0.1277, -0.0633, -0.1953, +0.1023, +0.1582, -0.0400, -0.1115, -0.1625, -0.2216, -0.0195, -0.0650, +0.0701, -0.1573, -0.1187, -0.0801, -0.1424, +0.1873, -0.2309, -0.1815, -0.0408, -0.1173, +0.0185, -0.1408, -0.0938, -0.2810, +0.2447, -0.4046, -0.1790, -0.0165, +0.1334, +0.0500, +0.0283, -0.0321, -0.2388, -0.0726, -0.3444, -0.3250, -0.1338, -0.0579, -0.1647, -0.0691, -0.0835, +0.0734, +0.1667, -0.1478, -0.2212, -0.0899, -0.0050, -0.2379, +0.0709, +0.0464, +0.1569, -0.2669, -0.2181, -0.4331, +0.0534, -0.0648, -0.1026, -0.1509, -0.2278, -0.0437])
-weights_dense2_w = np.array([
-[ -0.5294, -0.0896, +0.1998, -1.0655, -1.0578, -0.2702, +0.0052, +0.1819, -0.2272, -1.3830, +0.0185, +0.0236, +0.0611, +0.3201, -0.1723, +0.2887, -0.4885, +0.3460, -0.0437, -0.4517, +0.1636, +0.0027, -0.5574, -0.4712, -0.2482, +0.1202, +0.6143, -0.6510, -0.5672, -0.7578, -0.2628, -0.5118, +0.2114, +0.3419, +0.3262, -0.1558, +0.4818, -0.4314, -0.4611, -0.3294, +0.2443, -0.4138, +0.2451, -0.2765, -0.4818, +0.0854, -0.0011, +0.0080, -0.3759, -0.1235, -0.2526, +0.3319, -0.7957, -0.3891, +0.6225, +0.7334, -0.3936, -0.2982, +0.2974, -0.2766, +0.0199, -1.0206, -0.4054, -0.0960],
-[ -0.5329, -0.7876, -0.4974, +0.3381, +0.3092, +0.0208, -0.2402, -0.3306, -0.7425, +0.1489, +0.0271, -0.1945, +0.0315, +0.1836, +0.2294, -0.6615, -0.1362, +0.2090, -0.5984, -0.0163, +0.0886, +0.0679, +0.3041, -0.0070, -0.0550, +0.3623, -0.0483, -0.2679, +0.2927, +0.2728, +0.2955, -0.0641, +0.2888, +0.0278, +0.1980, +0.0714, +0.1605, +0.1879, +0.0666, -0.0505, +0.3625, +0.3155, -0.1965, -0.0301, +0.1697, -0.0102, -0.4709, -0.4190, +0.0265, -1.0402, -0.0718, +0.3172, -0.1062, -0.2538, -0.4556, -0.2825, -0.0534, -0.1540, +0.0872, +0.1585, -0.4927, -0.0311, +0.2163, -0.8230],
-[ -0.0620, -0.4689, -0.0407, -1.5569, -0.1551, -0.2028, -0.3836, -0.0306, -0.0718, -0.9097, -0.1025, +0.1040, +0.1657, +0.1093, -0.2807, +0.3353, -0.6893, +0.6661, +0.1312, -0.8763, -1.5289, -1.4383, +0.1129, +0.2337, -0.0876, -0.8757, +0.0550, -0.3456, +0.1468, -0.6056, -0.8811, -0.3539, +0.6850, +0.1739, +0.0344, -0.0354, -0.2883, -0.1680, -0.3950, -0.7221, -1.8289, -0.2404, -0.2498, +0.1401, +0.3679, -0.1029, -0.2085, -0.9932, -0.1101, -0.4335, -0.1423, -0.3566, -0.4630, +0.1845, +0.3527, -0.4799, -1.7876, +0.3755, +0.2791, +0.1744, -0.3218, -0.4807, -0.2936, +0.2639],
-[ -0.1966, +0.5649, -0.2069, +0.3588, -0.8745, +0.8721, +0.0814, +0.1852, +0.1873, -0.0432, -0.7933, -0.2585, -0.1218, -0.4980, +0.3300, +0.3064, -1.0648, -0.6760, +0.0998, +0.6166, -0.2364, +0.0741, -1.5132, -1.1618, -0.0384, +0.1799, -0.5393, +0.2645, -0.2358, +0.0418, +0.3921, -0.8185, +0.5272, +0.4155, -0.2473, +0.0026, -0.4362, -0.1113, -0.1036, -1.0282, -0.2206, +0.5201, -0.1124, +0.3642, +0.0213, +0.1247, +0.0868, +0.3541, -0.0376, -0.0735, +0.4899, -0.5098, -0.7578, -0.3030, +0.2886, -0.7427, -0.4035, +0.0161, -0.4715, +0.0235, +0.5217, -0.2785, +0.0707, -0.2289],
-[ -0.7238, +0.4670, -0.0149, +0.2279, -0.1295, +0.0670, -0.2468, +0.4984, +0.6797, +0.2095, -0.2371, -1.1373, -0.0913, -0.6137, -0.1067, +0.0817, -0.4967, -0.3839, -0.0531, -0.3020, -0.2330, -0.1719, -0.2915, -0.3750, -0.1896, -0.0480, -0.2671, +0.5401, -0.0648, -0.8036, +0.2070, -0.9393, +0.1914, +0.2418, -0.0981, -0.4760, -0.0516, -0.8327, +0.1371, -0.7785, -0.1945, -0.6666, -0.0209, +0.0864, -0.7345, -0.3576, -0.2442, +0.3027, -0.4184, +0.2634, +0.2169, +1.1403, -0.4589, +0.0943, -0.0657, -0.2680, -0.6890, -1.2024, -0.2191, -0.1494, -0.0415, -0.9274, +0.3765, +0.2284],
-[ +0.0721, +0.2423, +0.2696, -0.8249, -0.0644, -0.3427, -0.2876, -0.2066, +0.2195, +0.1008, +0.1247, +0.2757, -0.1372, -0.0132, +0.1199, -0.1206, +0.1263, +0.0607, -0.1235, -0.3237, +0.5096, -0.0538, +0.4292, -0.2570, -0.2744, -0.1671, +0.0643, +0.2648, -0.1993, +0.0420, +0.1681, +0.3126, -0.3654, -0.2719, +0.3103, +0.2754, +0.0040, -0.4387, -0.0634, +0.2868, +0.0613, -0.1423, +0.0911, -0.6027, -0.2560, -0.0131, -0.5504, -0.6812, +0.0176, +0.1782, -0.0082, -0.2754, +0.1471, +0.2872, -0.5940, +0.1319, +0.0220, +0.3727, +0.2380, +0.0558, +0.1206, +0.2882, +0.0155, +0.2597],
-[ -0.1229, -0.7953, -0.2690, -0.8715, -0.8578, +0.0133, +0.2098, -0.0996, -0.0174, +0.5429, -0.3021, -0.1241, +0.0091, -1.2123, +0.0488, -0.4687, -0.6124, -0.7139, -0.2042, -0.4138, -0.3101, -0.1909, +0.1478, -0.5427, -0.2557, -0.1813, +0.4605, -0.6159, -0.1311, -0.3425, -0.9877, -1.2896, -0.4583, +0.2293, -1.0717, +0.0631, +0.0908, -0.1255, -0.8500, +0.0157, +0.1026, -0.6678, -0.4511, -0.1720, -0.1051, -0.0788, -1.1285, -0.7684, -0.5400, -0.0879, -1.3907, +0.8072, +0.3826, +0.5732, -0.6696, +0.3482, -0.2598, -0.9451, +0.0000, +0.1565, -0.9628, -0.5438, -0.2299, +0.0864],
-[ -0.3683, +0.2445, -0.6280, -0.6619, -0.3666, -0.4500, -0.5599, -0.6186, +0.0152, -0.2720, +0.0609, -0.3384, -0.0136, +0.1575, +0.3848, -0.5577, +0.7921, -0.4193, +0.0182, +0.3805, +0.0310, +0.2653, -0.0866, +0.3095, -0.2329, -0.1241, +0.1641, -0.2871, +0.0675, -0.2960, +0.1917, -0.3727, +0.0599, +0.4283, -0.7127, -0.0708, -0.0144, +0.3581, -0.7382, -0.1784, -0.3748, -0.1627, -0.5114, -0.2711, +0.0602, -0.2263, -0.1847, -0.1914, -0.2189, -0.3361, +0.0516, -1.3228, +0.0331, +0.3685, +0.2941, -0.4427, +0.2907, -0.7059, -0.1141, -0.0540, +0.0532, -0.1200, +0.0966, -0.0749],
-[ -1.1537, -0.0967, -0.3476, -0.2341, +0.5311, -0.1617, -0.3381, +0.1348, +0.2100, -1.0730, -0.0577, -0.0237, -0.0373, -0.5123, +0.2998, -0.3247, +0.5258, +0.3037, -0.0538, +0.3679, -0.3760, +0.0351, +0.5999, +0.4626, -0.1599, -1.1580, -0.1344, +0.6217, -0.2474, -0.6322, -0.7804, -0.2596, +0.6680, -0.1191, -0.0805, +0.2087, -0.1946, -0.2961, -0.2653, -0.1915, +0.1113, -0.6597, +0.0847, -0.0599, +0.6311, -0.8174, -0.8733, -0.5911, +0.1962, -0.1327, -0.1959, +0.7040, +0.6005, +0.1157, -0.4948, -0.5988, +0.4162, -0.3101, +0.0050, +0.6379, +0.0811, -0.0415, +0.2975, +0.4097],
-[ -0.0605, -1.4543, +0.3715, +0.0582, -0.1646, +0.0919, -0.8151, -0.0222, -0.5294, -0.4140, -0.4782, -0.0889, -0.2930, -0.7260, -0.1270, -0.2699, -0.2068, -0.4855, -0.0244, +0.5308, +0.2588, +0.0277, +0.1398, -0.0020, -0.0209, +0.4305, +0.5735, -0.4727, -0.1810, -0.1060, +0.1201, +0.2439, -0.2472, -0.0717, +0.1351, +0.3603, +0.3060, -0.3795, -0.2812, -0.2544, +0.1106, -0.0701, +0.2985, -0.1396, -0.2122, +0.4243, -0.2770, -0.5565, -0.2525, +0.0816, -0.4047, -0.2782, -0.7214, -0.1042, -0.1084, +0.1894, +0.8661, -0.1578, +0.3679, +0.2941, +0.0799, -0.3008, -0.1891, -0.4522],
-[ -0.1581, -0.8760, -0.6871, +0.1299, -0.4920, -0.2449, +0.2764, -1.4836, -0.7051, +0.3574, -0.2647, -0.2578, -0.0707, +0.1505, -0.0393, -0.5107, +0.0504, +0.2922, -0.1558, +0.0842, -0.0566, +0.0806, +0.2948, +0.1275, +0.0113, +0.0670, +0.5678, +0.0579, -0.0082, -0.0575, +0.2882, +0.0579, +0.1669, -0.5888, -0.1277, -0.1875, -0.2031, +0.2563, -0.4510, +0.1176, -0.6062, +0.0932, -0.4625, +0.0489, -0.4213, +0.1625, +0.0889, +0.3401, -0.4626, -0.1120, -0.3998, -0.3627, +0.5388, +0.3221, +0.0293, +0.4626, -0.4754, -0.7499, -0.5847, -0.3559, +0.3759, +0.6087, -0.6434, -0.3520],
-[ +0.2500, +0.1920, -0.0041, +0.3031, +0.1244, +0.2579, -0.3249, +0.6266, +0.0798, -0.6341, +0.1762, -0.0811, -0.2604, -0.4294, -0.1638, -0.0724, -0.2681, -0.0688, -0.1879, +0.4750, +0.4832, +0.2947, +0.2664, +0.2740, -0.0683, +0.2160, -0.1307, +0.1062, +0.0801, -1.2182, +0.3045, +0.1882, -0.0800, -0.3235, -0.5861, -0.2444, -0.0772, +0.1528, -0.1473, +0.0380, -0.0192, -0.1198, +0.1908, -0.5856, -0.3644, -0.0235, +0.4902, -0.6515, -0.3490, +0.0620, +0.2643, +0.1549, -0.0580, -0.1879, +0.1547, -0.5689, +0.2646, +0.2184, -0.1865, -0.6921, +0.3484, -0.0395, -0.0506, +0.0883],
-[ +0.3222, -0.6081, -0.8570, +0.1662, -1.6457, -0.1301, +0.4362, -0.3683, -1.2053, +0.0051, +0.4562, +0.1176, +0.0681, +0.0442, +0.0929, -0.1070, +0.0833, -0.9221, -0.1152, -1.3000, +0.1766, +0.5323, -1.3052, -0.8361, -0.1032, +0.1584, -0.3473, -0.1487, -0.5833, -0.0997, -0.1513, +0.0293, +0.3824, -0.0470, -0.3443, -0.4211, -0.2198, -0.0394, -0.7857, +0.6342, -0.0022, -0.2827, -1.2328, +0.8836, -0.1748, +0.0327, -0.2512, -0.3752, -0.1145, -0.8466, -0.6688, -0.2503, +0.0641, -0.0112, -0.5286, -0.6550, -0.8791, +0.1105, -0.4148, +0.6753, +0.4758, -0.0569, +0.0966, -0.9476],
-[ -0.4199, -0.6072, -0.4537, -0.4169, -0.8892, +0.2855, +0.5756, -0.0186, -0.5130, -0.1059, -0.7573, -0.0568, -0.0684, -0.6527, -0.0938, -0.0042, -0.3279, -0.4445, +0.0217, +0.0967, -0.7654, -0.2576, -1.3607, -0.5645, +0.1616, +0.0616, -0.7005, -0.2452, +0.2257, -0.5849, +0.6963, -1.0530, -1.3240, -0.1119, -0.9036, -0.0479, -0.4890, +0.5005, -1.4962, +0.2961, -1.2472, -0.2179, +0.0196, +0.5316, -0.0054, -0.0947, -0.6427, -0.0188, -0.4429, +0.5082, -0.0946, -0.4850, +0.3228, +0.1117, +0.3974, +0.0178, -0.0763, -1.3113, -0.5316, +0.0163, -0.2001, -0.2488, +0.3841, -0.1722],
-[ -0.1212, -0.3952, +0.0911, -0.5135, -0.2093, -0.7678, +0.1495, +0.0407, +0.3257, +0.0601, -0.2006, +0.3888, -0.1896, +0.1708, -0.2838, -0.6900, +0.0937, +0.2306, +0.0376, -0.3426, -0.2854, -0.3829, +0.4875, +0.0551, +0.0143, -0.2186, +0.0469, -0.8389, -0.7003, +0.2505, -0.5086, +0.1452, -0.3577, -0.5950, -0.1434, -0.3216, -0.7059, +0.1497, -0.1612, +0.4857, -0.2867, -0.1537, -0.2302, -0.6386, +0.3762, +0.2766, +0.1610, -0.6457, +0.4320, -0.3433, +0.0201, -0.1067, +0.2527, +0.2581, -0.0995, -0.1953, -0.0237, +0.8414, +0.4549, -0.1515, -0.1875, -0.1065, -0.2381, -0.4321],
-[ -0.3393, -0.3520, -0.9045, +0.6000, +0.5172, -0.1926, -0.1635, +0.1719, -0.6527, +0.2668, +0.3255, -0.0443, +0.0438, -0.4045, -0.2399, -0.4114, -0.7029, -0.0357, -0.4091, -0.0354, -0.1053, +0.0729, -0.6477, -0.2433, -0.0480, +0.2689, +0.2895, +0.0905, -0.3754, -0.9434, +0.5497, -0.0091, +0.2105, -0.1584, +0.0904, -0.3422, +0.2668, -0.1983, +0.4242, -0.2503, -0.4326, -0.3479, -0.4545, +0.8625, -0.3452, +0.6519, +0.1031, +0.3487, -0.3660, -0.0598, +0.2381, +0.8141, -0.2223, -0.1759, -0.0212, -0.0058, -0.2119, +0.0731, -0.0786, -0.3202, -0.2608, -0.7982, +0.4981, +0.1286],
-[ -0.5110, +0.3147, +0.1463, -0.0389, -0.3521, +0.3138, -0.4345, -0.1397, +0.4069, +0.4113, -0.1701, +0.0171, -0.0710, -0.0741, -0.1748, +0.1410, +0.1965, -0.9863, -0.1121, +0.2325, -0.0745, +0.0503, -0.3608, -1.0871, -0.1174, +0.2476, -1.4639, +0.1530, +0.3929, +0.2179, -0.1187, -0.2966, -0.0866, +0.1865, -0.9683, -0.2727, -0.0255, -0.4145, +0.1239, -0.0952, -0.0126, +0.2078, +0.0525, -1.2549, -0.4354, -0.1329, -0.1288, -0.0279, -0.1269, +0.0084, +0.4687, +0.1488, -0.3704, +0.3366, +0.1487, -0.7377, -0.4681, -0.2716, -0.2919, +0.0930, -0.2879, -0.4733, -0.1250, +0.3180],
-[ -0.2212, -0.1165, +0.0573, -0.0257, +0.4105, -0.3042, -0.2197, +0.1105, -0.0834, -0.3845, +0.0174, +0.0070, +0.0297, +0.0073, -0.5144, +0.3017, +0.1921, +0.4018, -0.2265, -0.2572, +0.2103, -0.5301, -0.0210, +0.7838, +0.1188, +0.0774, +0.4195, -0.8113, +0.3870, +0.2450, -0.8158, +0.7872, +0.0218, +0.1636, -0.1837, +0.0628, +0.4486, -0.0948, +0.1513, -0.8843, -0.5782, -0.1950, +0.2832, -0.2192, +0.6143, -0.0574, +0.2811, -0.4833, +0.1312, +0.2647, -0.0071, +0.3059, -0.0858, -0.6766, +0.1089, +0.3099, -0.2368, +0.2549, +0.4027, -0.1061, -1.1896, -0.6198, -0.3528, +0.1676],
-[ +0.0035, -0.4849, -0.7783, -0.0504, +0.2348, -0.0571, +0.4417, +0.0601, -0.8799, +0.1450, -0.0952, -0.3266, +0.0411, -0.7422, +0.0060, -0.2092, -0.1885, -1.2113, -0.0374, +0.0568, +0.1130, -0.0895, +0.0957, +0.1047, +0.1396, -0.0320, -0.2089, +0.1098, -0.4008, +0.0389, +0.0482, -0.2914, -0.9251, +0.4323, +0.1206, +0.0567, +0.0699, +0.0587, +0.0422, +0.2053, +0.0602, -0.7918, +0.1464, +0.3530, -1.2250, -0.2547, +0.3194, -0.8625, -0.4735, +0.4783, +0.0043, +0.1931, +0.1671, +0.0328, -0.0747, +0.6361, +0.2269, -0.5492, +0.1361, -0.1751, -0.0100, -0.2549, -1.0106, -0.9024],
-[ +0.2591, -1.0195, -0.4721, -0.9731, +0.0299, +0.2645, +0.3216, -0.1474, -0.4643, -0.0471, -0.2468, +0.2281, +0.0187, -0.0859, +0.0399, +0.0137, -0.4151, -0.7058, -0.4788, +0.3670, -0.3171, -0.5478, -0.3702, -0.2157, +0.0541, -1.3574, -0.5394, -0.1754, +0.4716, -0.3429, +0.6257, -0.6191, -0.0252, -0.3959, +0.5052, +0.1172, -0.0161, +0.0461, -0.3518, -0.6841, +0.0599, +0.7104, -1.4835, +0.2076, -0.3105, -0.2433, -0.0676, +0.2361, +0.1693, -0.5076, -0.1233, -0.1134, -0.2816, -0.5818, +0.0513, -0.9941, +0.4563, -0.2065, -0.7186, -0.5165, -0.6421, -0.1892, +0.1439, -0.2584],
-[ +0.0525, +0.2656, -0.3646, -0.8030, -0.2153, -0.0913, -0.3868, +0.3407, -0.1766, +0.4419, -0.3384, +0.2972, -0.0482, +0.2394, +0.2429, -0.1640, +0.4954, -0.0242, -0.5130, +0.2863, +0.6940, +0.1821, +0.3729, -0.3485, -0.2009, +0.4411, +0.0800, +0.1678, -0.6286, -0.4632, -0.0660, +0.1633, -0.7075, -0.4767, +0.0660, +0.3576, -0.1382, +0.4100, -0.1458, +0.2652, +0.0179, -0.2446, -0.6880, -0.2835, -0.6586, +0.3138, -0.0370, -0.5427, -0.0139, +0.0475, +0.0476, +0.2838, +0.1937, +0.0958, -0.6775, -0.0984, -0.4858, +0.2718, +0.0920, -0.1442, -0.3254, +0.4006, +0.3794, -0.1053],
-[ -0.7993, +0.2057, -0.0825, -0.5901, +0.4015, +0.7778, +0.2741, +0.3809, -0.0990, -0.1496, +0.4271, +0.2286, +0.1506, -0.0415, +0.5997, -0.6465, +0.0393, +0.3040, +0.2443, -0.2178, -1.3364, -0.4051, +0.3383, -0.0159, +0.1492, +0.0452, -0.1428, -0.2160, +0.2785, +0.6410, -0.6244, +0.3319, -0.4489, -0.1197, -1.1882, +0.3110, +0.5941, +0.1675, +0.2606, -0.9117, +0.3474, -0.4273, +0.6581, -0.0334, -0.5226, -1.0439, -2.6607, -0.2681, +0.5722, -0.1204, -0.8560, -0.5789, -0.4583, +0.1208, -1.2444, -0.3378, -0.9704, -0.0412, +0.1563, -0.1445, -1.2344, -0.5351, -0.2627, -0.0315],
-[ -0.2311, +0.0027, -0.9287, -0.1228, -0.8419, +0.1478, -0.3367, -0.2493, -0.1044, -0.0661, -0.5176, +0.1812, -0.1505, +0.3252, +0.0689, -0.1895, -0.6359, +0.3539, +0.0074, +0.2096, -0.1721, -0.6680, -0.1181, +0.0884, -0.1903, -0.3968, +0.2160, -0.8183, -0.1148, -0.5661, +0.1892, -1.3805, +0.4477, -0.0261, +0.0525, +0.2808, -0.5591, +0.5135, -0.3758, +0.1060, +0.6081, -0.3552, -1.2404, +0.0532, +0.2700, +0.0979, -0.6299, -0.0514, +0.3286, +0.1688, -0.4352, -0.8093, -0.0033, +0.2607, +0.2893, -0.3395, -0.5950, +0.0470, -0.4043, -0.8434, -0.4925, -0.6462, -0.3282, -0.0198],
-[ +0.3055, +0.4763, +0.3049, -0.9238, +0.2499, -0.8889, +0.0817, +0.1527, +0.3570, -1.2277, +0.5060, +0.5231, -0.0977, +0.7970, -0.3972, -0.0988, +0.7831, -0.4279, +0.0235, +0.3373, +0.6341, +0.2142, -0.1506, +0.6003, -0.3704, -0.0476, +0.2141, -0.4490, -0.3270, -0.4279, -0.2669, +1.0325, -0.7446, -0.5226, +0.2484, -0.3719, +0.0762, -0.2644, +0.4603, +0.3430, +0.0474, +0.0505, -0.0625, -0.1566, -1.0823, +0.0666, +0.1685, -1.7572, +0.5213, -0.0229, +0.4925, -0.9132, +0.2729, -0.0375, -0.0308, -0.0809, -0.0612, +0.5318, -0.3841, -0.3973, +0.0513, +0.3254, +0.0226, +0.0897],
-[ -0.4901, +0.4057, +0.4243, -0.1017, -0.5561, +0.0413, -0.1884, +0.0115, +0.3556, +0.4905, +0.4599, +0.3225, -0.2060, -1.0437, -0.1747, +0.4379, -0.2705, -0.4107, -0.2775, +0.2060, +0.1902, +0.1741, -0.0650, -0.7355, -0.0770, -0.1194, -0.3411, -0.3670, -0.3807, +0.3297, -0.3163, +0.2963, +0.5599, +0.6562, -0.2402, -0.0244, +0.2263, -0.0590, +0.2397, +0.4873, +0.0771, +0.5808, +0.4708, -0.1900, -0.6152, +0.4273, +0.5762, -0.3754, -0.2344, +0.3123, -0.1155, -0.3437, -1.0409, -0.1489, -0.1104, +0.3270, +0.3800, +0.3680, +0.2113, -0.5376, +0.1063, +0.0841, -0.5439, -0.1957],
-[ -1.9974, -0.0211, -0.2446, -0.3544, -0.7249, -0.3924, -0.5035, -0.2175, -0.1627, -0.8428, -0.1119, -0.0274, -0.0418, -0.1262, +0.3002, -0.1632, -0.2389, +0.3389, +0.0569, +0.0202, -1.0143, +0.3537, -0.1440, +0.3140, -0.1313, -0.3848, +0.7528, -0.6598, -1.0451, +0.5417, -0.0634, +0.1701, -0.6359, +0.3913, +0.9036, +0.8082, -0.6004, -0.0083, -0.8911, -0.0479, +0.1066, -0.4130, +0.2471, +0.5112, +0.3424, +0.2349, +0.2216, -0.1641, +0.0944, -0.3781, -0.2863, +0.2887, -0.1032, +0.2387, +0.1109, -0.1010, +0.6019, -0.6929, -1.1630, +0.1658, -0.0167, -0.2142, +0.3414, -0.6920],
-[ +0.6931, +0.0145, +0.3552, -0.1500, -0.6177, +0.2065, +0.1103, -0.1340, +0.5208, +0.3153, -0.4249, +0.2061, -0.1484, -0.2901, +0.2288, -0.3281, -1.4010, -0.6546, -0.0633, +0.1697, -0.6311, -0.4404, -0.1730, -0.9839, -0.0577, +0.3237, -0.0267, -0.2236, +0.3860, +0.3659, +0.2307, +0.5690, -1.0721, -1.0289, +0.3124, -0.4391, -1.4334, +0.3776, -0.7681, -0.3304, +0.0015, +0.0868, -2.1094, -1.2462, +0.0804, +0.1231, -0.2476, -0.5150, -0.3384, -0.1315, -0.3313, +0.2172, +0.3345, +0.0750, +0.0769, +0.7963, -0.0705, +0.0998, +0.0840, -0.3474, -0.0533, +0.1124, -0.0993, -0.2206],
-[ +0.0738, +0.4493, +0.0851, -0.2606, -0.4232, +0.1632, +0.0389, +0.0128, +0.3265, -0.1896, +0.3890, +0.2983, -0.1198, -1.0363, -0.0076, +0.2032, -0.7419, -1.0515, -0.1930, -0.0945, -0.0872, -0.1580, -0.2602, -1.4956, -0.1525, +0.4170, -0.9875, +0.3425, +0.3709, +0.1006, +0.0766, +0.0740, -0.3491, +0.1276, -0.2520, -0.0348, -0.6866, +0.0363, +0.4659, -0.2804, -0.3475, -0.1448, +0.0616, -0.8020, -0.2784, +0.2680, +0.3337, -0.0333, -0.5948, +0.4099, +0.2169, -0.4844, -0.6288, -0.1061, +0.1890, -0.2980, +0.0414, +0.2023, +0.0107, -0.6235, -0.0916, -0.2670, -0.2182, -0.4410],
-[ +0.3507, +0.5252, -0.1627, -1.4898, +0.2313, +0.5587, +0.2386, +0.3379, +0.0982, +0.0413, +0.3709, +0.4906, +0.0007, -0.4149, +0.4735, -0.1098, -0.5601, +0.2028, +0.3657, -0.4582, -1.6526, -0.4622, +0.3676, -0.5300, +0.1754, +0.0149, +0.1038, -0.2189, +0.1419, +0.4394, -0.3616, +0.2069, -0.7841, -0.3796, -0.7757, +0.5907, +0.1856, +0.1489, +0.4881, -1.1035, +0.0189, -0.1605, +0.6046, -0.6840, -0.5543, -0.0317, -1.1382, +0.0052, +0.3898, +0.5780, -0.1522, -0.3236, -0.4997, +0.1208, +0.3768, +0.5135, -0.2755, -0.1092, +0.2018, -0.2345, -1.4905, -0.1996, -0.2652, -0.1369],
-[ -0.0105, +0.5400, +0.0687, +0.3213, -0.9347, +0.3641, -0.1674, -0.4105, +0.1847, -0.2406, -0.4423, -0.6186, -0.1456, -0.2169, +0.3144, -0.1460, +0.1520, +0.2036, +0.1390, +0.0801, -0.5625, -0.1819, -0.3711, -0.2140, -0.2649, -0.0028, +0.4067, -0.8796, -0.1423, -0.3487, -0.1759, -0.5259, -0.4894, +0.2141, -0.0896, +0.6119, +0.2727, +0.4561, -0.0039, -0.5774, -0.9105, -0.0751, +0.9462, +0.2550, +0.2783, -0.2219, -0.1080, -0.2208, -0.6883, +0.1096, -0.7935, -0.3954, +0.1652, +0.1019, -0.4601, +0.4553, -0.6417, -0.1358, -0.4737, +0.3128, -0.3267, -0.0540, -0.0633, +0.0747],
-[ -0.2253, -1.2597, -0.2355, +0.7981, +0.4423, -0.6973, +0.1781, -0.4507, -0.4586, -0.6728, -0.0542, -0.9978, -0.0401, -0.1790, +0.0617, -1.1232, -0.1113, +0.1408, +0.1287, -0.2249, +0.2728, +0.4372, +0.1111, +0.0541, +0.0471, +0.6102, -0.1691, +0.0115, +0.4568, +0.0321, -0.8153, -0.2889, +0.2773, -0.3295, +0.4547, +0.0681, +0.3247, +0.0053, -0.2419, -0.1754, +0.4957, -0.6494, -0.1602, -0.1358, +0.2751, -1.3709, -0.3958, -1.4701, -0.0427, -1.6050, -0.3034, +0.2151, -0.6053, -1.0677, -0.5643, -0.7845, +0.3169, -0.8565, -0.3574, +0.2891, +0.1122, -0.2884, +0.0601, -0.4517],
-[ +0.5794, +0.2631, +0.0298, -0.1887, -0.6058, +0.4974, +0.0394, +0.2606, -0.0979, +0.2046, -0.1194, +0.2263, -0.2702, -0.1877, +0.2569, -0.2315, -0.9000, -0.3146, -0.0264, +0.4439, -0.2352, -0.9247, +0.1092, -0.2865, +0.1680, +0.1662, -0.0617, +0.2461, +0.3578, +0.3580, +0.0366, +0.3635, -0.5039, -0.2711, +0.0653, +0.0065, -1.0248, -0.0090, +0.2204, -0.5041, -0.0247, -0.2344, -0.6278, -0.8120, -0.0303, +0.3207, -0.2989, +0.1933, -0.1498, +0.0319, +0.1813, -0.8244, -0.5803, +0.2969, +0.0516, -0.7916, +0.2017, +0.0585, +0.1980, -0.1696, +0.3148, +0.1424, -1.3858, -0.2667],
-[ -0.1941, -0.6240, -2.0568, -0.4370, -0.2328, -0.0722, +0.1253, +0.2146, -0.3976, +0.1229, -0.1581, -0.0012, +0.1981, -0.0432, +0.3407, -0.6734, +0.3886, +0.6251, -0.5550, -0.1302, +0.4913, +0.2797, -0.5856, -0.5146, +0.0478, -0.3227, -1.5350, -0.0298, -0.0659, +0.3368, +0.3931, -0.0328, -0.9625, -0.2308, +0.2069, -0.8179, -0.0210, -0.2816, -0.0345, -1.0297, +0.2480, +0.3974, -0.8667, +0.1481, +0.3191, +0.2165, -0.3631, -0.5387, -0.0522, -0.0564, +0.2433, +0.3049, -1.3699, -0.0584, -0.2832, -0.6592, +0.0884, -0.2148, +0.0559, -0.9336, -0.2033, -0.4094, +0.3269, -0.4964],
-[ +0.0753, +0.1742, +0.0289, +0.2070, +0.1448, -0.2884, -0.3095, +0.1798, +0.0199, -0.2820, +0.1938, -0.3718, -0.3645, -0.3529, -0.3720, -0.0512, +0.0513, +0.2669, -0.2589, +0.1347, -0.1360, +0.0911, +0.3276, +0.1716, -0.2404, +0.1529, +0.1362, -0.5175, -0.2299, -0.7689, -0.3936, +0.5067, +0.1310, -0.1135, -0.3412, +0.1108, +0.1786, +0.0673, -0.0204, -0.3017, -0.2068, -0.0664, +0.4354, -0.2405, -0.2007, -0.0767, +0.2006, -0.2971, -0.1813, +0.1541, +0.2968, -0.1119, +0.0695, -0.1098, -0.1175, +0.0256, -0.3372, +0.1161, -0.0643, -0.0223, -0.1124, +0.0984, -0.2127, +0.2459],
-[ -1.0418, -0.7575, -0.4414, -0.7391, +0.5002, -0.1492, -0.4713, -0.9001, -0.1078, -0.1626, +0.1688, -0.3508, -0.0691, +0.0143, +0.4832, -0.5588, +0.1924, +0.2538, -0.1200, -0.0766, -0.5754, -0.1720, +0.6831, -0.3890, -0.0020, -0.6173, +0.5652, -0.2394, +0.5254, +0.6080, -0.6162, -1.4693, +0.4980, +0.4190, +0.0770, +0.7358, -0.1511, -0.4138, -0.0947, +0.1821, +0.0477, -0.9686, -0.0194, -0.2626, +0.6581, -0.2775, -0.4984, -0.2816, +0.4898, -0.7165, -0.2212, +0.3316, +0.3437, -0.3604, -1.0851, -1.0551, -0.5356, -0.8371, +0.0848, -0.4796, -0.3950, +0.3524, +0.6147, +0.0963],
-[ -0.1117, +0.0358, +0.3472, -0.1657, -0.6318, -0.5969, +0.4199, -0.1558, +0.0856, -0.3948, -0.8222, -0.4227, -0.0461, -0.0458, -0.4246, -0.1711, -0.0217, +0.0392, -0.2153, +0.5657, +0.5179, +0.1690, -1.1408, -0.8345, -0.0868, +0.5821, +0.0440, -0.6810, -0.2952, +0.3344, +0.1719, -0.2792, -0.0611, -0.4510, -0.2232, -1.1814, -0.3142, +0.1828, -0.1726, -0.0683, +0.0175, +0.4286, -0.1024, +0.0233, -1.0238, +0.4454, +0.2450, +0.1602, -0.6960, -0.7975, -0.1214, -0.0340, -0.4455, +0.1809, -0.8249, +0.1098, -0.5579, +0.3200, +0.1753, -0.1689, +0.0027, +0.0572, +0.0126, -0.2266],
-[ -0.1541, +0.2923, -0.2675, +0.0141, -0.2878, -0.2558, -0.6803, -0.4920, -0.0482, +0.2163, -0.2285, -0.1143, +0.1724, -0.2392, +0.0384, -0.7696, -0.5254, -0.2088, +0.4050, +0.1970, -0.2508, +0.1567, -0.1317, +0.2986, +0.1892, -0.7880, -0.0051, -0.1918, +0.1953, -0.0103, +0.2693, -0.5871, -0.7306, -0.0499, +0.0851, -0.5956, +0.4699, -0.0072, -0.1728, +0.1598, +0.0234, -1.2646, -0.1123, +0.0051, -0.0769, -1.4065, -0.1744, -0.0151, -0.2550, -0.1064, +0.1078, +0.0256, -0.4517, +0.2327, -0.0821, -0.1661, +0.0991, -0.4721, +0.2160, +0.3123, -0.2508, -0.8949, -0.6991, +0.3514],
-[ +0.0703, -0.1692, -1.4867, -0.0076, -0.2931, -0.1692, +0.2276, +0.2554, +0.4607, -0.0033, -0.5308, -0.1111, -0.2342, -1.2702, -0.0528, +0.0717, -0.3220, -1.3547, +0.1024, +0.0170, +0.4253, +0.2123, -0.1259, -0.3122, -0.0105, -0.1530, -0.0172, +0.1871, -0.2647, -0.4114, -0.3456, +0.0040, -0.6042, -0.3889, -0.4615, -0.4490, +0.2165, +0.5019, +0.1494, +0.4083, -0.3297, -0.4118, -0.4185, -0.1609, -1.2773, -0.6846, +0.5723, -0.8063, -1.1917, +0.1809, +0.1200, +0.3350, -0.3911, -0.6569, -0.5049, -0.2564, +0.2318, -0.2522, +0.4132, -0.0193, +0.2003, +0.4302, -0.8441, -0.4850],
-[ -0.0068, +0.1774, +0.0754, -0.1137, +0.1380, -0.1756, +0.0479, +0.1636, -0.0450, -0.0059, +0.0132, +0.0796, -0.0633, +0.1532, -0.5575, +0.0712, +0.3744, +0.0354, -0.0290, +0.4456, +0.2901, +0.4112, +0.3827, +0.4580, -0.1335, +0.3195, +0.4608, +0.6066, -0.3994, -0.8452, -0.9019, +0.8846, -0.7821, -0.3973, -0.7044, -0.5552, +0.1131, +0.1128, +0.2313, -0.0934, -0.1934, -0.2593, -0.1353, -0.4150, -0.3226, +0.3543, -0.1122, -0.7826, -0.3823, -0.1661, +0.3273, -0.2386, +0.3994, +0.2439, -0.1369, +0.1377, +0.6842, -0.1323, -0.1286, -0.7267, -0.1476, +0.2956, -1.1468, -1.1240],
-[ +0.4587, -0.7120, -1.2147, +0.4533, +0.2276, +0.1187, +0.0242, -0.1101, -0.4575, +0.4281, -0.1702, +0.4025, -0.3204, -0.3382, +0.0152, -0.3671, +0.5063, +0.0993, -0.5994, +0.7286, -0.1769, +0.0241, -0.1544, -1.1380, -0.0154, -0.1003, +0.2631, -0.3019, -0.4871, -0.4790, +0.1549, +0.0706, -0.4589, +0.1127, +0.0359, -1.3804, +0.1469, +0.2458, +0.1503, -0.8209, +0.2133, +0.3083, -0.9755, -0.1969, +0.7787, +0.3313, +0.1551, -0.1931, +0.1911, -0.5686, +0.1347, +0.0831, -0.1930, +0.1631, -0.2833, -0.7028, -0.1118, +0.1533, -0.3999, -0.4258, -0.9083, -0.2582, +0.1941, +0.0233],
-[ +0.0318, -0.8817, -1.4912, -0.0615, -0.2420, -1.2041, +0.2243, +0.0201, -0.4026, -0.0492, -1.1668, -0.4146, -0.1817, -0.3084, -0.1083, +0.1698, +0.2102, +0.4088, -0.0380, +0.1766, +0.1979, +0.1506, -0.0227, -0.3307, +0.0935, +0.1202, +0.1487, +0.3542, -0.3225, -0.8973, -0.2828, +0.2174, +0.0593, -0.3961, +0.5630, -0.6109, -0.2253, +0.4927, -1.3722, +0.5185, -0.2207, +0.0805, -0.4203, -0.4720, -0.6695, +0.5880, +0.2328, -0.2068, -0.6150, -0.2285, -0.7370, -0.7668, +0.3113, +0.2548, -0.5908, +0.0268, +0.0115, -0.6208, -0.2927, -0.3607, +0.1788, +0.1785, +0.3288, -0.2640],
-[ +0.3848, -0.7088, -0.5749, +0.1465, -1.2500, +0.0894, +0.0777, +0.1599, -0.1955, +0.1559, -0.7550, +0.0516, -0.1624, +0.1289, -0.0537, -0.6007, -0.3695, -0.0942, -0.0091, +0.1988, +0.3324, -0.2406, -0.5028, -0.7058, -0.0122, +0.1081, +0.2517, +0.1361, -0.5815, +0.0485, +0.0734, +0.0126, +0.1104, +0.3183, +0.3643, -0.0232, +0.1123, +0.0566, -0.0732, -1.0371, -0.2023, -0.3095, -0.0496, +0.2435, +0.0358, +0.1252, -0.0470, +0.1997, +0.1537, +0.2705, -0.1455, -0.4738, -0.1437, -0.2477, -0.0010, +0.1878, -0.3148, +0.3925, +0.0561, -0.6492, +0.2474, +0.0362, -0.0897, -0.0669],
-[ +0.4270, +0.3770, +0.1042, -0.1881, -0.1886, -0.3124, -0.1310, +0.4075, +0.1730, +0.1946, +0.0432, +0.4997, -0.2206, +0.0528, -0.2293, +0.0143, +0.3952, +0.0471, -0.4042, +0.2191, +0.2432, +0.2490, +0.3498, +0.1874, -0.1504, +0.4387, +0.1808, +0.4898, -0.3061, -0.3669, -0.6956, +0.2347, -0.3228, -0.6154, +0.1517, -0.1794, -0.5862, +0.2166, -0.0318, +0.1555, -0.5109, -0.2037, -0.0856, -0.7037, -0.3461, +0.5705, +0.3204, -0.3547, -0.2938, +0.1567, +0.1097, -0.0829, +0.1561, +0.1868, -0.1200, +0.0785, +0.3374, +0.6903, +0.3010, -0.6605, +0.1897, +0.5542, -0.3416, -0.4434],
-[ +0.0792, -0.0354, +0.1346, -0.0867, -0.3061, -0.1105, -0.1961, +0.3380, +0.2322, +0.1389, +0.3620, +0.1611, +0.1719, +0.1811, -0.2072, +0.0334, -0.3774, -0.2193, +0.2164, +0.1568, +0.0684, +0.2052, +0.0536, -0.1594, +0.0561, +0.2893, -0.5556, +0.3248, -0.6442, -0.5264, -0.0596, +0.3401, -0.4276, -0.0385, -0.1273, +0.0564, +0.0775, +0.3581, -0.1403, +0.1570, -0.0367, -0.1462, +0.1820, -0.0586, -2.0140, +0.2617, +0.2951, -0.0837, -0.2212, +0.1362, -0.1088, +0.5008, -0.5582, +0.0823, -0.2323, -1.4969, +0.0935, +0.1385, +0.2140, -0.0230, -0.1270, -0.1048, +0.0824, +0.2496],
-[ +0.2433, -0.2738, -0.6610, -0.0505, -0.2477, +0.3417, +0.5587, -0.5406, -1.0247, -0.2288, +0.3152, +0.1982, +0.0772, +0.1352, -0.4929, +0.2685, -0.2318, +0.0696, +0.0467, -0.2719, -0.2102, +0.3232, +0.6245, -0.0790, -0.0616, +0.0617, -0.1172, -0.1969, -0.2093, -0.2784, +0.6245, +0.0007, +0.4830, -0.2599, +0.4948, +0.6130, -1.0589, +0.6332, -0.0488, +0.2545, -1.2056, -0.5316, -0.0954, +0.3171, -0.2520, +0.2887, +0.0818, -0.1944, -0.2920, -0.1329, -0.5170, -0.2719, +0.0334, -0.2360, +0.4558, +0.3121, +0.4630, -0.5016, +0.2215, -0.5113, +0.4688, +0.3660, +0.3881, -0.0949],
-[ -0.2656, +0.3331, +0.1076, +0.4581, -0.1431, -0.3597, -0.5184, +0.3444, -0.1091, -0.8341, +0.1024, -0.4100, -0.1841, -0.2893, +0.2359, -0.1603, +0.1739, +0.0252, -0.2123, -0.0169, -0.5213, +0.0193, +0.4833, -0.1353, -0.0798, -0.3748, +0.0164, -0.6037, -0.1706, -1.1654, +0.0855, -0.3299, +0.1365, -0.0167, +0.1727, +0.2777, -0.2126, -0.2516, -0.4917, -0.4254, -0.5338, +0.2868, +0.4736, +0.4043, +0.1799, +0.5764, -0.4045, +0.4918, +0.0200, +0.2983, +0.1779, +0.1119, -0.0803, +0.0530, -0.0388, -0.0848, -1.1362, -0.7623, -0.6830, +0.2258, -0.3375, -0.5304, -0.0166, -0.0452],
-[ +0.3656, -0.0786, -1.3351, +0.4419, -1.4259, +0.3107, +0.1254, -0.3197, -1.0404, -0.0778, -0.7287, -0.8611, -0.0762, -0.8058, -0.1075, +0.0800, -0.3792, +0.0459, -0.0407, -0.0736, -0.0587, +0.0415, +0.0496, -0.1451, -0.0132, -0.0385, +0.1978, -0.3532, -0.2219, -0.6179, +0.8095, -0.9253, -0.0623, -0.8459, -0.2542, +0.1622, -0.5230, +0.4588, -0.5261, -0.4698, -0.3448, -0.7056, +0.0831, +0.5875, -0.4304, -1.2342, +0.1449, +0.3140, -0.8756, -0.6573, +0.2131, -0.5328, -0.0440, -0.2245, +0.0357, +0.4620, -0.5595, -0.3738, -0.7502, +0.1694, -0.1364, +0.0650, +0.0636, +0.0344],
-[ -0.0606, +0.0726, +0.0580, -0.7201, +0.0616, -0.2663, -0.5110, -0.3657, -0.3247, +0.2932, +0.0176, -0.2670, +0.0671, +0.0998, +0.4772, -1.4650, -0.3015, -0.4687, -0.4883, +0.2534, +0.3658, +0.0559, -0.4296, -0.1036, -0.0094, -0.2585, +0.0756, +0.2631, +0.2918, -0.1307, -0.0181, +0.0034, -0.2567, -0.5368, +0.2606, -0.3876, +0.5663, -0.4215, +0.2809, +0.0201, +0.4246, +0.1693, -1.1285, -0.0438, -1.0839, -0.1515, -0.0892, -0.7921, -0.0792, +0.4657, +0.4911, +0.0949, +0.0362, +0.2820, -1.4115, -0.3908, +0.0311, -1.3656, -0.6728, +0.2379, -0.1602, -0.6410, +0.6788, -0.0510],
-[ -0.5191, +0.3638, +0.0075, -0.0052, +0.3951, +0.1660, -0.0268, -0.1166, +0.8735, +0.3597, -0.3420, +0.1475, +0.2089, -0.2733, -0.1302, +0.0650, -0.1682, -0.6237, -0.1886, +0.1425, +0.1127, -0.0607, -0.8113, -0.4995, +0.0277, -0.1803, -0.2508, +0.0372, -0.3036, -0.4915, +0.1037, +0.0229, -0.2382, -0.2354, -0.1711, +0.1846, -0.8776, -0.0200, -0.4414, -0.1533, +0.0448, -0.2010, +0.0688, -0.3020, -0.0526, +0.1589, +0.3231, +0.2847, -0.8578, +0.2167, +0.0969, -0.2852, -0.6027, +0.1368, +0.1651, -0.2152, +0.1624, +0.3639, +0.1221, -0.4960, +0.1362, -0.0557, -0.4168, -0.2864],
-[ +0.6175, +0.2864, -0.3944, -1.0445, -0.5126, +0.4037, +0.2065, +0.1380, +0.2727, +0.3778, +0.0995, +0.2318, -0.0628, +0.3280, -0.0223, +0.0671, -0.7848, +0.3413, +0.1067, -0.3424, -0.6270, -0.2365, -0.3945, -0.1812, -0.0288, -0.4210, -0.2331, +0.4286, +0.9716, +0.3043, -0.3778, +0.2830, -0.3521, +0.2004, +0.2613, -0.1126, -0.5060, -0.5227, -0.0945, -0.8172, -0.5810, +0.3176, -0.0357, -0.6075, -0.5641, -0.2488, -0.0749, -0.1395, +0.5087, +0.4870, +0.3374, -0.4190, -0.2451, +0.4110, +0.3360, -0.0793, +0.2368, +0.1880, +0.1418, -0.5637, -0.6581, -0.2530, -1.2775, -0.5173],
-[ +0.2575, +0.5610, -0.5591, +0.4868, -0.6510, -0.4951, -0.1665, -0.7622, -0.4095, +0.0202, -0.4084, +0.7634, +0.0548, -0.1287, -0.5385, -0.5446, -1.2329, -0.5231, +0.0580, +0.1868, -0.5969, -0.4468, -0.3048, -0.6629, -0.0188, -0.4573, -0.2831, -1.3261, -0.3051, -0.4240, +0.2223, -1.0709, +0.0737, -0.0383, +0.1114, +0.4315, -0.8949, +0.2700, -0.0884, -0.0519, +0.1506, -0.5043, -0.9217, +0.1245, -1.1364, +0.3721, -0.0370, +0.0862, -0.4580, -0.1029, +0.0867, -0.1142, -0.1955, +0.2370, -0.1568, -0.8279, -0.0199, -0.5395, +0.0016, -0.5594, +0.1911, -0.2403, +0.4911, -1.0443],
-[ -1.3302, -0.9338, +0.3871, -1.1495, -0.3531, -0.1944, -0.8389, -0.8362, -0.3735, -0.1939, -0.3993, -1.1031, -0.2929, -0.3900, +0.1848, -0.8209, -0.7968, -0.8029, -0.1552, -0.2470, -0.0961, -0.9054, -0.8644, -0.2718, +0.1205, -0.7466, +0.5260, -0.8186, +0.2249, -0.1852, +0.1637, +0.2386, -0.3861, -0.1152, +0.7676, -0.3567, +0.2007, -0.0614, +0.1410, +0.2211, -0.2671, +0.0567, +0.1667, -0.3056, -0.5998, -1.5851, -0.1660, -0.1601, +0.2225, +0.6939, +0.1670, +0.4183, +0.0228, +0.5104, -0.9676, -0.6234, +0.1827, -0.2717, -0.2918, +0.1188, -0.0111, -0.6147, +0.4209, +0.0278],
-[ +0.1161, +0.2482, +0.2554, +0.4476, +0.0995, -0.4997, +0.2332, +0.9127, +0.3242, -0.8211, +0.0737, -0.1947, -0.1772, -0.6136, -0.5493, +0.2106, +0.1126, -0.3909, -0.0581, -0.0024, +0.1720, -0.2446, -0.1968, -0.1427, -0.1429, +0.2843, -0.5226, +0.4872, -0.0392, -0.2645, -0.6053, -0.5143, +0.4939, -0.1568, -0.1001, -1.0052, -0.5236, -0.1548, -0.4120, +0.2023, -0.5504, -0.2983, +0.0447, -1.5144, -0.1567, +0.2201, +0.1278, -0.2537, +0.1308, -0.1034, +0.6555, -1.3159, -0.5089, -0.1758, -0.3958, -0.5218, -0.1935, +0.2361, +0.2255, -0.7272, -0.0587, -0.2821, -0.3442, -0.7232],
-[ -0.3517, -0.0203, -0.3070, -1.2829, +0.3473, +0.4040, -0.1731, -0.2593, +0.0120, -1.7168, +0.0700, +0.0111, -0.0112, +0.0938, -0.2550, -0.0387, -0.9967, -0.0670, -0.1163, -0.0396, -0.6377, -0.9166, +0.1814, -0.1000, -0.2425, -0.0557, -0.3294, +0.4148, +0.3240, +0.1026, -0.1858, -0.0817, -0.0452, +0.2382, -0.6017, +0.0693, +0.1167, -0.9697, +0.0599, -1.1097, -0.0638, +0.7294, +0.2900, -0.6312, -0.5011, +0.2075, +0.0598, -0.4969, -0.1090, -0.1907, +0.0369, +0.0796, -1.7630, -0.1289, +0.1517, -1.3118, -0.8149, -0.2056, +0.1837, -0.0746, -0.6321, -0.6908, -0.0132, +0.0751],
-[ -0.6365, -0.6129, -0.0568, -0.9972, -0.1083, -0.5357, -0.1754, -0.4249, -0.3845, -0.4516, +0.1213, +0.6502, +0.1079, +0.2016, -0.2369, +0.2815, -0.3741, -0.0515, +0.1369, -0.3568, +0.1390, -0.7787, -0.1987, -1.0299, +0.1383, +0.1656, -0.7985, -0.6206, +0.3338, +0.0575, -0.7736, -0.2891, +0.1845, -0.3902, -0.4144, +0.4074, +0.1418, -0.3710, +0.2686, +0.0234, -0.2382, -0.4719, -0.0803, -0.5591, +0.3811, -1.2136, -0.8015, -0.3746, -0.0117, -1.8425, +0.0330, -0.2085, +0.1446, -0.1752, -0.5046, -1.0435, +0.1141, -0.0602, +0.4022, +0.4310, +0.2164, -0.1623, -0.1944, -0.1913],
-[ -0.5695, -0.3372, -0.2433, -1.2988, -0.6181, +0.0353, +0.4011, -0.3847, -0.0820, +0.1582, -0.4111, +0.0552, +0.0906, +0.0849, +0.0692, +0.1922, -0.0549, -1.7126, -0.2257, +0.1049, +0.0016, -0.6541, -1.0900, -0.2897, -0.2057, -0.7505, -0.7495, +0.1641, +0.3909, -0.1974, +0.1989, -0.0289, -0.6525, +0.2379, +0.2185, -0.7424, +0.3704, -1.3808, -0.4839, -0.1950, -0.3002, -0.1963, +0.0819, -1.7138, -0.7822, -1.4837, -0.1470, +0.0372, -0.0416, +0.0395, -0.2169, +0.4130, +0.1063, +0.7070, -0.0286, -1.1673, -0.3685, -0.7736, +0.0467, +0.2205, +0.0719, -0.5629, -0.1000, -0.7227],
-[ -0.0742, +0.2908, +0.0301, +0.2182, -0.0747, -0.1263, -0.1355, +0.2109, -0.2850, -0.5664, +0.1393, -0.3777, -0.1310, +0.1102, +0.3325, -0.1378, -0.0709, +0.1402, +0.0943, -0.0407, -0.3467, +0.0916, +0.2023, -0.1731, -0.1292, +0.1054, -0.0246, -0.2775, +0.0886, +0.3904, +0.0465, -0.5304, -0.0224, +0.1768, -0.2666, +0.2306, +0.1383, -0.7646, +0.0099, -1.2146, -0.9118, -0.5281, +0.1534, +0.3789, -0.0579, -0.1973, -0.1614, +0.6662, -0.3768, +0.3651, +0.4518, +0.1664, -0.1549, +0.1844, +0.1412, +0.0283, -0.7128, -0.8330, -1.7285, -0.1793, -0.2031, -0.1453, +0.2164, +0.2915],
-[ -0.4528, +0.3647, +0.1067, -0.1699, -0.5783, +0.1129, -0.1196, -1.6987, +0.2552, +0.0092, -0.2868, -0.1119, -0.0707, -0.0441, +0.3715, +0.1826, -0.7670, -0.7732, +0.0356, -0.3435, -0.8718, -1.0227, -0.6381, -0.2767, -0.1146, -0.9304, -0.2226, +0.4722, +0.2540, -0.7784, +0.5070, +0.1428, -0.6285, -0.1488, -0.6175, +0.2040, +0.2312, -0.1978, +0.0764, -0.3868, +0.9002, +0.2344, -0.5108, -0.2623, -0.8658, -0.6194, +0.1982, -0.6725, -1.8083, +0.2282, +0.1429, +0.3556, -0.0452, +0.3160, -0.3793, -0.6729, +0.7203, +0.1603, -0.3994, -0.2190, -0.7442, -0.0352, -0.7935, -0.1473],
-[ -0.8168, -0.0091, -0.0508, -0.4927, -0.6616, +0.4340, -0.2432, +0.4167, +0.3489, +0.8354, +0.2251, +0.0112, -0.0185, -0.6260, -0.2298, -0.0221, -0.6862, -0.2349, +0.2170, +0.1041, -0.6343, -0.8665, +0.1858, -1.4852, -0.0523, -0.8654, -0.5574, -0.3615, -0.3560, -0.3082, -1.4751, -0.5826, +0.1229, +0.0924, -0.1141, -0.0477, +0.1553, -0.3143, -0.5285, -0.7833, +0.2824, -0.4220, +0.1819, -0.2719, -0.0280, -0.6713, -0.8150, -0.5180, -0.1413, +0.2325, -0.3501, +0.0866, -0.2519, +0.3551, -0.4227, -0.1018, -0.9312, -0.2401, +0.4466, -0.2421, -0.4953, -0.9608, -0.3090, +0.0437],
-[ -0.3678, -0.0514, +0.8817, -0.7280, -0.1600, +0.8120, -0.4446, -0.1063, -0.5102, +0.1453, -0.0061, -0.1726, +0.0986, +0.2938, +0.1933, +0.3513, +0.5222, +0.1550, -0.0421, +0.1425, -0.1413, +0.1639, -0.8166, -0.1317, -0.4997, -0.0874, -0.3524, -0.8873, -0.9856, +0.6431, +0.1933, +0.0048, -0.0601, +1.0241, +0.3887, -0.7046, +0.4948, -0.7165, +0.0877, +0.0682, +0.6019, +0.5806, +0.3123, -0.1842, -0.1036, +0.3439, -0.4009, -0.4758, +0.2913, +0.0956, +0.6178, -1.4622, -0.1621, -0.7775, -0.0004, +0.2367, -0.2088, -0.9526, -0.1860, +0.1470, +0.1572, -0.1658, +0.1708, +0.5259],
-[ -0.2214, +0.1985, -0.1847, +0.5871, -0.3763, +0.0672, -0.1033, -0.0671, +0.1542, +0.0275, -0.5201, +0.1248, +0.1134, -0.3788, +0.0484, -0.5302, -0.0118, -0.8965, +0.0713, +0.0392, +0.1628, -0.0572, -1.8384, -0.3889, -0.2469, +0.4550, -0.0606, +0.0431, -0.0217, -0.4960, +0.1855, -0.1257, +0.2440, +0.0600, +0.2227, -0.6121, -0.2051, +0.0859, -0.4757, -0.2172, -0.1453, +0.1773, -0.3348, +0.1459, +0.1331, -0.0931, +0.0132, +0.2765, -0.3224, -0.7257, -0.0038, -0.1957, -0.6276, -0.1183, +0.0673, +0.3088, -0.0822, +0.1390, +0.4112, +0.0519, +0.3311, +0.2228, -0.4378, -0.5721],
-[ -0.0147, -0.0421, +0.0189, -0.4632, -0.1887, +0.1763, +0.2966, -0.2942, -0.1684, +0.0008, +0.3991, -0.1310, +0.2420, +0.3445, +0.0718, -0.2459, -0.4664, -0.7893, +0.0726, -1.0375, -0.7542, -0.5141, +0.3281, -0.5370, -0.4788, -0.4261, +0.1905, +0.0993, +0.4738, +0.1131, +0.1462, -0.1149, -0.8987, -0.3439, -0.0783, +0.3170, +0.2363, -0.2870, -0.1533, -0.1604, +0.2246, -0.9061, -0.3147, +0.0034, -0.0893, -0.1349, -0.3582, +0.0769, +0.3767, -0.1624, -0.3113, -0.3842, +0.2768, +0.5184, +0.1937, +0.6202, +0.2389, +0.0061, +0.2531, -0.1111, -0.3178, -0.1828, -0.2073, -0.2022],
-[ -0.1047, -0.1899, -0.0452, -1.5021, -0.0903, -0.5365, -0.7039, -0.8838, +0.0651, -0.0976, -0.5219, -0.2925, +0.1947, -0.0408, +0.0430, -0.5362, -0.3390, -0.2032, -0.3870, -1.5461, -0.4847, -0.8721, +0.0815, +0.0294, +0.0019, -0.1992, -0.0342, -0.7489, +0.3711, -0.1925, -0.3552, -0.0407, -0.0402, -0.4258, -0.1176, -0.6723, +0.4815, -0.2728, +0.1984, -0.4091, -0.3322, -0.0223, -0.4487, -0.6132, -0.7094, -0.5729, -0.3616, -1.4608, -0.1466, -0.2963, -0.1808, +1.0996, -1.1116, +0.0384, +0.1127, -1.0002, -0.3117, -0.4126, +0.1461, -0.2834, +0.1687, -1.2180, +0.8404, +0.3414],
-[ -0.2871, -0.2753, +0.3318, -0.0631, -0.0329, -0.2655, +0.1154, +0.1341, -0.3528, -0.4633, -0.4270, +0.1776, +0.1154, -0.0745, -0.3922, +0.0375, +0.0055, +0.4779, -0.1397, -0.5729, -0.1113, +0.0881, -0.0655, -0.4586, -0.0322, +0.1184, -0.5583, -0.4987, -0.0660, -0.1451, +0.1862, -0.8150, +0.8184, -0.0894, -0.3762, -0.5304, -0.5791, +0.0317, -0.2269, +0.2771, -0.1284, -0.3164, -0.5405, +0.1469, -0.8860, +0.4223, +0.1829, -0.3194, -0.4208, +0.4972, -0.7205, -0.7719, -0.3450, +0.5980, -0.1395, -0.3528, -0.1897, +0.1412, +0.1881, -0.0785, +0.3184, -0.3845, -0.3870, -0.1074],
-[ -0.0549, -0.1759, -1.4543, -0.4064, -0.4019, +0.0416, +0.2107, -0.9047, -0.5796, +0.0453, -0.2060, +0.7131, +0.1083, +0.0712, +0.0948, -0.7550, -1.0484, -0.1334, -0.3905, +0.3899, -0.6879, -0.9365, +0.3175, -0.2515, -0.0216, -0.6523, -0.5432, -0.3200, +0.2436, +0.4666, +0.2695, +0.6725, -0.3633, -0.4047, +0.0874, +0.2482, +0.0669, +0.0321, -0.0457, +0.2833, +0.4448, -0.1799, +0.0688, +0.0473, +0.0295, +0.4890, -0.1082, -0.2163, +0.2725, -0.0772, -0.0288, +0.4464, -0.2413, +0.0908, +0.3795, -0.7329, +0.0918, -0.0568, +0.4359, -0.1642, -0.4720, -0.6958, +0.3310, -0.9285],
-[ -0.3428, +0.3394, +0.2910, +0.0395, +0.1968, -0.3811, -0.3117, +0.2441, +0.2823, -0.4930, +0.1645, +0.1595, -0.2763, +0.2406, -0.3192, -0.4154, -0.2809, +0.0606, -0.1039, +0.2498, -0.4704, -0.1710, -0.3512, -0.0781, -0.1085, -0.2105, -0.1707, +0.1695, +0.2557, -0.8382, -0.4814, -0.3560, +0.0130, -0.0411, -0.5253, +0.1622, +0.0977, -0.3241, +0.3357, -1.1972, -1.0786, +0.0531, -0.0801, -0.1700, -0.1637, -0.3555, +0.0159, +0.3452, -0.2490, -0.0398, +0.3255, +0.0474, -0.2646, +0.2222, -0.0094, -0.4791, -0.7316, -0.1143, -0.5465, -0.2249, -0.4003, -0.4671, -0.0495, +0.1696],
-[ -0.4032, -0.7569, -0.6099, -0.1711, -0.8909, +0.2922, +0.1176, -0.3625, -1.0356, +0.2123, -0.6401, +0.1968, -0.3508, +0.1569, -0.0021, -0.8648, -0.0136, +0.0362, -0.4099, +0.0140, -0.3279, +0.0350, +0.1094, -0.4495, -0.1535, -0.8482, -0.3956, +0.0348, -0.8475, -0.1615, +0.4068, +0.2318, -0.3285, -0.4544, +0.3332, +0.4241, -0.1228, +0.1105, +0.2951, -0.1227, -0.0585, -0.1504, +0.0110, -0.4835, +0.0051, +0.2351, -0.7890, -0.3031, -0.1653, -0.0390, -0.2326, -0.3724, +0.1074, +0.0847, -0.0288, -0.0392, +0.1232, +0.3832, -0.0923, +0.2702, -0.0836, -0.6782, +0.1941, -0.5479],
-[ -0.0042, -0.1946, -0.1632, +0.2652, -0.3281, -0.5539, +0.1933, -0.5138, -0.7291, -0.0916, +0.0651, -0.0960, -0.0087, -0.6420, -0.1012, -1.2801, +0.0314, +0.3125, -0.1892, +0.0743, -0.2332, +0.0198, +0.1641, +0.1603, +0.0527, -0.1782, +0.2653, -0.9144, -0.2789, +0.2436, -0.0685, +0.8306, -0.1436, -0.3050, -0.1886, +0.1350, -1.0503, -0.2253, -0.2741, +0.2681, -0.4613, -0.7832, +0.5836, +0.0801, -0.5491, +0.1075, +0.3780, +0.3248, -0.2623, +0.0749, +0.1353, -0.6015, +0.3448, -0.0809, +0.0375, +0.2001, -0.2588, -0.2804, -0.2702, +0.2283, +0.1124, +0.4594, -0.4324, +0.1485],
-[ +0.1532, +0.2848, -0.2427, +0.4166, +0.0042, -0.3085, +0.1124, +0.2537, +0.1375, -0.2485, -0.0234, -0.0071, -0.0783, -0.2518, +0.1560, -0.5850, +0.1183, -0.0517, -0.1053, +0.3356, +0.3028, +0.2722, +0.1897, +0.2332, -0.3597, +0.5258, -0.0684, -0.0984, -0.2643, -0.5880, +0.1289, +0.0015, -0.1563, -1.0911, -0.2512, -0.4506, +0.0817, +0.1627, -1.0543, +0.6363, -0.2562, -0.5514, -0.2316, +0.0717, -0.1111, -0.1945, +0.1628, -0.0464, -0.4399, -0.2649, +0.1594, +0.0358, -0.1435, +0.1108, +0.1648, +0.4697, -0.0951, +0.1059, -0.5489, -0.4333, -0.0550, -0.2629, -0.9481, -0.0023],
-[ -0.1565, +0.0574, -0.2594, +0.1234, +0.1356, -0.2661, +0.3433, +0.2905, -0.1498, -0.0338, +0.3885, -0.0082, +0.0051, -0.8434, +0.2996, -0.1082, -0.2098, -0.4112, -0.1268, -0.1134, +0.2039, +0.0491, -0.0465, -0.5719, -0.1081, -0.0628, -0.5965, +0.3252, -0.0130, -0.3893, -0.0323, +0.1651, -0.5723, +0.4407, +0.0223, -0.1040, -0.2432, +0.0811, -0.1804, +0.2986, +0.0872, -0.0198, +0.1289, -0.7460, -0.4659, +0.3831, -0.0848, -0.8659, -0.4278, +0.1593, -0.2717, -0.2745, -0.4147, -0.4569, -0.4038, -0.3464, +0.0218, -0.1718, +0.2309, +0.1343, +0.2253, -0.1355, -0.4830, -0.4628],
-[ +0.0450, -0.7682, -0.5959, +0.1884, -0.3429, -0.2553, +0.7554, -0.1022, +0.4099, -0.1219, -0.2093, -0.0878, +0.0561, -0.5284, +0.0385, -0.7532, +0.5020, -0.9372, -0.1928, -0.3592, -0.0536, -0.1005, -0.1540, -0.2265, -0.1188, +0.1608, +0.1528, +0.2769, +0.5073, -0.1996, -0.1063, +0.1040, -0.8756, -0.0927, -0.0733, -0.4302, -0.4747, +0.4669, -1.0292, -0.2093, -1.6550, -0.7398, -0.0037, -0.0352, -0.7409, +0.0588, +0.1492, +0.1683, -0.3111, +0.1539, -0.2438, -0.8038, +0.1800, +0.0742, +0.2182, +0.2555, +0.1701, -0.2382, -0.0567, -0.2451, -0.3627, -0.0496, -0.0007, +0.0642],
-[ -0.0198, -0.7084, -1.7288, +0.0023, -0.6159, -0.3045, +0.2740, -0.6177, -0.9246, -0.7641, -0.0082, -0.1067, -0.1914, -0.1873, +0.3149, -0.3414, +0.2478, +0.5272, +0.0465, -0.2181, +0.2295, +0.1319, -0.0236, -0.2259, -0.3665, +0.1407, +0.5191, -0.2611, -0.0468, +0.2089, -0.1337, -1.2692, +0.2063, -0.2235, +0.2870, -1.0765, +0.2921, +0.0708, -0.8893, +0.1605, -0.4512, -0.1917, -0.1650, -0.1710, +0.2144, -0.1577, -0.0188, -0.2185, -0.2129, -0.3773, -1.1166, -0.8290, +0.2877, +0.1461, -0.1932, +0.4364, -0.2597, -0.6060, +0.3258, -0.1753, +0.3740, +0.1653, +0.3116, +0.1972],
-[ -0.5676, -0.1738, +0.0645, -1.0766, +0.5088, -0.2353, +0.1632, +0.0342, +0.6782, -0.1393, -0.1100, -0.4369, +0.1336, +0.2995, -0.5347, +0.4146, -0.0427, -0.2986, -0.0927, +0.0586, +0.5212, -0.0742, -0.0939, -0.4191, -0.0830, -0.0546, -0.3702, +0.6367, +0.0227, -0.0992, -0.2374, -0.0286, -0.3807, +0.0304, -0.2574, +0.0564, +0.0096, +0.1621, +0.1392, -0.3874, -0.0431, +0.2932, +0.3008, -0.3351, -1.0291, +0.9737, +0.1879, +0.4559, -0.2085, +0.1174, +0.6974, +0.1809, -1.4216, -0.7912, -1.2257, +0.1453, -0.2233, +0.3229, +0.4583, +0.0773, -0.7117, -0.3845, +0.1082, +0.0987],
-[ +0.0781, -0.0814, +0.8480, +0.2264, -0.4587, -0.3083, +0.1459, +0.4196, +0.3756, -0.1326, +0.0951, -0.2471, -0.1196, -0.8551, +0.0014, -0.2029, +0.2577, +0.2734, -0.0681, -0.4470, +0.5168, +0.1951, +0.0949, -1.0213, -0.0389, +0.2296, +0.4116, +0.1783, -0.4069, -0.2838, -0.1370, +0.0335, -0.0403, -0.0137, +0.4868, +0.1037, +0.3783, +0.1564, -0.1589, +0.3586, +0.0252, -0.2580, +0.1670, -0.4183, -0.0371, +0.0142, +0.2253, -1.0320, -0.2583, -0.1020, -0.2032, -1.3460, +0.5840, -0.0893, -0.6009, +0.5548, -0.0857, -0.0794, +0.3571, +0.0167, +0.0949, +0.1082, -0.2736, -0.3984],
-[ +0.1488, +0.0836, -0.1156, -0.0946, -0.6624, +0.3870, +0.1203, +0.2345, +0.5957, -0.0864, +0.0939, +0.3911, -0.3770, -0.7077, -0.1206, -0.2049, -0.5693, -1.1134, -0.1524, +0.1622, -0.1211, -0.6374, -0.6248, -1.2622, +0.0899, -0.1572, -0.2152, +0.6604, +0.7116, -0.3532, +0.2550, +0.6011, -0.1052, +0.2644, -0.0520, -0.2045, -1.3817, +0.4718, +0.1422, -0.1959, -0.4853, +0.3969, -0.1666, -1.0437, -0.2013, -0.4767, -0.2118, +0.4010, -0.4163, +0.5423, -0.0842, -0.4901, -0.3661, +0.3607, +0.4009, +0.0245, +0.2585, +0.3218, +0.3151, -0.4333, -0.9903, -0.3832, -0.6528, -0.9357],
-[ +0.2625, -0.3163, -0.7011, -0.4750, -0.2169, -0.4875, -0.7199, +0.4407, +0.0992, +0.3363, -0.3765, +0.1178, -0.1361, +0.0589, -0.2783, -0.0918, +0.8017, -0.1301, -0.0942, +0.5582, +0.3169, -0.1525, -1.0656, -0.9893, +0.0477, +0.0623, -0.8920, +0.7155, +0.1733, +0.6024, -0.1510, -0.2588, -0.9339, +0.0646, +0.1528, -1.4100, -0.4579, +0.1205, +0.1494, -0.5505, +0.2527, +0.6798, -0.0354, +0.1972, -0.0864, -0.0724, +0.4457, -0.1612, -0.0747, -0.8515, +0.5947, +0.0358, -1.5359, -0.0754, +0.1504, +0.1272, -0.2733, -0.6504, +0.1311, -0.6455, +0.3241, -0.7097, -0.2899, +0.1537],
-[ -1.1608, -0.5298, -0.8712, +0.1991, -0.3332, +0.3643, +0.0401, -0.4816, +0.3851, +0.2349, -0.6814, +0.1716, -0.2337, -0.0912, +0.4335, -0.1547, -0.4001, +0.3222, -0.1337, +0.3072, +0.2498, -0.2764, -0.8538, -0.2515, -0.0439, +0.1265, -0.5853, +0.0693, -0.4379, +0.1737, +0.3439, -0.7150, +0.3867, +0.3087, +0.4529, -0.6548, -0.2920, -0.0996, -0.9976, -0.3262, +0.7263, +0.7688, -0.9637, +0.0227, +0.3281, +0.2599, -0.6599, -0.0804, +0.2021, -0.4105, -0.8758, +0.5409, -0.3671, -0.0064, +0.3239, -0.5062, -0.1013, +0.0167, -0.2186, -0.4367, -1.0176, -0.3509, -0.0338, -0.1166],
-[ -0.2009, -0.0097, -0.3805, +0.5547, +0.0211, -0.1902, +0.2175, +0.2475, -0.1842, -0.5084, +0.4752, +0.4515, -0.0791, -0.5530, -0.1438, +0.0275, +0.0589, +0.2926, +0.0454, -0.1496, +0.1475, -0.1997, +0.1834, -0.5198, +0.0427, -0.2978, -0.2438, +0.0810, +0.3660, +0.0816, -0.5628, -0.0037, +0.4582, +0.5978, -0.0285, +0.1455, -0.7267, -0.5732, -0.0079, -0.0751, -0.8395, -1.2686, +0.2954, -0.2310, +0.4056, -0.0743, -0.2228, +0.0327, +0.2061, +0.2131, -0.2174, +0.1368, -0.5607, -0.1470, +0.2396, -0.4317, +0.5534, -0.3621, -0.1064, -1.2382, +0.3209, -0.1634, -0.9480, +0.3144],
-[ -0.1292, -0.5636, -0.0849, +0.2092, -0.1442, -0.2223, +0.1724, -0.6844, -0.8701, -0.3775, -0.3263, -0.2123, +0.0666, -0.6740, +0.4411, -0.6332, +0.3243, +0.2527, -0.0565, +0.1122, +0.4365, +0.2004, +0.5247, +0.2099, -0.0063, +0.1774, +0.5491, -0.4683, -0.0755, +0.6953, +0.0733, -0.6102, +0.1488, -0.2186, +0.4960, +0.2464, -0.2218, -0.2068, -0.5311, +0.4264, +0.5527, +0.2815, -0.3011, -0.2885, +0.1760, -0.4510, +0.2082, -0.3399, -0.2715, -0.2917, -0.4012, -0.6663, +0.6144, +0.3065, -0.6742, +0.2289, +0.0560, -0.6837, +0.0275, -0.1482, +0.6406, +0.1464, +0.0440, +0.3607],
-[ -0.2100, -0.3766, -0.3248, -0.0815, -0.0021, -0.0053, +0.1080, +0.1588, -0.0212, +0.0710, -0.1382, +0.0091, +0.0343, -0.8511, -1.4211, +0.4568, -0.2851, -0.6204, +0.1094, -0.5432, -0.0860, -0.2730, -0.6808, -0.3779, -0.1227, -0.1347, +0.0673, +0.0427, -0.4947, -0.0973, -0.3803, -0.1468, +0.1988, -0.2611, -0.6531, -0.1605, -0.9337, +0.5437, +0.0989, +0.1534, -0.4737, -0.8900, -0.6949, -0.1503, -0.9317, +0.3230, +0.2311, -0.3696, -0.4520, -0.7193, +0.6298, -0.2834, +0.5434, -0.5763, +0.3341, -0.1008, +0.2521, -0.1212, -0.2856, +0.0286, +0.1565, -0.1973, -0.9579, +0.2266],
-[ -0.3733, -0.5246, -1.0401, -1.1247, +0.5040, +0.1447, -0.3600, -0.5734, -0.9212, -0.3597, +0.2485, -0.3560, -0.0752, -0.8746, +0.4507, -0.5267, +0.1474, +0.3419, +0.0363, -0.7705, -1.6857, -1.1070, +0.2625, -1.0731, +0.1143, +0.1023, -0.9064, -0.5451, -0.5312, +0.0702, -0.2498, -1.3055, +0.1746, +0.5512, -1.0339, +0.1665, -0.0061, +0.3917, +0.3936, -0.0938, -0.3131, -0.5685, +0.1470, -0.5130, +0.4499, -0.3169, -0.1906, -0.3272, +0.1276, +0.3542, -0.8497, +0.0924, +0.2336, +0.0205, +0.5533, -0.6078, -0.0380, -0.9867, +0.3744, -0.4039, -0.2097, -0.6184, -0.4652, +0.0281],
-[ -0.7440, -1.0423, +0.2391, -0.7264, +0.6529, +0.1477, -0.6196, -0.4762, +0.0692, -0.4353, +0.6195, -0.3501, +0.0457, +0.5445, +0.3201, +0.5907, +0.1408, +0.5189, +0.2457, -0.1996, -0.0750, -0.8873, -0.3630, -0.2106, -0.0367, +0.3119, -0.3941, -0.7667, +0.2979, -0.1940, -1.1527, -0.7601, +0.3334, +0.7463, +0.0006, +0.5900, +0.4330, -0.2191, +0.1961, -0.1740, -0.0606, -1.9663, -0.0980, -0.3602, +0.2108, -0.8138, +0.2321, -0.0849, +0.5843, -0.1114, +0.1376, +0.0711, -0.2334, -0.4425, -0.4017, -0.9668, -0.2785, -1.0386, +0.1323, -0.3491, -0.1183, -0.1991, +0.1755, +0.2324],
-[ -1.6279, -0.5764, -0.5582, -0.1969, -0.2668, +0.0346, -0.5277, -0.4330, -0.3943, +0.3645, -0.1540, +0.0062, -0.0567, -0.0784, +0.1743, -0.9562, -0.4454, +0.0533, -0.1731, +0.1988, +0.1024, +0.5358, -0.4556, -1.0002, -0.1435, -0.2930, -0.4634, -0.2278, -0.3642, +0.3626, +0.5493, +0.1137, -0.1669, -0.4225, +0.0216, +0.4361, -0.1621, -0.1015, -0.0550, -0.3966, +0.5804, +0.1967, -0.3464, +0.0925, +0.3493, +0.1171, -0.3405, -0.0503, +0.1499, -0.3313, -0.0033, +0.0960, -0.6710, +0.2601, -0.1169, -1.5937, -0.0615, -0.1506, -0.2239, +0.1024, -0.2309, -0.4043, +0.4463, -1.0894],
-[ -0.2373, -1.4598, -0.1174, -0.1045, +0.4946, -0.5140, +0.0110, -0.6460, -1.3452, +0.4370, -1.0515, -0.7801, -0.2640, +0.0359, -0.0097, -0.4043, +0.1002, -0.0268, -0.0773, -0.0390, +0.0679, -0.2875, -0.9561, -0.2837, -0.1344, +0.1141, +0.2607, -0.1805, -0.2482, +0.4783, -0.0732, -0.3817, +0.3229, -0.1179, +0.3825, -0.3490, +0.6231, -0.3663, -0.2762, +0.1450, -0.0651, +0.3529, -0.6646, -0.0485, +0.6340, -0.1721, -0.0388, +0.1370, +0.3559, -0.1751, -0.3544, -0.2360, +0.1969, -0.0265, -0.5621, +0.1465, -0.5286, -0.0378, -0.3572, -0.2107, +0.1881, -0.3776, -0.1373, -0.2395],
-[ -0.0932, -0.1324, -0.7774, +0.7236, -0.0517, +0.2264, -0.0171, -0.3843, -1.8551, -0.2552, +0.2186, -0.1668, -0.0405, -0.7226, +0.3290, -0.4577, +0.6845, +0.2283, +0.0772, +0.3389, -0.1607, +0.2051, +0.2808, -0.1648, -0.1542, -0.1327, +0.3047, -0.1349, -0.3720, +0.5004, +0.1875, -0.3262, +0.7620, +0.2608, -0.6428, +0.5077, -0.8593, +0.1150, -0.6590, +0.5739, -0.3998, -0.2555, +0.4572, +0.5381, +0.2333, -0.3406, +0.3267, -0.2062, -0.4765, +0.0695, -0.7520, +0.3144, +0.2924, +0.0593, -0.2462, -0.2207, +0.1864, -0.6530, +0.3565, -0.2062, -0.0916, +0.1603, -0.1901, +0.0146],
-[ +0.5634, +0.0527, -0.4892, +0.2440, -0.1720, +0.2785, -0.4833, +0.1367, -0.1087, -0.1074, -0.2101, +0.2272, -0.2405, +0.2242, +0.4896, -0.5147, +0.1469, +0.2632, -0.2786, -0.5737, -0.2000, -0.3146, +0.1852, -1.6770, -0.0606, -0.6669, -0.6540, +0.3910, +0.1855, +0.2526, -0.2044, +0.2109, -0.5512, -0.2409, +0.1259, +0.5317, -0.5607, -0.0788, +0.0273, -0.1690, +0.1662, +0.0275, -0.4170, -0.7013, -0.0454, +0.4406, -0.5298, -0.3473, +0.0638, -0.3749, +0.2545, +0.5678, +0.5063, +0.3236, -0.7996, +0.3285, -0.1605, +0.6192, +0.1014, +0.1821, -0.5310, -0.5324, +0.1416, -0.3316],
-[ -1.1046, -0.7047, -0.2575, -0.7403, -0.7298, -0.2453, -0.3595, -0.4102, -0.3522, +0.5069, -0.3525, +0.0370, +0.0301, +0.2036, +0.1020, -0.2437, +0.2750, +0.4183, -0.0769, -0.2143, +0.4041, -0.1546, -0.3924, -0.4053, -0.1305, -1.6502, -0.5113, -0.4471, -1.4570, +0.0472, +0.2965, +0.2012, -1.2503, -0.4947, +0.0608, +0.0305, +0.2824, -0.0230, -0.5519, +0.3479, +0.1785, -0.3687, -0.1119, -0.2599, -0.3071, -0.4963, -0.8701, +0.0014, +0.2138, -0.1607, -0.7962, -0.3856, +0.0298, +0.2767, -0.5021, -0.8125, +0.1187, -0.2955, +0.0602, +0.2604, +0.1913, -0.7938, +0.4153, -0.4320],
-[ -0.1053, -0.4955, -0.7817, +0.4661, -0.5876, -0.0594, +0.3703, +0.0458, -0.2497, +0.1020, +0.4331, -0.1484, -0.1813, -0.4629, +0.4557, +0.1618, -0.1633, -0.0155, -0.0498, +0.2643, +0.4639, +0.2317, +0.0692, +0.2114, +0.0785, +0.3615, +0.3779, -0.1974, -0.2165, +0.0856, +0.0563, +0.1860, -0.7703, +0.0791, +0.0535, +0.1625, +0.1107, +0.1564, +0.0604, +0.5328, +0.2965, -0.4956, -0.0350, -0.8169, -0.1578, -0.3033, +0.3697, -0.2652, -0.0895, +0.2893, -1.2192, -0.3056, -0.5532, -0.6461, -0.9112, -0.5628, +0.5037, +0.0736, +0.1086, +0.0716, +0.5142, +0.1312, -1.4517, -0.9905],
-[ -0.9468, -0.7466, -0.6471, -0.1362, -0.8800, +0.5892, +0.5213, -0.6689, +0.2229, -1.6990, -0.1504, -0.1068, +0.0205, +0.2356, +0.5575, -0.4093, -0.0981, -0.9981, +0.0432, -0.6207, -0.0574, -0.1144, -1.5140, -0.3693, -0.1618, +0.3839, -0.1877, -0.2322, +0.0598, +0.2673, +0.3659, -1.0235, +0.0875, +0.3404, -1.0691, -1.6803, -0.2115, -0.6276, -0.5968, -0.7992, +0.0821, -0.6022, -0.0708, +0.2164, +0.5098, -0.1063, -0.2642, +0.3782, +0.3025, -0.7081, +0.1065, -0.5805, -1.1473, -0.4245, +0.3123, +0.2769, +0.4162, -0.4652, -0.7961, +0.0205, +0.1451, -0.4086, -0.1521, -0.2852],
-[ -0.7144, -0.0732, -0.2513, -0.5200, +0.2989, +1.0393, -0.0999, +0.6432, -0.2806, -0.3070, +0.5141, -0.0163, -0.0070, -0.5330, +0.1894, -0.1748, -0.2329, +0.3600, +0.4255, -0.6582, -1.3598, -0.8585, +0.1014, -0.4106, -0.0970, +0.1253, -0.1873, -0.3545, +0.2180, +0.3920, -0.5099, +0.0616, -0.3497, +0.2023, -0.8214, -0.1101, +0.6518, -0.4036, +0.1847, -1.2271, +0.2813, -1.0571, +0.6299, +0.2067, -0.6461, -0.6766, -1.4846, +0.0878, +0.6149, -0.1618, -0.3680, -0.4017, -0.7612, -0.2911, -3.0760, -0.0799, -0.6366, -0.2699, +0.3534, +0.0080, -1.2127, -0.5772, -0.8138, -0.3230],
-[ +0.0332, +0.2400, -0.4718, +0.1539, +0.1194, -0.0690, +0.2228, +0.1942, +0.1187, +0.2018, +0.4571, +0.3205, -0.2239, -0.5064, +0.1089, -0.1322, -0.4595, -0.4284, -0.1388, -0.0142, -0.0337, -0.1693, +0.3553, -0.6581, -0.0025, -0.1231, -0.4583, +0.2712, +0.1195, +0.1075, -0.1298, +0.1162, +0.2405, +0.1785, -0.0615, -0.0789, -0.5330, -0.1870, -0.0264, -0.0452, -0.1919, -0.0952, +0.3738, -0.2498, -0.2696, +0.4355, +0.1340, -0.4136, -0.2625, +0.1043, +0.2227, -0.2964, +0.0329, -0.0459, +0.3446, -0.3150, -0.0285, -0.1389, -0.0620, -0.3741, -0.0209, +0.0344, -0.4535, +0.3100],
-[ -0.3163, -0.4723, -0.0250, -0.0141, +0.4464, -0.1986, -0.6116, -0.0829, -0.1127, -0.1741, +0.3716, -0.5599, -0.0702, +0.4810, +0.2091, -0.0865, +0.1534, -0.2891, -0.3830, -0.1924, -0.0542, -0.0241, -0.1366, +0.0385, -0.1856, +0.5328, -0.4052, -0.5755, -0.2612, +0.0013, -0.0076, -0.2590, +0.3901, -0.4172, -0.1419, +0.0362, +0.1212, -0.3479, -0.1679, -0.0086, -0.1725, +0.0736, +0.0087, +0.1469, +0.0006, +0.1689, -0.3634, -0.1821, +0.3467, -0.2033, -0.1277, +0.1919, +0.1260, -0.1244, -0.2993, -0.0904, -0.1687, +0.3754, +0.2097, -0.5879, -0.0770, +0.0359, +0.2110, -0.1712],
-[ -0.3661, -0.2717, +0.1113, +0.2665, -0.0972, -0.5824, +0.2890, -0.1308, -0.0929, -0.0011, +0.2813, -0.1148, +0.0119, -0.0529, -0.0646, -1.4966, +0.4980, +0.0945, +0.1389, -0.4049, -0.2027, -0.0673, +0.1332, +0.7332, +0.1248, -0.0770, +0.6605, -0.8541, -0.0439, -0.1973, -0.4820, -0.0423, -0.2129, -0.0853, -0.6524, -0.0321, -0.0372, +0.3873, +0.0421, -0.4772, -0.5575, -0.5932, +0.1917, +0.2110, +0.1637, -0.3029, -0.2104, -0.0282, -0.7481, +0.0828, +0.0379, +0.2106, -0.0853, -0.2235, -0.1073, +0.5198, -0.2518, -1.3097, -0.3292, +0.1675, +0.0255, -0.1867, -0.6809, -0.4100],
-[ +0.3530, -0.2818, -0.8931, -0.6490, -0.0029, -0.0079, +0.6413, -0.4325, -0.2703, -0.5681, +0.2736, -0.2060, -0.2772, +0.0567, -0.1602, +0.0456, -0.2931, +0.1224, +0.0146, +0.6612, +0.0332, -0.2383, -0.3551, -0.4960, +0.0080, +0.0682, +0.2126, +0.0375, -0.1039, +0.2998, -0.4285, +0.1969, +0.2692, +0.2157, +0.1096, +0.1654, -0.6327, +0.4191, -1.3065, +0.1224, +0.5497, +0.2013, +0.1524, +0.0798, -0.0325, -0.2407, -0.2019, -0.7491, -0.3803, -0.1791, -1.0558, +0.3998, -0.2989, +0.1077, -0.4348, +0.0519, -0.2329, -0.1133, +0.0053, +0.2635, -0.4516, -0.0578, -0.3698, -0.1016],
-[ +0.6371, -0.1203, +0.0076, -0.8131, -0.0454, -0.8196, -0.9530, +0.0536, -0.0904, -0.6379, +0.0735, +0.4852, -0.0525, +0.5745, +0.1264, -0.3008, -0.7915, -0.0787, +0.1571, +0.1630, -0.3364, -0.1717, +0.5771, -0.6814, -0.2517, -0.3498, -0.3729, -0.4342, -0.5237, -0.6116, -0.1791, -0.0410, +0.0610, -0.2450, -0.8010, +0.5793, -0.5352, +0.1076, -0.1877, -0.1534, +0.3871, +0.0020, +0.1915, -0.3309, +0.0250, -0.5323, -1.2959, -0.9239, +0.2443, +0.0734, -0.2273, +0.0469, +0.2829, +0.2647, -0.5502, -0.4885, -1.0957, +0.1740, +0.1821, -0.6767, -0.2402, -0.3386, +0.1601, +0.3032],
-[ -0.9192, +0.1419, -0.0422, -0.8396, -1.4337, -0.4047, +0.4867, -0.1729, +0.0987, +0.2949, -0.1027, +0.1376, +0.0276, -0.3454, +0.1000, +0.1415, +0.1384, -0.4045, -0.3747, -0.0164, +0.2935, -0.1466, -0.1396, +0.0236, -0.0539, +0.1790, -0.2958, +0.2800, -0.6574, +0.0546, -0.3582, -1.0463, +0.1917, +0.1586, -1.2121, -0.7189, -0.4901, +0.6121, -0.2627, +0.1610, -0.0404, +0.1463, -0.2310, -0.3012, +0.1397, +0.8620, -0.0025, -0.9045, -0.4128, -0.1460, +0.3187, -2.0256, -0.4127, +0.2568, +0.7488, -0.0511, -0.1044, +0.0262, +0.2524, +0.0832, +0.2267, +0.2748, -0.4902, +0.3688],
-[ +0.1430, +0.0566, +0.6816, -0.3206, -1.4961, +0.1194, +0.6902, +0.0898, -0.2031, +0.1232, +0.0439, +0.1807, -0.0578, -0.0846, -0.1607, +0.0681, -0.0610, -0.5653, +0.0072, -0.5820, -0.0853, -0.3235, -0.4972, +0.0032, -0.2038, -0.2900, -0.1359, +0.0540, -0.0303, -0.6849, -0.9005, -0.1212, +0.0606, +0.1388, -0.4231, -1.0739, +0.1928, +0.0319, +0.0958, +0.0125, -0.1298, -0.2588, +0.1088, -0.5559, -0.3151, +0.0548, +0.3297, -0.5271, -0.7640, -0.0341, +0.1411, -0.4929, -0.1423, -0.0565, +0.2080, +0.0836, -0.3868, -0.1338, +0.1035, -1.4365, +0.1114, -0.2450, -0.7043, +0.3546],
-[ +0.2535, -0.0369, +0.4675, +0.1631, -1.1942, -0.2561, -0.0358, -1.2841, -0.7228, -0.7758, -1.0097, -0.9734, +0.0736, +0.0120, +0.2161, -0.4861, +0.1287, +0.5726, -0.1021, +0.0230, +0.2227, +0.0172, -0.3978, +0.2238, -0.0154, -0.0980, +0.2639, +0.4450, -0.1750, +0.1290, +0.3401, +0.0108, +0.3784, -0.5999, +0.7053, -0.2275, -0.1755, -0.8104, +0.1894, +0.4153, +0.3092, +0.1734, -0.3326, -0.1536, -0.1178, -0.6143, -0.1548, -0.2079, +0.0667, +0.1950, -0.4622, -0.4300, +0.4255, -0.0521, -1.0740, -0.2555, -0.3026, -1.4444, -0.7026, +0.3971, +0.2106, +0.2773, -0.1475, +0.1711],
-[ -0.7103, -0.2924, -0.1677, +0.5409, -0.8698, +0.1309, +0.1154, -0.6516, -0.9558, -0.9140, -0.0917, +0.0043, -0.1487, +0.0357, +0.3957, -0.1346, +0.6243, +0.0267, -0.1561, -0.9322, +0.5103, -0.2402, +0.2321, -1.1931, -0.1977, +0.0085, -1.2352, +0.2785, -0.5084, +0.3258, +0.3364, +0.2619, -0.0041, -0.1554, -0.0281, -0.4433, +0.2035, -0.0982, -0.0065, +0.4423, +0.2874, -0.4494, -0.0345, -0.3386, -0.4039, -0.8893, -0.1554, -0.2474, -0.1889, -0.1272, +0.2077, -1.2152, +0.4811, +0.1376, +0.1043, +0.3282, +0.0409, +0.0068, +0.1769, +0.1182, +0.4116, -0.3562, +0.0513, -0.5300],
-[ -0.1572, -1.5188, -1.5678, -0.4130, -0.4267, -0.1431, +0.1554, -0.3178, -0.7728, +0.2314, -0.2010, +0.2888, +0.1788, -0.1780, +0.0944, -0.9144, +0.5334, +0.2888, -0.2076, +0.1253, +0.2449, +0.1610, -0.2281, +0.0742, -0.0978, +0.2734, -0.3029, -0.2320, +0.1220, +0.0550, +0.1580, -0.1043, -0.2656, -0.0400, +0.2219, -0.6095, +0.1252, -0.1372, +0.3713, -0.5300, +0.1172, +0.2025, -0.4247, +0.0746, +0.1929, +0.0514, +0.2209, -0.5462, -0.2288, -0.7486, +0.2197, +0.1359, -0.7125, -0.8333, -0.5579, -0.8019, -0.5522, -0.2105, +0.1643, -1.0014, -0.4503, -0.6657, +0.4036, -0.0555],
-[ -0.0590, -0.3719, -0.5114, +0.2530, -0.7208, -0.0563, +0.3854, +0.3026, +0.0735, +0.3427, +0.6002, -0.1396, -0.1402, +0.1080, +0.1864, +0.3067, -1.0581, -1.9660, -0.2471, -0.0337, +0.0124, -0.2047, -0.6474, -0.8498, +0.0491, +0.0070, -0.1226, +0.0656, -0.2951, +0.0360, -0.9327, -0.2177, -1.0216, +0.6137, -0.5219, -0.3685, -0.0321, -0.2387, +0.6478, -0.0755, -0.0629, -0.7876, +0.2509, -0.3656, -0.1480, +0.1127, +0.5233, -1.2403, +0.1726, +0.3162, +0.3171, -0.6025, -0.6811, -0.9313, -0.1579, -0.1299, +0.1423, -0.1796, +0.2760, -0.4841, +0.1697, -0.1206, -1.3476, -0.4628],
-[ -0.3120, -0.7815, -0.7293, +0.2830, -1.2078, +0.3774, +0.5226, -0.7750, -0.7630, +0.6087, +0.6374, +0.2126, -0.1801, -0.1649, -0.0703, +0.0150, -0.5099, -0.8238, +0.2890, -0.5040, +0.0895, -0.2675, -1.6283, -0.6663, +0.1520, +0.1787, -0.1078, +0.0191, +0.2750, -0.6022, -0.2075, +0.1815, -0.0741, +0.4324, -1.1463, -0.3964, +0.4130, -0.8703, -0.1329, -0.4860, -0.3910, +0.1145, +0.1338, -0.1027, +0.2230, +0.2237, +0.0151, +0.3517, -0.5960, -0.1026, +0.0241, +0.0157, -0.3517, -0.0960, +0.2909, +0.2758, -0.2046, -0.0833, -0.1670, -0.4800, +0.3463, -0.9654, -0.4277, -0.4589],
-[ -0.1478, +0.1582, -0.2973, -0.1952, -0.1098, +0.5831, +0.6361, +0.3629, -0.1146, -0.6157, +0.5632, +0.4363, +0.0612, -0.9039, +0.1119, -0.5786, -0.5540, +0.0398, +0.1752, -0.5577, -0.6667, -0.2905, +0.2213, -0.0194, +0.3635, -0.6965, +0.0050, +0.0740, +0.1895, +0.1548, -0.5477, +0.4813, -0.6568, +0.7340, -1.0991, +0.0799, +0.1582, +0.0278, +0.5434, -0.1960, +0.4060, -0.6551, -0.0725, -0.4377, -0.7184, +0.1424, -0.8283, +0.7254, +0.4389, +0.5734, +0.2364, -0.5897, -0.0238, -0.0007, +0.3947, -0.0760, +0.1847, +0.1770, +0.0928, +0.3543, -0.4835, -0.3019, -0.9959, +0.0583],
-[ +0.1443, +0.2220, +0.1527, -0.3340, +0.2000, -0.1948, -0.2900, +0.3642, +0.1534, -0.0776, +0.1768, -0.1703, -0.2562, -0.2758, -0.4396, +0.0234, -0.1917, +0.1102, -0.2345, -0.1229, +0.0281, +0.0845, +0.1131, +0.4417, +0.0569, -0.3473, +0.0394, -0.0056, +0.0946, +0.0011, -0.7753, +0.1805, -0.1408, +0.1301, +0.0846, -0.4318, -0.3021, +0.0477, +0.0908, +0.0013, -0.3767, +0.2696, +0.4063, -0.3381, -0.7599, +0.1141, +0.3743, -1.1590, +0.0345, +0.2245, +0.2459, -0.2822, -0.4002, -0.7271, -0.1023, -0.3171, -0.1637, +0.2897, +0.1085, -0.4487, -0.0477, +0.1013, +0.0479, +0.0018],
-[ -1.0487, -0.2101, +0.2740, +0.0018, -0.1096, -0.8838, -0.4168, -0.3155, -0.2515, -0.1041, -0.0137, +0.3740, -0.1076, +0.2306, -0.4726, +0.0436, -0.3551, +0.3825, -0.2449, +0.4380, -0.7459, +0.2044, -0.5208, -0.7803, -0.0959, -0.2527, +0.0630, -0.9097, -0.0458, -1.0599, +0.3440, -0.3823, +0.0603, -0.7298, +0.3327, +0.3867, -0.2603, +0.0369, +0.6102, -0.0971, -0.0400, -0.2093, -0.3939, +0.2720, +0.4138, +0.0643, -1.0037, -0.2460, +0.1148, -0.3138, -0.1753, -0.0530, -0.8875, +0.3475, -0.3792, -0.8626, -0.3554, -0.2610, +0.0977, -0.1185, -0.3172, -0.0645, +0.0849, +0.3102],
-[ +0.6196, -0.2248, +0.3701, +0.3871, +0.1780, -0.8845, -1.1825, -0.2375, -0.3429, +0.1191, +0.4072, -0.4555, -0.1496, +0.1067, +0.0234, -0.8369, -0.0937, -0.0319, -0.2486, +0.0657, -0.6954, +0.2187, +0.3412, +0.2551, -0.3422, -0.0815, -0.2930, -0.2226, -1.1675, +0.5878, -0.5601, +0.1259, -0.0683, -0.2040, -0.0079, -0.1074, -0.1578, -0.1415, -0.1203, -0.9654, +0.7452, +0.0246, -0.3484, -0.0277, +0.1140, +0.1730, -1.0210, -0.5052, +0.3313, -0.2379, +0.1376, +0.1366, +0.3220, +0.2231, -0.7424, -0.1786, -1.4978, -1.3279, -0.3878, -0.0794, -1.7559, -0.0926, +0.2841, +0.0046],
-[ -0.0346, +0.2532, +0.3598, -0.0466, +0.0500, +0.0986, -0.4646, -0.2297, -0.4361, -1.7196, +0.2609, -0.4030, -0.2188, -0.2671, -0.1898, +0.1210, +0.6077, +0.1553, +0.0702, +0.1467, -0.2473, +0.1862, +0.3394, +0.2467, -0.4418, -0.1372, +0.5745, -0.3004, +0.1039, +0.1269, -0.4942, +0.1940, +0.5131, -0.2525, -0.7989, +0.2016, +0.3945, -0.1058, -0.6304, -0.6872, -0.1522, +0.6897, -0.0695, +0.1169, -0.0974, +0.0709, -0.2866, +0.2668, -0.0795, +0.3041, -0.1889, +0.1018, +0.2852, +0.4602, -0.1846, +0.5833, -0.1721, +0.6602, -0.6977, -0.2847, -0.0483, +0.0897, -0.0469, +0.1863],
-[ -0.0781, -0.3706, +0.2251, +0.2849, +0.0941, -0.2094, +0.6678, -0.0101, +0.0424, -0.0293, +0.2295, -0.1194, +0.0675, +0.0213, -0.1025, +0.3390, +0.1805, -0.2866, +0.2053, +0.2851, +0.4197, -0.1941, -0.4910, +0.2821, -0.2832, -0.1295, -0.0805, +0.1562, +0.2949, -0.3321, -0.7247, -0.4742, +0.3879, +0.2745, -0.3844, -0.6716, -0.3245, +0.4906, -0.2705, -0.2982, -0.1698, -0.7898, +0.1142, -0.1942, -0.3603, -0.1740, +0.3400, -0.0506, -0.3486, -0.2486, -0.0503, -0.3264, -0.5077, -0.0445, +0.1496, +0.2111, -0.6167, -0.3732, -0.9418, -0.7983, +0.0077, -0.2045, -0.7608, +0.1405],
-[ +0.2049, +0.1535, +0.2128, -0.4164, -0.2544, -0.6106, -0.7504, -0.3578, -0.2596, -1.0701, +0.0292, -0.1886, -0.1032, -0.5208, +0.0134, -0.3110, -0.7516, +0.4388, +0.0340, +0.0624, +0.0834, -0.0516, -0.1133, -0.7225, -0.2224, -0.5351, -0.0026, -0.6803, -0.0265, -0.1342, -0.2246, +0.2535, -0.5135, -0.4462, +0.3514, -0.0025, +0.1148, -0.5111, -0.2767, -0.1291, +0.2889, +0.1646, +0.4116, -0.5003, -0.1414, +0.4581, -0.0032, +0.2815, -0.1550, -0.1487, -0.2589, -0.7931, -1.5351, +0.6082, -0.8509, -0.5817, +0.3463, +0.1935, +0.4886, +0.3674, -0.1345, -0.5708, -0.5943, -1.0342],
-[ -0.4535, -0.7263, +0.1911, -0.1976, -0.0240, -0.2905, -0.3329, -0.2344, +0.1119, -0.7598, +0.2671, -0.0547, +0.0231, -0.1666, -0.1475, -0.9600, -0.2575, -0.5557, -0.0586, +0.1305, -0.7248, -0.1328, -0.0749, -0.1792, -0.0993, +0.0632, +0.0370, -0.0350, -0.2100, -1.0003, -0.2526, +0.4889, -0.0268, -1.0811, -1.0744, -0.2632, +0.6099, +0.1728, -0.3989, -0.4078, +0.4547, -2.1630, +0.0652, -0.1967, +0.0211, -0.7390, -1.2135, -0.2196, -0.0140, -0.4225, -0.0909, +0.3659, +0.2051, +0.1075, -0.2806, -0.2124, -0.0317, +0.0040, -1.0535, -0.0977, -0.0551, -0.4167, -0.4222, -0.5449],
-[ -0.5821, +0.1573, +0.3883, -0.0208, +0.0267, -0.1548, +0.0036, +0.0238, +0.2573, -0.2390, +0.1001, -0.4440, +0.1714, +0.4488, -0.0916, -0.0133, +0.0881, +0.1937, +0.0243, +0.0557, -0.0183, -0.3184, -0.0971, +0.1885, -0.1141, -0.0808, +0.2792, +0.3806, +0.1167, -0.0970, -1.1862, -0.3819, -0.0736, -0.2230, -0.2072, -0.4767, +0.3344, -0.4753, +0.4085, -0.9508, -1.3361, -0.5341, -0.2721, -0.2227, -0.2407, -0.2488, +0.0815, +0.0050, -0.0188, +0.1103, +0.3057, -0.1838, +0.1879, +0.0258, -0.0092, +0.2777, -2.1384, -0.0154, -0.0746, +0.1013, -0.0875, -0.4639, -0.1884, +0.3613],
-[ -0.3665, -0.1782, +0.0419, -0.2690, -0.3408, +0.7867, +0.3313, -0.9157, +0.4388, -0.4855, -1.2508, -0.4405, -0.2233, +0.0522, +0.4611, -0.3997, -0.5933, -1.3610, -0.3253, -0.1574, +0.0802, -0.4449, -0.6778, -0.3988, -0.2578, -0.7707, -0.7587, -0.0789, -0.0164, +1.0809, +0.1280, -0.4027, -1.1598, +0.7488, -0.6504, +0.0912, +0.5017, -0.1733, -0.5198, -0.7894, -0.0064, -1.4117, +0.1238, -1.8378, -0.0063, +0.7132, -0.0657, -0.0301, +1.1850, -0.3432, -0.5329, +0.2786, -0.8299, -0.5956, +0.0208, -0.4721, +0.2628, -0.3157, +0.1742, -0.8047, +0.0856, +0.2113, -0.6971, -0.1566],
-[ -0.6693, -0.1809, +0.0884, -0.1358, +0.5172, -0.0687, -0.0120, -0.3826, -0.5306, -0.0103, +0.8560, -0.3482, +0.0860, +0.3675, -0.5334, -0.0405, +0.2357, -0.2945, -0.4034, +0.3049, -0.6580, -0.2272, -0.5667, -0.0805, -0.0008, +0.3024, -0.2402, -0.5567, +0.2349, -0.4490, -0.3248, +0.3113, -0.0458, +0.5295, -0.8893, -0.1700, +0.1197, -0.0317, +0.2407, -0.3567, -0.3077, -0.4958, +0.3886, +0.4175, -0.0700, -0.4049, +0.3392, -0.1947, +0.7443, +0.2133, +0.3215, +0.0441, -0.5935, -0.3116, -0.0350, -0.7650, -0.6026, -0.3508, -0.1284, -0.9857, -0.1828, -0.2976, -0.2231, -1.0016],
-[ +0.0507, -0.0567, +0.2445, -0.0756, -0.0082, +0.4970, -0.0516, -0.0301, +0.3676, -0.1720, +0.0047, -0.3551, -0.0340, -0.0532, -0.4424, -0.3569, -0.0102, -0.1321, +0.1088, -0.2266, -0.8376, -0.6879, +0.5277, +0.1749, +0.0183, -1.0760, -0.5535, +0.1199, +0.0335, -0.4466, +0.0450, -0.9575, -0.7582, +0.5908, -0.6280, +0.5010, -0.0937, +0.4709, +0.1345, -0.1088, -0.4050, -0.9498, +0.1079, -0.0437, -0.1768, -0.8175, +0.3442, -0.0402, -1.4693, +0.2791, +0.1296, -0.0762, +0.0142, -0.9085, +0.3446, +0.1278, -0.0685, -0.5707, +0.4476, +0.0823, -0.4022, -0.5325, -0.5841, -0.2564],
-[ +0.0898, -1.1540, -0.9679, -0.3278, +0.1902, -0.3525, +0.0045, -0.2419, -0.9443, +0.2821, -0.4016, -0.3287, -0.0096, -0.2795, +0.3097, -0.2414, +0.1993, -0.0236, -0.2561, -0.1521, +0.1322, +0.0188, +0.2566, -0.7166, -0.0330, +0.1491, -0.1133, +0.1535, -0.2132, -0.2450, -0.3134, -0.0497, -0.4828, -0.0163, +0.0998, -0.0427, +0.0128, +0.4167, -0.4010, +0.3123, +0.1781, -0.0243, -0.1447, -0.4638, -0.6196, +0.1720, -0.1308, -0.7977, -0.4340, -0.3038, -0.9074, -0.1848, +0.1264, +0.0249, -0.5808, -0.0785, -0.1180, -0.6689, +0.4223, -0.0547, +0.3043, +0.1254, +0.2954, -0.2502],
-[ +0.0870, +0.0780, -0.0389, +0.1600, -0.0364, +0.2506, +0.0564, +0.2378, +0.0033, -0.1340, -0.1532, +0.3440, -0.4366, -0.1984, +0.0098, +0.1903, +0.0752, -0.1213, +0.0378, -0.1293, +0.0029, -0.1710, +0.1367, -0.0665, -0.0351, -0.1341, -0.1123, -0.2100, -0.0160, -0.0597, -0.2886, +0.1219, -0.0732, +0.2243, -0.3820, -0.1373, -0.0118, +0.0217, +0.2059, +0.0855, -0.0949, -0.0514, -0.0669, -0.3338, -0.4548, -0.0133, +0.0292, -0.0179, +0.1236, +0.2291, +0.2861, -0.2900, -0.0856, -0.2934, +0.0034, -0.3797, +0.0143, +0.0729, +0.0875, +0.2393, -0.0385, -0.1214, +0.0479, -0.0652],
-[ -0.7501, -1.1375, -0.2978, -0.8633, -0.8919, +0.2189, -0.5857, -0.2409, +0.0604, -0.0567, -0.1097, +0.2126, +0.0844, -0.3906, +0.3503, -0.9469, +0.0383, -0.3880, +0.1532, -0.7949, +0.2010, -0.3122, -0.3812, -1.0744, -0.0195, -0.4764, +0.2610, -0.7452, +0.1366, +0.2796, +0.2770, -0.2790, -0.7372, -0.2902, -0.7949, -0.1160, -0.1794, -0.6606, -0.0722, -0.1698, +0.1217, +0.2441, +0.2072, -0.3946, +0.1858, -0.1417, -0.9906, -0.2096, -0.0386, -0.3452, +0.3401, -0.3946, -0.0491, +0.0953, -0.5440, -0.9668, -1.4922, +0.0952, +0.2255, -0.0070, -0.0929, -0.6225, +0.2984, -0.1608],
-[ +0.0875, -0.8502, +0.2431, -1.4256, -0.0134, -0.5211, +0.1531, -0.3139, -0.2330, -0.0786, -0.0809, -0.1122, -0.1306, -0.0140, +0.4723, -0.6809, -1.0225, +0.1196, +0.1491, -0.2224, -1.9714, -1.6552, -0.0284, -0.6446, +0.1878, -0.0111, +0.2549, -0.5032, +0.2373, -0.2167, +0.0885, -0.0815, -0.8509, -0.9426, -0.4842, +0.2617, +0.0947, +0.8169, -0.0459, +0.1221, -0.0595, -0.5754, -0.5843, -1.3281, +0.1531, -1.3252, -0.7069, -0.5561, +0.1954, +0.0952, -0.5631, +0.2066, +0.7464, +0.1565, -1.3679, -0.5306, +0.1436, -0.5271, -0.1679, -0.0539, +0.5787, -0.2023, +0.3189, -0.4968],
-[ +0.0315, -1.1600, -0.1894, +0.1841, -0.0069, -0.9793, -0.0278, -0.9642, -1.0357, +0.5406, -0.1473, +0.2056, -0.3358, +0.3904, -0.0970, -1.3872, +0.2364, +0.2908, +0.0140, -0.1797, -0.0895, +0.1147, +0.0184, +0.2090, -0.2029, -0.0183, +0.3583, -0.6774, -0.3236, +0.4919, +0.1323, -0.3519, +0.2735, -0.4859, +0.1274, +0.0592, +0.0293, -0.0612, -0.2484, +0.0962, -0.4288, +0.5136, -0.6259, +0.2224, +0.2347, +0.0524, -0.0633, +0.0179, +0.0616, -0.9062, -0.1752, -0.0501, +0.3795, +0.4146, +0.0351, +0.3203, -0.0841, -1.0873, -1.3012, -0.3519, +0.3106, +0.3838, +0.1764, -0.1131],
-[ -0.0067, +0.0395, -0.7516, -0.2958, -0.1750, +0.4141, -0.3325, -0.3768, -0.4620, +0.8233, +0.3492, -0.0237, +0.0106, -0.8323, +0.3937, -0.1977, -0.4075, -0.2006, -0.0474, +0.3061, +0.0789, -0.2584, -0.0647, +0.1114, +0.0884, +0.4178, -0.6012, -0.1629, +0.4286, +0.4013, -0.9800, -0.6920, +0.3876, +0.7810, -0.7333, -0.0620, -0.2162, -0.4436, -0.1308, +0.0799, -0.0925, -1.3182, +0.3494, -0.7913, +0.1979, +0.5827, +0.2238, +0.0280, +0.0497, -0.0354, -0.0631, +0.8220, -0.1120, -0.2673, +0.1897, -0.6081, -0.1298, -0.7712, -0.2133, -0.6315, -0.3532, -0.9268, +0.2826, +0.2492],
-[ -0.6092, -0.1699, +0.0756, -1.0743, +0.7791, -0.0013, +0.0261, +0.0341, +0.0039, -1.3614, +0.0474, +0.1043, -0.1149, -0.3031, -0.1387, -0.2534, -0.1865, -0.0783, +0.0465, +0.1722, +0.0714, -0.3566, -0.3526, -0.3374, -0.2516, +0.0578, -1.6820, +0.6733, +0.1903, +0.3942, +0.0378, -0.0427, -0.0685, +0.2141, -0.7520, -0.5861, -0.1980, -0.8542, -0.2299, -0.4345, -0.1855, -0.1432, +0.3582, -0.4741, -0.5136, +0.3023, -0.0360, -0.0623, +0.1555, -0.1655, +0.2128, -0.4508, -1.2209, -0.0260, +0.0659, -1.1528, +0.2362, -0.5791, -0.2722, -0.1899, -0.1704, +0.0203, -0.7536, +0.2306],
-[ -0.1456, +0.4228, -0.2169, -0.1864, +0.2956, +0.0975, -0.4902, -0.4168, -0.0061, -0.0129, +0.5856, +0.0718, -0.1802, -0.3765, +0.3940, -0.0377, -0.1783, +0.1068, +0.1506, +0.1025, -0.4088, +0.1379, +0.4524, -0.2770, +0.0499, +0.0828, +0.0832, +0.1792, -0.0652, +0.3557, +0.1142, +0.1000, +0.5156, -0.0644, -0.2629, -0.4445, +0.2076, +0.1216, +0.3907, +0.0722, -0.0435, -0.1319, +0.2939, +0.1871, -0.1707, -0.1241, +0.0260, -0.0176, +0.7158, +0.0326, +0.2360, -0.0155, -0.2790, -0.0850, -0.0872, +0.0258, +0.1475, -0.2429, -0.3992, -0.5970, -0.0884, +0.0104, +0.2510, -0.3747],
-[ -0.1019, +0.0217, +0.0604, +0.2556, +0.0670, -0.2470, -0.0896, +0.0972, -0.5061, -0.0539, -0.1494, -0.6850, -0.1314, +0.4489, +0.3238, -0.1830, -0.3250, -0.4818, +0.1131, +0.0809, -0.1849, +0.0768, -0.4203, -0.1073, +0.0289, +0.0777, -0.2676, -0.1635, +0.2819, -1.1156, +0.4612, -0.5983, +0.2212, -0.2626, -0.3611, -0.8076, +0.0604, +0.1751, -0.1189, -0.8877, +0.1995, -0.5779, +0.1674, +0.1556, -0.4025, -0.7868, -0.6574, -0.0562, -0.3712, -0.0835, +0.2261, -0.0039, -0.0864, +0.1381, -0.2375, -0.1138, +0.0788, -0.7128, -2.4133, +0.2474, -0.5965, +0.0887, -0.3717, +0.1583],
-[ -0.0173, -0.8841, -0.1036, -0.4535, -0.0171, -0.5824, -0.0683, -0.1105, -0.6359, +0.0860, -0.4490, +0.1697, -0.1639, +0.2569, +0.2831, +0.2610, -0.6809, -0.4909, -0.5067, -0.2111, +0.0006, -0.9312, -0.1564, -0.0030, -0.4018, -1.0880, -0.2422, -0.5496, +0.4572, -0.2074, +0.5928, -0.6699, +0.2007, -0.1501, +0.6496, +0.0006, -0.8182, +0.1627, -0.9395, -0.1071, -0.1078, +0.5001, -0.9152, -0.0298, +0.2665, -0.2468, +0.3327, +0.1171, +0.2442, -0.4903, -0.3593, +0.0516, -0.2479, +0.0401, +0.2455, +0.1927, +0.4553, -0.4156, +0.4963, -0.4824, -0.7662, +0.1025, -0.1231, -0.0549],
-[ -0.5653, -0.0579, +0.0711, +0.1978, +0.1483, -0.2487, +0.5816, -0.2505, -1.0865, -0.3124, +0.4662, +0.3429, +0.1187, +0.3957, -0.3051, -0.2266, -0.5454, -0.4433, +0.1236, -0.2226, +0.1168, -0.1802, -0.2434, -1.0033, -0.3189, +0.1394, -0.7433, +0.5946, +0.1073, -0.4106, -0.5485, -0.5361, +0.3073, +0.3227, -0.6396, -0.2144, +0.3187, -1.2617, +0.1526, -0.4829, +0.1673, -0.4504, +0.3942, -0.6261, +0.1535, +0.1946, -0.2928, -1.2917, -0.4011, +0.0209, -0.2192, +0.1189, -0.2842, -0.3277, -0.0050, +0.1858, -0.7773, -0.1619, -0.2147, -0.6281, +0.3831, -0.8085, -0.6315, +0.4716],
-[ -0.8026, -0.3107, +0.0903, +0.0076, +0.4653, +0.2245, +0.1581, +0.3757, +0.3310, -1.2516, -0.1040, -0.6431, +0.0373, +0.0716, +0.1643, -0.6158, -0.0895, +0.2540, -0.1583, -0.0699, +0.1837, +0.4705, -0.9086, -0.0468, -0.2022, +0.2916, -0.3869, +0.1620, -0.2646, -0.1511, -0.2067, -0.3882, -0.6044, -0.1775, -0.8657, +0.2309, +0.3567, +0.0654, +0.5363, +0.0686, -0.0198, -0.9192, -0.1272, +0.5987, -0.0621, -0.3943, -0.0519, -0.5483, +0.0777, -0.5409, -0.0296, +0.0010, +0.2560, -0.1014, -0.8840, -0.4932, -0.2339, -1.0472, -0.4789, -0.2379, -0.6807, -0.0958, +0.2527, -0.5875],
-[ +0.0894, +0.2394, +0.4565, +0.5095, -0.9334, -1.2892, -0.8885, +0.0167, +1.0713, -0.3041, -0.7280, +0.2223, -0.5221, -0.0032, -0.0743, +0.1534, +0.5751, -0.1298, -0.1282, -0.4674, +0.5752, +0.2239, +0.4114, +0.3252, -0.1642, +0.2532, +0.3494, -0.8035, -0.2348, +0.3177, -0.5218, +0.0481, -0.3052, -0.9177, +0.1627, +0.6603, -0.7468, +0.0274, +0.0626, +0.0355, -0.2757, +0.2697, +0.4732, -0.2061, -0.0190, +0.5470, -0.5898, -0.8168, -0.0884, -0.4522, -0.1064, -0.8207, +0.2726, +0.1109, -0.2514, +0.1580, +0.6825, +0.7124, +0.8108, +0.2258, -0.1274, +0.2130, -0.3830, -0.9575],
-[ +0.0671, +0.2013, -0.4460, -1.0518, -0.0167, +0.1024, +0.0547, +0.3296, +0.0516, +0.0503, +0.1956, -0.0536, +0.0108, -0.2160, +0.1852, -0.0177, -0.4770, -0.2327, -0.2887, +0.2862, -0.0357, +0.0026, -0.6428, -0.5677, -0.0354, -0.0304, -0.1272, +0.1630, -0.1319, -0.1122, +0.3381, +0.0000, -1.0265, +0.1319, -0.2374, -0.1598, -0.0059, +0.1722, +0.2300, +0.1748, -0.0167, -0.0891, +0.0350, -0.4563, -0.5325, +0.0078, -0.2475, +0.1184, +0.0133, +0.2512, +0.3639, -1.5981, -0.5117, -0.2703, +0.0222, -0.5620, -0.1466, -0.1626, -0.3288, -0.0070, +0.0508, -0.3687, -0.4245, -0.2751]
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ +0.6734, +1.1364, +0.6117, +0.5185, +0.5099, -0.2038, -0.0045, -0.1448,
+ +0.5081, +1.1685, -0.7904, -0.4623, +0.0027, -0.0473, -0.1144, +0.5095,
+ -0.1913, +0.2021, +0.3485, +0.1104, -0.4992, +0.5207, -0.1013, -0.6947,
+ +0.1624, +0.3533, -0.2485, -0.0012, +0.1674, +0.1253, +1.5485, +0.3576,
+ +0.8236, +0.7361, +0.6604, -0.0834, +0.1212, -0.8404, -0.8337, +0.3709,
+ -0.4218, -0.1011, -1.1418, -0.0554, +0.6676, +0.4739, -0.2105, +0.3187,
+ -0.4321, -0.7018, +0.1845, +0.2525, +0.0205, +0.9391, +0.6123, +0.6868,
+ +0.5116, +0.3483, +0.1148, +0.6747, -0.1590, +0.1879, +0.4836, +0.1997,
+ +0.5105, -0.2695, +0.0645, +0.5566, +0.0502, +0.2292, -0.4234, -0.3778,
+ -0.7639, -0.6084, -0.0375, -0.4799, +0.6465, -0.4097, +0.1091, -0.0681,
+ -0.1813, +0.3625, +0.6067, +0.1837, +0.1600, -0.1706, +0.0531, -0.3710,
+ +0.1320, +0.5035, +0.1106, +0.9955, -0.2657, +0.6051, -0.2525, -0.9118,
+ -0.6031, +0.2025, -0.2774, +0.3985, -0.0809, +0.3601, -0.0410, -0.5067,
+ +0.4987, +0.4126, -0.1393, -0.6596, +0.8182, -0.2352, -0.9337, +0.1438,
+ +0.3871, -0.1844, -0.4010, -0.3338, +0.1597, +0.2381, -0.4403, +0.5105,
+ +1.0354, -0.1503, +0.2731, +0.6555, +0.2048, +0.4932, -0.0067, +0.0413
+ ],
+ [
+ -0.0031, -0.2183, +0.2275, -0.4836, +0.1347, +0.3581, +0.0921,
+ +0.1900, -0.1721, +0.0150, -0.2146, +0.5346, +0.2407, -0.0791,
+ +0.5115, -0.0763, +0.2025, +0.2792, +0.4087, +0.2082, +0.0086,
+ -0.2742, +0.3703, +0.4297, -0.3141, -0.3896, +0.4101, -0.3967,
+ -0.2173, -0.0532, +0.2521, +0.3938, -0.3727, +0.6136, +0.0902,
+ -0.4617, -0.3266, -0.2273, +0.0031, +0.4605, +0.1221, +0.3603,
+ -0.1018, +0.1839, +0.3198, -0.1404, -0.1751, -0.1030, -0.5847,
+ +0.2526, -0.1280, +0.1644, +0.2988, -0.1793, -0.2120, +0.3398,
+ -0.4582, +0.0758, -0.2848, -0.1537, -0.2718, -0.2207, +0.0109,
+ +0.1374, -0.0281, -0.0494, -0.0093, +0.0098, +0.2691, +0.1589,
+ +0.2483, +0.1394, +0.2531, +0.3884, +0.0740, -0.4444, +0.1441,
+ +0.0768, +0.2154, +0.4015, -0.2109, -0.0985, -0.1066, -0.0167,
+ -0.0204, -0.2345, +0.3131, +0.1026, +0.1873, +0.2644, +0.2253,
+ -0.0173, +0.1014, +0.0781, +0.0455, -0.0489, -0.3541, -0.1257,
+ -0.1248, +0.4402, -0.0682, -0.3045, +0.1751, +0.0397, -0.3392,
+ -0.2758, +0.1542, -0.0460, -0.0622, +0.2255, +0.2442, +0.2070,
+ +0.3175, -0.0913, -0.2772, +0.7036, -0.0876, +0.0907, +0.3794,
+ +0.4784, -0.5111, +0.0982, -0.0145, +0.0397, -0.3429, -0.2727,
+ -0.1384, +0.0512
+ ],
+ [
+ +0.2192, +0.0688, -0.1092, +0.1436, -0.2598, -0.0012, -0.2220,
+ -0.2450, -0.0783, -0.0078, +0.3065, +0.1604, -0.0593, -0.0759,
+ -0.4101, -0.1819, +0.4160, +0.0141, +0.0059, -0.2494, -0.0616,
+ -0.3100, -0.3231, -0.3935, +0.1965, -0.0352, -0.0119, +0.3883,
+ -0.5905, -0.0536, -0.0617, -0.2884, +0.1134, +0.1539, +0.2002,
+ -0.3158, -0.5476, -0.4131, -0.1966, +0.1083, -0.3329, +0.1219,
+ +0.2977, -0.7132, -0.1963, -0.2359, -0.4734, +0.0130, -0.1034,
+ -0.1376, -0.1824, +0.1999, -0.3775, -0.0697, +0.1875, -0.0673,
+ -0.0673, -0.0555, -0.3243, +0.2020, +0.1416, +0.1995, -0.1931,
+ -0.6125, -0.3465, +0.0640, +0.3529, -0.4684, +0.2335, -0.0449,
+ -0.1216, +0.1921, +0.0636, -0.0420, +0.1371, -0.1246, -0.2963,
+ +0.0264, +0.3962, -0.3106, -0.2107, -0.2983, +0.0386, -0.0458,
+ -0.3277, -0.1686, -0.3064, +0.2433, +0.3454, +0.0046, +0.0885,
+ -0.2479, +0.2886, -0.0804, +0.0110, -0.1369, -0.1210, +0.1901,
+ +0.0001, -0.1155, +0.2887, -0.0943, -0.1167, +0.1746, +0.0379,
+ +0.0964, -0.2615, -0.0209, -0.0680, +0.0031, -0.0905, -0.0618,
+ -0.5630, -0.0664, -0.1976, -0.2367, -0.2360, -0.2243, +0.2448,
+ +0.2446, -0.0012, -0.6920, -0.0880, -0.4630, -0.5512, +0.0312,
+ +0.1522, -0.1278
+ ],
+ [
+ -0.2378, +0.2783, +0.0848, -0.3973, -0.5359, +0.2541, +0.1616,
+ +0.1856, +0.6054, +0.0894, +0.2599, -0.0082, -0.5433, -0.3567,
+ -0.1134, -0.2706, -0.9177, +0.1949, +0.4099, -0.3198, +0.3856,
+ -0.0285, -0.0692, +0.0882, -0.1052, -0.0122, -0.0271, -0.4122,
+ -0.0921, -0.2014, +0.0314, -0.0638, -0.0986, +0.1912, +0.6157,
+ -0.0856, +0.0450, +0.3492, -0.0958, -0.1261, +0.1242, +0.0930,
+ +0.1372, -0.1914, +0.4377, +0.0586, +0.2271, -0.1985, -0.1012,
+ -0.2074, +0.2934, -0.2271, -0.4235, -0.0077, -0.2304, -1.1012,
+ -0.1832, -0.1528, -0.4307, -0.4059, -0.4289, +0.1290, -0.1688,
+ -0.0446, +0.2036, -0.5397, -0.3280, +0.3672, -0.3012, -0.1896,
+ +0.0923, +0.1472, -0.0703, -0.0328, -0.1597, -0.3102, -0.4221,
+ +0.3261, +0.4840, +0.0083, +0.2617, -0.2548, -0.5314, -0.4192,
+ +0.6303, +0.2605, -0.6675, -0.0837, -0.8402, -0.4546, +0.2169,
+ +0.0480, +0.2543, +0.0004, +0.2982, -0.2037, -0.4812, +0.0583,
+ -0.8738, +0.0586, -0.3745, -0.5477, -0.2971, -0.1551, -0.4880,
+ -0.1060, +0.2188, -0.4043, -0.0349, -0.1349, -0.4093, -0.4371,
+ +0.3101, +0.5219, -0.0655, -0.2546, -0.6408, +0.2019, +0.1351,
+ +0.0971, -0.4105, +0.1299, -0.6688, -0.0550, -0.2388, -0.4246,
+ +0.1126, -0.5573
+ ],
+ [
+ +0.3232, -0.0110, -0.0201, -0.2022, +0.1144, -0.2510, -0.3709,
+ +0.4360, -0.4248, +0.1316, -0.5286, -0.0186, +0.2077, +0.2049,
+ +0.2458, -0.3234, -0.0890, +0.2950, +0.0363, +0.0579, -0.0995,
+ +0.1529, -0.0182, -0.2339, +0.0239, -0.3706, +0.2179, +0.1782,
+ +0.1137, +0.3492, -0.1769, +0.1565, +0.2168, -0.0898, +0.4457,
+ +0.4303, +0.3227, +0.1329, -0.0832, +0.0037, -0.1080, -0.1041,
+ +0.0529, +0.2101, -0.1206, +0.1770, -0.1607, -0.2222, -0.3057,
+ +0.0691, -0.1493, -0.1024, +0.1907, +0.0748, +0.3616, -0.5097,
+ -0.4243, +0.1401, -0.4711, -0.4066, -0.4260, -0.3973, -0.3461,
+ +0.2407, +0.1542, -0.3836, -0.2245, -0.0567, +0.3746, -0.3234,
+ +0.4039, +0.0513, -0.1164, +0.3607, -0.1126, +0.0400, +0.2217,
+ +0.1035, +0.0252, -0.1768, -0.4746, -0.3228, -0.3284, -0.0242,
+ +0.0163, -0.2037, +0.0809, -0.0400, -0.0311, +0.3103, -0.1519,
+ +0.0303, +0.3008, +0.1998, -0.1943, +0.2562, +0.5656, -0.0671,
+ +0.3937, +0.4006, +0.3835, -0.0457, +0.5424, +0.2108, -0.0296,
+ -0.1178, -0.0066, -0.5670, -0.1310, +0.2254, +0.0798, +0.0547,
+ -0.0507, -0.2947, +0.0727, -0.4834, +0.0126, +0.2459, +0.2963,
+ +0.2442, +0.1020, +0.0645, +0.6951, -0.4037, -0.1358, +0.4485,
+ -0.1978, -0.0996
+ ],
+ [
+ +0.3579, +0.4973, -0.5223, +0.4582, -0.3209, -0.1405, -0.3946,
+ +0.4934, -0.2217, +0.4501, +0.2339, -0.5480, +0.0177, -0.7866,
+ -0.0221, +0.0816, -0.6471, +0.2561, -0.0114, +0.7428, -0.0908,
+ +0.1886, -0.0973, +0.3981, -0.2908, +0.3556, -1.2527, -0.7678,
+ -0.1662, -0.0463, +0.8122, -0.7603, +0.8625, -0.3672, -0.0821,
+ +0.4161, +0.6106, +0.3156, -0.3068, +0.9691, +0.4397, +0.2930,
+ -0.3802, -0.0977, -0.2970, -0.5699, +0.3788, +1.1378, -0.6848,
+ -1.0195, +0.2025, +1.3364, -0.0277, -0.2723, -0.5642, +0.3973,
+ -0.1903, +0.6823, -0.2150, +0.6972, -0.0855, -0.1414, +0.7036,
+ -1.0000, -0.1264, -0.1947, +0.9226, +0.1346, -0.4493, -0.3550,
+ -1.0708, +0.2620, +0.0332, -0.3827, -1.0002, +0.9836, +0.2433,
+ -1.1610, +0.3742, -0.0695, -0.5658, -0.2597, +0.3667, +1.2486,
+ -0.5875, -0.1238, +0.9558, +0.6116, -0.4355, +0.3359, -1.2784,
+ +0.1217, -0.0572, -0.4791, -0.5930, -1.4577, -0.6798, +0.6478,
+ -0.4734, +1.3337, +0.0625, -0.1462, -0.4832, -0.2721, -0.3731,
+ +1.0106, -0.5080, -0.7930, +0.3208, -0.5621, +0.3719, +0.0714,
+ +0.1665, +0.0678, -0.0667, -0.0222, +0.3113, -0.8660, +0.9910,
+ -0.3596, -0.9364, -0.2329, -0.0983, -0.0231, -0.9173, -0.4387,
+ -0.1335, +0.0457
+ ],
+ [
+ +0.3956, -0.3152, +0.2209, +0.5020, -0.1946, +0.1046, +0.2062,
+ +0.3388, +0.0394, -0.3347, +0.0989, -0.3360, -0.5885, -0.2084,
+ -0.0802, +0.1041, +0.4200, -0.5033, +0.2403, +0.3485, -0.1897,
+ +0.1247, -0.3015, -0.5448, -0.2833, -0.2345, +0.3037, -0.0964,
+ -0.0418, +0.4569, +0.5159, +0.1612, -0.1066, -0.1735, +0.1562,
+ -0.1419, +0.0397, -0.5056, +0.5741, +0.1335, -0.5054, +0.2876,
+ +0.2772, -0.4229, +0.3375, +0.1689, -0.0673, -0.1658, -0.0537,
+ +0.0839, +0.0286, +0.2321, +0.0324, -0.3339, +0.3598, +0.2639,
+ -0.1830, +0.0786, +0.0150, -0.5155, -0.2999, -0.3272, -0.1231,
+ +0.0314, -0.2119, -0.2094, +0.1294, -0.1965, +0.0588, -0.6383,
+ -0.0198, -0.1309, +0.5456, +0.1369, +0.5467, +0.1478, +0.0873,
+ +0.0337, -0.1971, -0.4118, +0.2234, +0.3570, -0.0030, -0.4428,
+ +0.2950, +0.0275, -0.0361, -0.2056, +0.1671, -0.5099, +0.1179,
+ -0.0046, -0.3599, +0.2915, -0.1620, -0.4229, +0.0425, -0.2419,
+ +0.5708, +0.2975, +0.2598, -0.5877, -0.2703, -0.1468, -0.5714,
+ +0.1464, -0.3119, -0.0598, +0.4885, -0.0556, -0.2712, +0.1269,
+ -0.3214, -0.2681, -0.1313, -0.0982, -0.1379, -0.0300, -0.1540,
+ -0.3185, -0.0519, -0.2397, -0.0479, -0.2774, +0.3924, -0.2064,
+ -0.1053, +0.4871
+ ],
+ [
+ -0.1492, +0.3323, -0.4775, -0.5605, -0.8677, +0.7841, +0.7171,
+ +0.8697, +0.2130, +0.4039, +0.9357, -0.8427, +0.0227, +0.2223,
+ -0.4140, -0.7540, -0.2611, +0.5574, +0.2121, -0.3201, +0.0518,
+ +0.3469, +0.3044, +0.6718, +0.4063, +0.9037, +0.2910, -0.5208,
+ +0.2262, +0.5543, -0.1615, -0.2219, -0.7828, +0.0647, +0.2140,
+ +0.9491, +0.0749, +0.2561, +0.2599, -0.2359, +0.4074, -0.2257,
+ +0.0635, +0.1117, +0.5031, -0.2702, -0.0526, +0.1067, -0.1765,
+ +0.0509, +0.2734, -0.2659, -1.0558, -0.3635, +0.4609, +0.0294,
+ -0.6205, +1.3626, -0.1060, +0.2375, -0.4266, +0.6304, -0.9487,
+ -0.2076, +0.3588, -0.2924, +0.2451, +0.5756, -0.1227, +0.1409,
+ -0.2573, +0.8268, -0.3649, +0.7991, -0.2339, -0.2500, -0.2263,
+ +0.0482, +0.9563, -0.2986, +0.5015, +0.2141, -0.3226, +0.3428,
+ +1.1022, +0.3828, -0.1544, +0.4925, -0.0866, +0.2472, -0.0740,
+ -0.0906, +0.6950, +0.4435, -0.2513, +0.0544, +0.1793, +0.9038,
+ +0.3841, -0.3180, -0.2950, +0.0953, +0.4973, -0.3028, -0.0141,
+ +0.0051, +0.9349, +0.0603, -0.1071, +0.2711, +0.0975, +0.6570,
+ +0.1094, +0.1404, +0.9337, -0.2258, -0.5518, +0.0847, +0.8611,
+ +0.0640, -0.3152, +0.3464, -0.2628, +0.2387, -0.1313, -0.3580,
+ +1.7605, -0.7844
+ ],
+ [
+ -0.1598, -0.0421, -0.4126, -0.4364, -0.2147, +0.4256, -0.0339,
+ -0.3245, -0.4184, +0.0827, -0.5233, -0.3281, -0.3892, -0.5833,
+ -0.0462, -0.5472, +0.0374, +0.0243, -0.3826, -0.1234, -0.6757,
+ -0.2869, -0.2674, +0.0504, +0.2552, +0.0059, -0.0716, -0.0678,
+ -0.2011, +0.1214, -0.0007, +0.2210, -0.3461, +0.0562, -0.5642,
+ +0.1014, -0.5826, -0.1434, -0.1884, -0.4357, -0.0456, -0.1590,
+ -0.3123, -0.1467, -0.2865, +0.2239, -0.1522, -0.4315, -0.0772,
+ +0.2507, -0.6389, -0.3853, -0.1505, +0.5287, +0.1969, +0.3432,
+ +0.1255, +0.3163, -0.3674, +0.3488, +0.0463, +0.2907, -0.2616,
+ -0.1169, -0.0705, +0.3281, +0.0255, +0.2221, -0.0777, -0.3293,
+ -0.3078, -0.6078, -0.1859, -0.2359, -0.1811, -0.3349, -0.1777,
+ -0.0656, -0.6531, -0.3420, -0.3709, -0.1240, -0.2513, +0.1877,
+ +0.0152, +0.0720, +0.1846, -0.1148, -0.1539, +0.0653, +0.0752,
+ -0.7600, -0.0605, +0.0614, -0.5569, -0.2471, -0.0556, -0.6890,
+ -0.2103, -0.2875, -0.2620, +0.0966, -0.4809, +0.2514, +0.0813,
+ -0.4869, -0.1030, -0.3295, -0.0645, -0.3906, -0.0294, +0.0987,
+ -0.0403, -0.8376, -0.4490, -0.1942, -0.0488, -0.6031, -0.2849,
+ -0.3964, +0.3836, -0.2380, -0.0565, -0.0857, +0.3379, -0.1756,
+ +0.1558, -0.0667
+ ],
+ [
+ -0.6008, -0.1594, -1.3237, -0.1536, +1.9008, -0.6173, -0.1694,
+ -0.5906, -0.9055, +0.0241, -0.5906, +1.1458, +0.2310, +0.1497,
+ -0.8268, +0.4505, +1.4660, -0.6533, +0.7903, -0.0505, -0.3790,
+ -0.1951, -0.2461, +0.1151, +1.0092, -0.2464, -0.0728, +1.2368,
+ -0.0530, -0.4323, -0.4228, -0.4808, +0.1259, +0.3584, -0.7628,
+ +0.4720, +0.0326, +0.3357, +0.5799, +0.0110, -0.6230, -0.9810,
+ +0.2532, +0.7874, -0.8300, +0.0061, +0.0040, -0.0170, +0.2485,
+ +0.8276, +0.6964, +0.1540, +0.0615, +0.7226, -0.6115, +0.6827,
+ +0.5075, +1.0073, +0.5858, -0.6826, -0.1033, -0.0188, -0.6122,
+ -0.7580, +0.2348, +1.5513, -0.0221, -0.2869, -0.2070, -0.4511,
+ -0.2812, -1.5290, +1.2652, -0.6644, +0.8840, +0.9897, -0.4561,
+ -0.0053, -1.3338, +0.8146, -0.2168, -0.1642, -0.3823, -0.7818,
+ -0.6392, -0.1877, -0.4944, -0.4896, -0.7634, +0.5820, +0.4216,
+ -0.8257, -0.0432, -0.1807, -0.3475, -0.4825, +1.3182, -1.1372,
+ -1.3308, +0.4233, +0.5569, +0.2234, +0.0889, +0.9940, +0.4986,
+ -1.1977, -0.5440, +1.1946, +0.1312, +0.2419, +0.2770, +0.3172,
+ +0.8566, +0.4982, -1.1142, +0.5097, -0.2901, -0.5129, -0.4256,
+ +0.1067, +0.6052, +0.0384, +0.4465, +0.5017, +0.0892, +0.0556,
+ -0.3456, +0.6560
+ ],
+ [
+ +0.3583, +1.0694, +1.0793, +0.1956, +0.9347, -0.1516, +0.2906,
+ -0.0810, +1.0637, +0.6084, -0.5063, -0.0255, +1.2826, +0.2770,
+ -0.5689, +0.2976, +0.7089, +0.1910, -0.3054, +0.9237, -0.8452,
+ +0.5122, -0.0839, -0.9952, -0.5889, +0.8015, +0.0731, -0.2068,
+ +0.3829, +0.3838, +0.4355, +0.2167, +0.3566, -0.2521, +0.9746,
+ -0.8775, +0.1110, -1.1838, -0.8276, -0.4934, -1.3759, -0.0209,
+ -1.5168, -0.3727, +0.1119, +1.3367, +0.4088, +0.3294, -0.5456,
+ +0.2210, +0.6118, +0.2596, -1.0670, +1.3099, +1.0417, +0.9949,
+ +0.8502, +0.9434, -0.2738, +0.4274, +0.4289, +0.2027, +1.1081,
+ +0.1081, +1.6702, +0.4582, +0.2781, -0.2702, -0.3890, -0.4782,
+ -0.3262, -0.6193, +0.4284, -0.8390, +0.1704, -0.8469, -0.1431,
+ +0.8059, +0.0640, -1.1101, +1.0580, +1.1130, +1.0080, -0.0662,
+ +0.9241, -0.1041, +0.1315, -0.4465, +0.2591, +0.2863, +0.1199,
+ -0.2631, +0.3084, +0.8540, +0.2204, -0.7237, -0.2178, +0.6342,
+ -0.0101, +0.5942, -0.5495, +0.3994, +0.5621, -0.2694, +0.9952,
+ +0.0877, +0.0722, +0.6375, -0.4122, -0.2261, +0.2578, -0.1989,
+ +0.4453, +0.0418, -0.6586, -0.0630, +0.1367, +0.0375, -0.3982,
+ +0.6956, +0.4349, +0.7847, +0.9856, -0.2118, -0.1211, +0.2099,
+ +0.6343, -0.2238
+ ],
+ [
+ +0.2576, +0.1708, +0.5942, -0.8994, -0.0868, +0.7046, +0.8070,
+ +0.3142, +0.4562, +0.5703, -0.5525, +0.0864, +0.2016, -0.9636,
+ +0.7642, -0.4136, +0.3538, +0.0215, -0.0008, -0.4398, +0.5139,
+ +0.4963, -0.8291, +0.6681, +0.2463, +0.1906, -0.0195, -0.1146,
+ -0.0489, -1.0220, +0.3947, +0.0897, +0.3557, -0.0899, +0.7004,
+ +0.0732, +0.4142, -0.5701, -0.1690, +0.0402, -0.3416, -0.9773,
+ +0.0455, -0.1412, -0.8012, -0.3097, -0.9837, +0.4047, -0.7972,
+ -0.2902, -0.3245, +0.0464, -0.2058, +0.6175, +0.9464, +0.2569,
+ -0.5419, -0.0480, +0.4761, +0.4906, -1.0051, -0.0336, +0.1762,
+ +0.7865, +0.5313, +0.2276, +0.3898, -0.5483, -0.7494, -0.5172,
+ -0.6968, -0.7780, +0.6258, -0.1979, -0.3625, +0.0796, -0.5390,
+ -0.2714, +0.4319, -0.9952, +0.1555, +0.7258, +0.3754, -0.5892,
+ -0.0937, +0.9012, +1.3195, -0.2689, -1.6369, +0.4650, +0.1741,
+ -0.2305, -0.7181, -0.3967, +1.0093, +0.1660, +0.0568, +0.1924,
+ +0.0595, +0.4189, -1.1472, -0.9761, -0.4957, +0.0854, +0.8852,
+ +0.2884, +0.2345, -0.1550, +0.9522, -0.1306, -0.1394, -1.3291,
+ +0.0207, +0.3611, -0.0699, -0.0948, +1.7921, +0.1665, -0.5039,
+ -0.4613, -0.1789, +0.4391, -0.5099, -0.5557, -0.2059, +0.1237,
+ +0.0259, -0.1886
+ ],
+ [
+ +0.2817, -0.0454, +0.1386, -0.1673, +0.2426, -0.0467, -0.1203,
+ +0.3156, -0.0052, +0.3391, +0.1706, +0.1125, -0.1778, -0.5539,
+ +0.2748, -0.0129, -0.2321, +0.5550, +0.1019, -0.9796, -0.2074,
+ -1.3227, -0.7212, +0.4632, +0.0566, -0.4680, -0.5681, -0.5756,
+ -1.4594, -0.3052, +0.2753, -0.6632, +0.0368, +0.2291, -0.0578,
+ +0.3663, -0.1122, +0.0024, +0.5366, -0.3653, +0.2721, -0.0873,
+ -0.1185, -0.3832, -0.5141, -0.0425, -0.0007, +0.2201, -0.0954,
+ -0.4895, -0.3387, +0.5406, +0.1037, +0.0756, -0.2258, +0.1772,
+ +0.1323, +0.2892, -0.5137, +0.2084, -0.1640, -0.7629, +0.4224,
+ +0.3344, -0.5014, +0.1077, -0.4575, +0.3734, +0.2012, -0.2691,
+ -0.3532, +0.5112, +0.2323, +0.2361, -0.6075, +0.0756, -0.6252,
+ -0.2803, +0.1436, +0.1922, +0.1045, +0.2936, +0.0511, +0.0997,
+ +0.1260, -0.7201, +0.2040, -0.6068, -0.2572, -1.1220, -0.4336,
+ +0.1953, +0.2289, +0.0583, -0.0825, +0.0174, +0.2520, +0.3962,
+ +0.1735, -0.1254, -0.2769, -0.0927, -0.8869, +0.2688, +0.0637,
+ -0.0104, +0.1743, +0.6607, +0.3604, +0.0411, +0.6830, -0.2192,
+ +0.6120, +0.5902, -0.0692, +0.0640, -0.4776, -0.3384, +0.3360,
+ -0.2106, -0.2018, -0.1111, +0.4084, -1.0131, +0.1918, +0.1225,
+ +0.1328, -0.1810
+ ],
+ [
+ -0.5625, +0.6491, -0.2732, +0.4952, -0.1584, +0.2908, -0.6854,
+ -0.4982, -0.0942, -0.2324, +0.2329, +0.3380, +0.4047, +0.8220,
+ +0.1344, +0.2586, -0.2234, +0.1572, -0.5163, +0.5888, +0.3405,
+ -0.3463, +0.9772, +0.1675, -0.6181, +0.4957, +0.6584, -0.1368,
+ -0.1735, +0.4557, +0.6991, -0.0403, +0.2271, +0.2258, +0.2296,
+ -0.0160, -0.4586, -0.4367, +0.5504, +0.5095, -0.0341, +0.4141,
+ +0.0418, -0.2047, +0.3971, +0.3569, +0.6946, +0.1311, +0.3614,
+ -0.0544, +0.7212, +0.0162, +0.0360, -0.3230, +0.4143, -0.2461,
+ +0.1784, -0.2672, -0.7151, +0.0920, +0.2453, -0.1601, -0.1728,
+ +0.0921, +0.3203, +0.1281, +0.7218, -0.2275, +0.6779, -0.4679,
+ +0.2388, -0.2174, +0.1108, -0.2124, +0.1118, +0.1878, +0.6509,
+ -0.2355, -0.3070, -0.1175, -0.8563, +0.7712, +0.7216, +0.2705,
+ -0.3359, +0.0834, +0.3364, -0.9102, -0.0050, -0.2038, -0.3887,
+ -0.0003, +0.3009, +0.5568, +0.4128, -0.1470, -0.4033, +0.4556,
+ -0.0164, +0.6296, -0.6479, -0.6349, -0.4118, -0.1700, +0.5044,
+ +0.6149, +0.5285, +0.2198, -0.5983, +1.1778, +0.1033, -0.1016,
+ +0.5921, -0.3015, -0.4725, -0.1732, -0.0215, +0.7037, +0.5043,
+ -0.7740, -0.4181, -0.1432, +0.4241, +0.5390, -0.8923, +0.8941,
+ -0.2442, -0.1354
+ ],
+ [
+ -0.3359, -0.1083, -0.8409, +0.2590, +0.3363, +0.1838, -0.3840,
+ +0.3864, +0.2034, -0.3445, +0.0949, -0.1383, +0.3539, -0.5850,
+ -0.0659, +0.4438, +0.3457, -0.7643, +0.0728, -0.0271, +0.1040,
+ -0.1681, +0.3348, +0.5446, -0.6685, +0.4041, -0.0872, -0.2793,
+ +0.2181, +0.0853, -0.0353, -0.5413, -0.1816, -0.1187, +0.1640,
+ -0.2443, +0.1492, -0.2037, -0.0081, +0.0258, +0.2739, +0.0343,
+ -0.1295, +0.0078, +0.0392, +0.4218, +0.3354, +0.6948, +0.0345,
+ -0.7231, +0.8704, +0.1680, -0.1541, -0.5035, -0.0281, +0.0994,
+ +0.3783, +0.2794, -0.4267, -0.6257, -0.2330, -0.3536, -0.1162,
+ -0.0411, +0.1763, +0.1975, +0.1464, +0.0609, -0.2487, +0.3408,
+ -0.7077, +0.0542, -0.3465, +0.0497, +0.1247, +0.1681, -0.4003,
+ -0.2574, +0.1809, -0.0013, -0.1649, -0.3992, +0.3628, +0.0089,
+ +0.3263, -0.3100, +0.2304, -0.2072, -0.2944, -0.4202, -0.0603,
+ -0.0752, -0.2653, +0.2389, +0.6501, +0.0928, -0.8089, +0.1342,
+ +0.3140, -0.2359, -0.3699, +0.0832, -0.4305, -0.5970, +0.3982,
+ +0.7136, +0.3347, -0.1750, -0.5559, +0.1141, +0.0591, -0.1708,
+ -0.3083, -0.4088, +0.5476, -0.0705, -0.1452, +0.2297, +0.1725,
+ -0.4675, -0.2641, +0.2952, +0.2449, -0.3262, -0.2343, -0.2551,
+ +0.2011, +0.3487
+ ]])
+
+weights_dense1_b = np.array([
+ +0.0032, +0.0591, +0.1871, -0.0873, +0.0194, -0.1684, -0.0091, +0.0135,
+ -0.0694, -0.3312, +0.0673, -0.1489, +0.1365, +0.0575, -0.1155, -0.0904,
+ -0.1321, +0.0492, -0.2257, -0.2418, -0.0204, -0.1910, -0.0512, -0.0482,
+ -0.2969, -0.3574, -0.1852, -0.1644, -0.2957, -0.1906, -0.0170, -0.0760,
+ +0.0006, -0.1286, -0.0746, +0.0039, -0.1005, -0.0535, +0.0375, -0.2162,
+ -0.1251, -0.0368, +0.0101, -0.3220, -0.1152, -0.3656, -0.2491, +0.0638,
+ -0.0312, +0.0054, -0.2318, -0.2900, -0.1189, -0.0725, +0.0490, -0.0679,
+ +0.0117, +0.0926, -0.0824, +0.0479, +0.0756, -0.0462, +0.1529, +0.0081,
+ -0.0984, -0.1227, -0.0247, -0.1277, -0.0633, -0.1953, +0.1023, +0.1582,
+ -0.0400, -0.1115, -0.1625, -0.2216, -0.0195, -0.0650, +0.0701, -0.1573,
+ -0.1187, -0.0801, -0.1424, +0.1873, -0.2309, -0.1815, -0.0408, -0.1173,
+ +0.0185, -0.1408, -0.0938, -0.2810, +0.2447, -0.4046, -0.1790, -0.0165,
+ +0.1334, +0.0500, +0.0283, -0.0321, -0.2388, -0.0726, -0.3444, -0.3250,
+ -0.1338, -0.0579, -0.1647, -0.0691, -0.0835, +0.0734, +0.1667, -0.1478,
+ -0.2212, -0.0899, -0.0050, -0.2379, +0.0709, +0.0464, +0.1569, -0.2669,
+ -0.2181, -0.4331, +0.0534, -0.0648, -0.1026, -0.1509, -0.2278, -0.0437
])
-weights_dense2_b = np.array([ +0.0266, +0.3395, +0.0968, +0.0097, +0.0443, -0.1722, -0.2537, +0.1501, +0.0233, -0.0174, +0.1783, -0.0513, -0.1531, -0.2145, +0.0299, -0.1589, +0.1143, +0.1132, -0.2700, -0.0481, +0.2876, +0.1824, +0.2418, +0.1009, -0.1451, +0.1637, +0.1703, +0.0336, -0.1405, -0.0162, -0.1158, +0.1691, -0.0223, -0.1828, +0.2352, +0.0209, -0.1362, -0.2636, +0.1271, -0.0936, -0.1436, +0.0606, +0.1311, -0.0989, -0.2877, +0.2593, +0.0781, -0.1118, -0.1264, +0.2478, +0.2398, -0.1515, +0.0959, -0.0821, -0.1740, +0.1116, -0.0682, +0.1743, +0.1746, -0.1950, -0.0951, +0.2190, -0.0294, +0.1950])
+weights_dense2_w = np.array(
+ [[
+ -0.5294, -0.0896, +0.1998, -1.0655, -1.0578, -0.2702, +0.0052, +0.1819,
+ -0.2272, -1.3830, +0.0185, +0.0236, +0.0611, +0.3201, -0.1723, +0.2887,
+ -0.4885, +0.3460, -0.0437, -0.4517, +0.1636, +0.0027, -0.5574, -0.4712,
+ -0.2482, +0.1202, +0.6143, -0.6510, -0.5672, -0.7578, -0.2628, -0.5118,
+ +0.2114, +0.3419, +0.3262, -0.1558, +0.4818, -0.4314, -0.4611, -0.3294,
+ +0.2443, -0.4138, +0.2451, -0.2765, -0.4818, +0.0854, -0.0011, +0.0080,
+ -0.3759, -0.1235, -0.2526, +0.3319, -0.7957, -0.3891, +0.6225, +0.7334,
+ -0.3936, -0.2982, +0.2974, -0.2766, +0.0199, -1.0206, -0.4054, -0.0960
+ ],
+ [
+ -0.5329, -0.7876, -0.4974, +0.3381, +0.3092, +0.0208, -0.2402,
+ -0.3306, -0.7425, +0.1489, +0.0271, -0.1945, +0.0315, +0.1836,
+ +0.2294, -0.6615, -0.1362, +0.2090, -0.5984, -0.0163, +0.0886,
+ +0.0679, +0.3041, -0.0070, -0.0550, +0.3623, -0.0483, -0.2679,
+ +0.2927, +0.2728, +0.2955, -0.0641, +0.2888, +0.0278, +0.1980,
+ +0.0714, +0.1605, +0.1879, +0.0666, -0.0505, +0.3625, +0.3155,
+ -0.1965, -0.0301, +0.1697, -0.0102, -0.4709, -0.4190, +0.0265,
+ -1.0402, -0.0718, +0.3172, -0.1062, -0.2538, -0.4556, -0.2825,
+ -0.0534, -0.1540, +0.0872, +0.1585, -0.4927, -0.0311, +0.2163, -0.8230
+ ],
+ [
+ -0.0620, -0.4689, -0.0407, -1.5569, -0.1551, -0.2028, -0.3836,
+ -0.0306, -0.0718, -0.9097, -0.1025, +0.1040, +0.1657, +0.1093,
+ -0.2807, +0.3353, -0.6893, +0.6661, +0.1312, -0.8763, -1.5289,
+ -1.4383, +0.1129, +0.2337, -0.0876, -0.8757, +0.0550, -0.3456,
+ +0.1468, -0.6056, -0.8811, -0.3539, +0.6850, +0.1739, +0.0344,
+ -0.0354, -0.2883, -0.1680, -0.3950, -0.7221, -1.8289, -0.2404,
+ -0.2498, +0.1401, +0.3679, -0.1029, -0.2085, -0.9932, -0.1101,
+ -0.4335, -0.1423, -0.3566, -0.4630, +0.1845, +0.3527, -0.4799,
+ -1.7876, +0.3755, +0.2791, +0.1744, -0.3218, -0.4807, -0.2936, +0.2639
+ ],
+ [
+ -0.1966, +0.5649, -0.2069, +0.3588, -0.8745, +0.8721, +0.0814,
+ +0.1852, +0.1873, -0.0432, -0.7933, -0.2585, -0.1218, -0.4980,
+ +0.3300, +0.3064, -1.0648, -0.6760, +0.0998, +0.6166, -0.2364,
+ +0.0741, -1.5132, -1.1618, -0.0384, +0.1799, -0.5393, +0.2645,
+ -0.2358, +0.0418, +0.3921, -0.8185, +0.5272, +0.4155, -0.2473,
+ +0.0026, -0.4362, -0.1113, -0.1036, -1.0282, -0.2206, +0.5201,
+ -0.1124, +0.3642, +0.0213, +0.1247, +0.0868, +0.3541, -0.0376,
+ -0.0735, +0.4899, -0.5098, -0.7578, -0.3030, +0.2886, -0.7427,
+ -0.4035, +0.0161, -0.4715, +0.0235, +0.5217, -0.2785, +0.0707, -0.2289
+ ],
+ [
+ -0.7238, +0.4670, -0.0149, +0.2279, -0.1295, +0.0670, -0.2468,
+ +0.4984, +0.6797, +0.2095, -0.2371, -1.1373, -0.0913, -0.6137,
+ -0.1067, +0.0817, -0.4967, -0.3839, -0.0531, -0.3020, -0.2330,
+ -0.1719, -0.2915, -0.3750, -0.1896, -0.0480, -0.2671, +0.5401,
+ -0.0648, -0.8036, +0.2070, -0.9393, +0.1914, +0.2418, -0.0981,
+ -0.4760, -0.0516, -0.8327, +0.1371, -0.7785, -0.1945, -0.6666,
+ -0.0209, +0.0864, -0.7345, -0.3576, -0.2442, +0.3027, -0.4184,
+ +0.2634, +0.2169, +1.1403, -0.4589, +0.0943, -0.0657, -0.2680,
+ -0.6890, -1.2024, -0.2191, -0.1494, -0.0415, -0.9274, +0.3765, +0.2284
+ ],
+ [
+ +0.0721, +0.2423, +0.2696, -0.8249, -0.0644, -0.3427, -0.2876,
+ -0.2066, +0.2195, +0.1008, +0.1247, +0.2757, -0.1372, -0.0132,
+ +0.1199, -0.1206, +0.1263, +0.0607, -0.1235, -0.3237, +0.5096,
+ -0.0538, +0.4292, -0.2570, -0.2744, -0.1671, +0.0643, +0.2648,
+ -0.1993, +0.0420, +0.1681, +0.3126, -0.3654, -0.2719, +0.3103,
+ +0.2754, +0.0040, -0.4387, -0.0634, +0.2868, +0.0613, -0.1423,
+ +0.0911, -0.6027, -0.2560, -0.0131, -0.5504, -0.6812, +0.0176,
+ +0.1782, -0.0082, -0.2754, +0.1471, +0.2872, -0.5940, +0.1319,
+ +0.0220, +0.3727, +0.2380, +0.0558, +0.1206, +0.2882, +0.0155, +0.2597
+ ],
+ [
+ -0.1229, -0.7953, -0.2690, -0.8715, -0.8578, +0.0133, +0.2098,
+ -0.0996, -0.0174, +0.5429, -0.3021, -0.1241, +0.0091, -1.2123,
+ +0.0488, -0.4687, -0.6124, -0.7139, -0.2042, -0.4138, -0.3101,
+ -0.1909, +0.1478, -0.5427, -0.2557, -0.1813, +0.4605, -0.6159,
+ -0.1311, -0.3425, -0.9877, -1.2896, -0.4583, +0.2293, -1.0717,
+ +0.0631, +0.0908, -0.1255, -0.8500, +0.0157, +0.1026, -0.6678,
+ -0.4511, -0.1720, -0.1051, -0.0788, -1.1285, -0.7684, -0.5400,
+ -0.0879, -1.3907, +0.8072, +0.3826, +0.5732, -0.6696, +0.3482,
+ -0.2598, -0.9451, +0.0000, +0.1565, -0.9628, -0.5438, -0.2299, +0.0864
+ ],
+ [
+ -0.3683, +0.2445, -0.6280, -0.6619, -0.3666, -0.4500, -0.5599,
+ -0.6186, +0.0152, -0.2720, +0.0609, -0.3384, -0.0136, +0.1575,
+ +0.3848, -0.5577, +0.7921, -0.4193, +0.0182, +0.3805, +0.0310,
+ +0.2653, -0.0866, +0.3095, -0.2329, -0.1241, +0.1641, -0.2871,
+ +0.0675, -0.2960, +0.1917, -0.3727, +0.0599, +0.4283, -0.7127,
+ -0.0708, -0.0144, +0.3581, -0.7382, -0.1784, -0.3748, -0.1627,
+ -0.5114, -0.2711, +0.0602, -0.2263, -0.1847, -0.1914, -0.2189,
+ -0.3361, +0.0516, -1.3228, +0.0331, +0.3685, +0.2941, -0.4427,
+ +0.2907, -0.7059, -0.1141, -0.0540, +0.0532, -0.1200, +0.0966, -0.0749
+ ],
+ [
+ -1.1537, -0.0967, -0.3476, -0.2341, +0.5311, -0.1617, -0.3381,
+ +0.1348, +0.2100, -1.0730, -0.0577, -0.0237, -0.0373, -0.5123,
+ +0.2998, -0.3247, +0.5258, +0.3037, -0.0538, +0.3679, -0.3760,
+ +0.0351, +0.5999, +0.4626, -0.1599, -1.1580, -0.1344, +0.6217,
+ -0.2474, -0.6322, -0.7804, -0.2596, +0.6680, -0.1191, -0.0805,
+ +0.2087, -0.1946, -0.2961, -0.2653, -0.1915, +0.1113, -0.6597,
+ +0.0847, -0.0599, +0.6311, -0.8174, -0.8733, -0.5911, +0.1962,
+ -0.1327, -0.1959, +0.7040, +0.6005, +0.1157, -0.4948, -0.5988,
+ +0.4162, -0.3101, +0.0050, +0.6379, +0.0811, -0.0415, +0.2975, +0.4097
+ ],
+ [
+ -0.0605, -1.4543, +0.3715, +0.0582, -0.1646, +0.0919, -0.8151,
+ -0.0222, -0.5294, -0.4140, -0.4782, -0.0889, -0.2930, -0.7260,
+ -0.1270, -0.2699, -0.2068, -0.4855, -0.0244, +0.5308, +0.2588,
+ +0.0277, +0.1398, -0.0020, -0.0209, +0.4305, +0.5735, -0.4727,
+ -0.1810, -0.1060, +0.1201, +0.2439, -0.2472, -0.0717, +0.1351,
+ +0.3603, +0.3060, -0.3795, -0.2812, -0.2544, +0.1106, -0.0701,
+ +0.2985, -0.1396, -0.2122, +0.4243, -0.2770, -0.5565, -0.2525,
+ +0.0816, -0.4047, -0.2782, -0.7214, -0.1042, -0.1084, +0.1894,
+ +0.8661, -0.1578, +0.3679, +0.2941, +0.0799, -0.3008, -0.1891, -0.4522
+ ],
+ [
+ -0.1581, -0.8760, -0.6871, +0.1299, -0.4920, -0.2449, +0.2764,
+ -1.4836, -0.7051, +0.3574, -0.2647, -0.2578, -0.0707, +0.1505,
+ -0.0393, -0.5107, +0.0504, +0.2922, -0.1558, +0.0842, -0.0566,
+ +0.0806, +0.2948, +0.1275, +0.0113, +0.0670, +0.5678, +0.0579,
+ -0.0082, -0.0575, +0.2882, +0.0579, +0.1669, -0.5888, -0.1277,
+ -0.1875, -0.2031, +0.2563, -0.4510, +0.1176, -0.6062, +0.0932,
+ -0.4625, +0.0489, -0.4213, +0.1625, +0.0889, +0.3401, -0.4626,
+ -0.1120, -0.3998, -0.3627, +0.5388, +0.3221, +0.0293, +0.4626,
+ -0.4754, -0.7499, -0.5847, -0.3559, +0.3759, +0.6087, -0.6434, -0.3520
+ ],
+ [
+ +0.2500, +0.1920, -0.0041, +0.3031, +0.1244, +0.2579, -0.3249,
+ +0.6266, +0.0798, -0.6341, +0.1762, -0.0811, -0.2604, -0.4294,
+ -0.1638, -0.0724, -0.2681, -0.0688, -0.1879, +0.4750, +0.4832,
+ +0.2947, +0.2664, +0.2740, -0.0683, +0.2160, -0.1307, +0.1062,
+ +0.0801, -1.2182, +0.3045, +0.1882, -0.0800, -0.3235, -0.5861,
+ -0.2444, -0.0772, +0.1528, -0.1473, +0.0380, -0.0192, -0.1198,
+ +0.1908, -0.5856, -0.3644, -0.0235, +0.4902, -0.6515, -0.3490,
+ +0.0620, +0.2643, +0.1549, -0.0580, -0.1879, +0.1547, -0.5689,
+ +0.2646, +0.2184, -0.1865, -0.6921, +0.3484, -0.0395, -0.0506, +0.0883
+ ],
+ [
+ +0.3222, -0.6081, -0.8570, +0.1662, -1.6457, -0.1301, +0.4362,
+ -0.3683, -1.2053, +0.0051, +0.4562, +0.1176, +0.0681, +0.0442,
+ +0.0929, -0.1070, +0.0833, -0.9221, -0.1152, -1.3000, +0.1766,
+ +0.5323, -1.3052, -0.8361, -0.1032, +0.1584, -0.3473, -0.1487,
+ -0.5833, -0.0997, -0.1513, +0.0293, +0.3824, -0.0470, -0.3443,
+ -0.4211, -0.2198, -0.0394, -0.7857, +0.6342, -0.0022, -0.2827,
+ -1.2328, +0.8836, -0.1748, +0.0327, -0.2512, -0.3752, -0.1145,
+ -0.8466, -0.6688, -0.2503, +0.0641, -0.0112, -0.5286, -0.6550,
+ -0.8791, +0.1105, -0.4148, +0.6753, +0.4758, -0.0569, +0.0966, -0.9476
+ ],
+ [
+ -0.4199, -0.6072, -0.4537, -0.4169, -0.8892, +0.2855, +0.5756,
+ -0.0186, -0.5130, -0.1059, -0.7573, -0.0568, -0.0684, -0.6527,
+ -0.0938, -0.0042, -0.3279, -0.4445, +0.0217, +0.0967, -0.7654,
+ -0.2576, -1.3607, -0.5645, +0.1616, +0.0616, -0.7005, -0.2452,
+ +0.2257, -0.5849, +0.6963, -1.0530, -1.3240, -0.1119, -0.9036,
+ -0.0479, -0.4890, +0.5005, -1.4962, +0.2961, -1.2472, -0.2179,
+ +0.0196, +0.5316, -0.0054, -0.0947, -0.6427, -0.0188, -0.4429,
+ +0.5082, -0.0946, -0.4850, +0.3228, +0.1117, +0.3974, +0.0178,
+ -0.0763, -1.3113, -0.5316, +0.0163, -0.2001, -0.2488, +0.3841, -0.1722
+ ],
+ [
+ -0.1212, -0.3952, +0.0911, -0.5135, -0.2093, -0.7678, +0.1495,
+ +0.0407, +0.3257, +0.0601, -0.2006, +0.3888, -0.1896, +0.1708,
+ -0.2838, -0.6900, +0.0937, +0.2306, +0.0376, -0.3426, -0.2854,
+ -0.3829, +0.4875, +0.0551, +0.0143, -0.2186, +0.0469, -0.8389,
+ -0.7003, +0.2505, -0.5086, +0.1452, -0.3577, -0.5950, -0.1434,
+ -0.3216, -0.7059, +0.1497, -0.1612, +0.4857, -0.2867, -0.1537,
+ -0.2302, -0.6386, +0.3762, +0.2766, +0.1610, -0.6457, +0.4320,
+ -0.3433, +0.0201, -0.1067, +0.2527, +0.2581, -0.0995, -0.1953,
+ -0.0237, +0.8414, +0.4549, -0.1515, -0.1875, -0.1065, -0.2381, -0.4321
+ ],
+ [
+ -0.3393, -0.3520, -0.9045, +0.6000, +0.5172, -0.1926, -0.1635,
+ +0.1719, -0.6527, +0.2668, +0.3255, -0.0443, +0.0438, -0.4045,
+ -0.2399, -0.4114, -0.7029, -0.0357, -0.4091, -0.0354, -0.1053,
+ +0.0729, -0.6477, -0.2433, -0.0480, +0.2689, +0.2895, +0.0905,
+ -0.3754, -0.9434, +0.5497, -0.0091, +0.2105, -0.1584, +0.0904,
+ -0.3422, +0.2668, -0.1983, +0.4242, -0.2503, -0.4326, -0.3479,
+ -0.4545, +0.8625, -0.3452, +0.6519, +0.1031, +0.3487, -0.3660,
+ -0.0598, +0.2381, +0.8141, -0.2223, -0.1759, -0.0212, -0.0058,
+ -0.2119, +0.0731, -0.0786, -0.3202, -0.2608, -0.7982, +0.4981, +0.1286
+ ],
+ [
+ -0.5110, +0.3147, +0.1463, -0.0389, -0.3521, +0.3138, -0.4345,
+ -0.1397, +0.4069, +0.4113, -0.1701, +0.0171, -0.0710, -0.0741,
+ -0.1748, +0.1410, +0.1965, -0.9863, -0.1121, +0.2325, -0.0745,
+ +0.0503, -0.3608, -1.0871, -0.1174, +0.2476, -1.4639, +0.1530,
+ +0.3929, +0.2179, -0.1187, -0.2966, -0.0866, +0.1865, -0.9683,
+ -0.2727, -0.0255, -0.4145, +0.1239, -0.0952, -0.0126, +0.2078,
+ +0.0525, -1.2549, -0.4354, -0.1329, -0.1288, -0.0279, -0.1269,
+ +0.0084, +0.4687, +0.1488, -0.3704, +0.3366, +0.1487, -0.7377,
+ -0.4681, -0.2716, -0.2919, +0.0930, -0.2879, -0.4733, -0.1250, +0.3180
+ ],
+ [
+ -0.2212, -0.1165, +0.0573, -0.0257, +0.4105, -0.3042, -0.2197,
+ +0.1105, -0.0834, -0.3845, +0.0174, +0.0070, +0.0297, +0.0073,
+ -0.5144, +0.3017, +0.1921, +0.4018, -0.2265, -0.2572, +0.2103,
+ -0.5301, -0.0210, +0.7838, +0.1188, +0.0774, +0.4195, -0.8113,
+ +0.3870, +0.2450, -0.8158, +0.7872, +0.0218, +0.1636, -0.1837,
+ +0.0628, +0.4486, -0.0948, +0.1513, -0.8843, -0.5782, -0.1950,
+ +0.2832, -0.2192, +0.6143, -0.0574, +0.2811, -0.4833, +0.1312,
+ +0.2647, -0.0071, +0.3059, -0.0858, -0.6766, +0.1089, +0.3099,
+ -0.2368, +0.2549, +0.4027, -0.1061, -1.1896, -0.6198, -0.3528, +0.1676
+ ],
+ [
+ +0.0035, -0.4849, -0.7783, -0.0504, +0.2348, -0.0571, +0.4417,
+ +0.0601, -0.8799, +0.1450, -0.0952, -0.3266, +0.0411, -0.7422,
+ +0.0060, -0.2092, -0.1885, -1.2113, -0.0374, +0.0568, +0.1130,
+ -0.0895, +0.0957, +0.1047, +0.1396, -0.0320, -0.2089, +0.1098,
+ -0.4008, +0.0389, +0.0482, -0.2914, -0.9251, +0.4323, +0.1206,
+ +0.0567, +0.0699, +0.0587, +0.0422, +0.2053, +0.0602, -0.7918,
+ +0.1464, +0.3530, -1.2250, -0.2547, +0.3194, -0.8625, -0.4735,
+ +0.4783, +0.0043, +0.1931, +0.1671, +0.0328, -0.0747, +0.6361,
+ +0.2269, -0.5492, +0.1361, -0.1751, -0.0100, -0.2549, -1.0106, -0.9024
+ ],
+ [
+ +0.2591, -1.0195, -0.4721, -0.9731, +0.0299, +0.2645, +0.3216,
+ -0.1474, -0.4643, -0.0471, -0.2468, +0.2281, +0.0187, -0.0859,
+ +0.0399, +0.0137, -0.4151, -0.7058, -0.4788, +0.3670, -0.3171,
+ -0.5478, -0.3702, -0.2157, +0.0541, -1.3574, -0.5394, -0.1754,
+ +0.4716, -0.3429, +0.6257, -0.6191, -0.0252, -0.3959, +0.5052,
+ +0.1172, -0.0161, +0.0461, -0.3518, -0.6841, +0.0599, +0.7104,
+ -1.4835, +0.2076, -0.3105, -0.2433, -0.0676, +0.2361, +0.1693,
+ -0.5076, -0.1233, -0.1134, -0.2816, -0.5818, +0.0513, -0.9941,
+ +0.4563, -0.2065, -0.7186, -0.5165, -0.6421, -0.1892, +0.1439, -0.2584
+ ],
+ [
+ +0.0525, +0.2656, -0.3646, -0.8030, -0.2153, -0.0913, -0.3868,
+ +0.3407, -0.1766, +0.4419, -0.3384, +0.2972, -0.0482, +0.2394,
+ +0.2429, -0.1640, +0.4954, -0.0242, -0.5130, +0.2863, +0.6940,
+ +0.1821, +0.3729, -0.3485, -0.2009, +0.4411, +0.0800, +0.1678,
+ -0.6286, -0.4632, -0.0660, +0.1633, -0.7075, -0.4767, +0.0660,
+ +0.3576, -0.1382, +0.4100, -0.1458, +0.2652, +0.0179, -0.2446,
+ -0.6880, -0.2835, -0.6586, +0.3138, -0.0370, -0.5427, -0.0139,
+ +0.0475, +0.0476, +0.2838, +0.1937, +0.0958, -0.6775, -0.0984,
+ -0.4858, +0.2718, +0.0920, -0.1442, -0.3254, +0.4006, +0.3794, -0.1053
+ ],
+ [
+ -0.7993, +0.2057, -0.0825, -0.5901, +0.4015, +0.7778, +0.2741,
+ +0.3809, -0.0990, -0.1496, +0.4271, +0.2286, +0.1506, -0.0415,
+ +0.5997, -0.6465, +0.0393, +0.3040, +0.2443, -0.2178, -1.3364,
+ -0.4051, +0.3383, -0.0159, +0.1492, +0.0452, -0.1428, -0.2160,
+ +0.2785, +0.6410, -0.6244, +0.3319, -0.4489, -0.1197, -1.1882,
+ +0.3110, +0.5941, +0.1675, +0.2606, -0.9117, +0.3474, -0.4273,
+ +0.6581, -0.0334, -0.5226, -1.0439, -2.6607, -0.2681, +0.5722,
+ -0.1204, -0.8560, -0.5789, -0.4583, +0.1208, -1.2444, -0.3378,
+ -0.9704, -0.0412, +0.1563, -0.1445, -1.2344, -0.5351, -0.2627, -0.0315
+ ],
+ [
+ -0.2311, +0.0027, -0.9287, -0.1228, -0.8419, +0.1478, -0.3367,
+ -0.2493, -0.1044, -0.0661, -0.5176, +0.1812, -0.1505, +0.3252,
+ +0.0689, -0.1895, -0.6359, +0.3539, +0.0074, +0.2096, -0.1721,
+ -0.6680, -0.1181, +0.0884, -0.1903, -0.3968, +0.2160, -0.8183,
+ -0.1148, -0.5661, +0.1892, -1.3805, +0.4477, -0.0261, +0.0525,
+ +0.2808, -0.5591, +0.5135, -0.3758, +0.1060, +0.6081, -0.3552,
+ -1.2404, +0.0532, +0.2700, +0.0979, -0.6299, -0.0514, +0.3286,
+ +0.1688, -0.4352, -0.8093, -0.0033, +0.2607, +0.2893, -0.3395,
+ -0.5950, +0.0470, -0.4043, -0.8434, -0.4925, -0.6462, -0.3282, -0.0198
+ ],
+ [
+ +0.3055, +0.4763, +0.3049, -0.9238, +0.2499, -0.8889, +0.0817,
+ +0.1527, +0.3570, -1.2277, +0.5060, +0.5231, -0.0977, +0.7970,
+ -0.3972, -0.0988, +0.7831, -0.4279, +0.0235, +0.3373, +0.6341,
+ +0.2142, -0.1506, +0.6003, -0.3704, -0.0476, +0.2141, -0.4490,
+ -0.3270, -0.4279, -0.2669, +1.0325, -0.7446, -0.5226, +0.2484,
+ -0.3719, +0.0762, -0.2644, +0.4603, +0.3430, +0.0474, +0.0505,
+ -0.0625, -0.1566, -1.0823, +0.0666, +0.1685, -1.7572, +0.5213,
+ -0.0229, +0.4925, -0.9132, +0.2729, -0.0375, -0.0308, -0.0809,
+ -0.0612, +0.5318, -0.3841, -0.3973, +0.0513, +0.3254, +0.0226, +0.0897
+ ],
+ [
+ -0.4901, +0.4057, +0.4243, -0.1017, -0.5561, +0.0413, -0.1884,
+ +0.0115, +0.3556, +0.4905, +0.4599, +0.3225, -0.2060, -1.0437,
+ -0.1747, +0.4379, -0.2705, -0.4107, -0.2775, +0.2060, +0.1902,
+ +0.1741, -0.0650, -0.7355, -0.0770, -0.1194, -0.3411, -0.3670,
+ -0.3807, +0.3297, -0.3163, +0.2963, +0.5599, +0.6562, -0.2402,
+ -0.0244, +0.2263, -0.0590, +0.2397, +0.4873, +0.0771, +0.5808,
+ +0.4708, -0.1900, -0.6152, +0.4273, +0.5762, -0.3754, -0.2344,
+ +0.3123, -0.1155, -0.3437, -1.0409, -0.1489, -0.1104, +0.3270,
+ +0.3800, +0.3680, +0.2113, -0.5376, +0.1063, +0.0841, -0.5439, -0.1957
+ ],
+ [
+ -1.9974, -0.0211, -0.2446, -0.3544, -0.7249, -0.3924, -0.5035,
+ -0.2175, -0.1627, -0.8428, -0.1119, -0.0274, -0.0418, -0.1262,
+ +0.3002, -0.1632, -0.2389, +0.3389, +0.0569, +0.0202, -1.0143,
+ +0.3537, -0.1440, +0.3140, -0.1313, -0.3848, +0.7528, -0.6598,
+ -1.0451, +0.5417, -0.0634, +0.1701, -0.6359, +0.3913, +0.9036,
+ +0.8082, -0.6004, -0.0083, -0.8911, -0.0479, +0.1066, -0.4130,
+ +0.2471, +0.5112, +0.3424, +0.2349, +0.2216, -0.1641, +0.0944,
+ -0.3781, -0.2863, +0.2887, -0.1032, +0.2387, +0.1109, -0.1010,
+ +0.6019, -0.6929, -1.1630, +0.1658, -0.0167, -0.2142, +0.3414, -0.6920
+ ],
+ [
+ +0.6931, +0.0145, +0.3552, -0.1500, -0.6177, +0.2065, +0.1103,
+ -0.1340, +0.5208, +0.3153, -0.4249, +0.2061, -0.1484, -0.2901,
+ +0.2288, -0.3281, -1.4010, -0.6546, -0.0633, +0.1697, -0.6311,
+ -0.4404, -0.1730, -0.9839, -0.0577, +0.3237, -0.0267, -0.2236,
+ +0.3860, +0.3659, +0.2307, +0.5690, -1.0721, -1.0289, +0.3124,
+ -0.4391, -1.4334, +0.3776, -0.7681, -0.3304, +0.0015, +0.0868,
+ -2.1094, -1.2462, +0.0804, +0.1231, -0.2476, -0.5150, -0.3384,
+ -0.1315, -0.3313, +0.2172, +0.3345, +0.0750, +0.0769, +0.7963,
+ -0.0705, +0.0998, +0.0840, -0.3474, -0.0533, +0.1124, -0.0993, -0.2206
+ ],
+ [
+ +0.0738, +0.4493, +0.0851, -0.2606, -0.4232, +0.1632, +0.0389,
+ +0.0128, +0.3265, -0.1896, +0.3890, +0.2983, -0.1198, -1.0363,
+ -0.0076, +0.2032, -0.7419, -1.0515, -0.1930, -0.0945, -0.0872,
+ -0.1580, -0.2602, -1.4956, -0.1525, +0.4170, -0.9875, +0.3425,
+ +0.3709, +0.1006, +0.0766, +0.0740, -0.3491, +0.1276, -0.2520,
+ -0.0348, -0.6866, +0.0363, +0.4659, -0.2804, -0.3475, -0.1448,
+ +0.0616, -0.8020, -0.2784, +0.2680, +0.3337, -0.0333, -0.5948,
+ +0.4099, +0.2169, -0.4844, -0.6288, -0.1061, +0.1890, -0.2980,
+ +0.0414, +0.2023, +0.0107, -0.6235, -0.0916, -0.2670, -0.2182, -0.4410
+ ],
+ [
+ +0.3507, +0.5252, -0.1627, -1.4898, +0.2313, +0.5587, +0.2386,
+ +0.3379, +0.0982, +0.0413, +0.3709, +0.4906, +0.0007, -0.4149,
+ +0.4735, -0.1098, -0.5601, +0.2028, +0.3657, -0.4582, -1.6526,
+ -0.4622, +0.3676, -0.5300, +0.1754, +0.0149, +0.1038, -0.2189,
+ +0.1419, +0.4394, -0.3616, +0.2069, -0.7841, -0.3796, -0.7757,
+ +0.5907, +0.1856, +0.1489, +0.4881, -1.1035, +0.0189, -0.1605,
+ +0.6046, -0.6840, -0.5543, -0.0317, -1.1382, +0.0052, +0.3898,
+ +0.5780, -0.1522, -0.3236, -0.4997, +0.1208, +0.3768, +0.5135,
+ -0.2755, -0.1092, +0.2018, -0.2345, -1.4905, -0.1996, -0.2652, -0.1369
+ ],
+ [
+ -0.0105, +0.5400, +0.0687, +0.3213, -0.9347, +0.3641, -0.1674,
+ -0.4105, +0.1847, -0.2406, -0.4423, -0.6186, -0.1456, -0.2169,
+ +0.3144, -0.1460, +0.1520, +0.2036, +0.1390, +0.0801, -0.5625,
+ -0.1819, -0.3711, -0.2140, -0.2649, -0.0028, +0.4067, -0.8796,
+ -0.1423, -0.3487, -0.1759, -0.5259, -0.4894, +0.2141, -0.0896,
+ +0.6119, +0.2727, +0.4561, -0.0039, -0.5774, -0.9105, -0.0751,
+ +0.9462, +0.2550, +0.2783, -0.2219, -0.1080, -0.2208, -0.6883,
+ +0.1096, -0.7935, -0.3954, +0.1652, +0.1019, -0.4601, +0.4553,
+ -0.6417, -0.1358, -0.4737, +0.3128, -0.3267, -0.0540, -0.0633, +0.0747
+ ],
+ [
+ -0.2253, -1.2597, -0.2355, +0.7981, +0.4423, -0.6973, +0.1781,
+ -0.4507, -0.4586, -0.6728, -0.0542, -0.9978, -0.0401, -0.1790,
+ +0.0617, -1.1232, -0.1113, +0.1408, +0.1287, -0.2249, +0.2728,
+ +0.4372, +0.1111, +0.0541, +0.0471, +0.6102, -0.1691, +0.0115,
+ +0.4568, +0.0321, -0.8153, -0.2889, +0.2773, -0.3295, +0.4547,
+ +0.0681, +0.3247, +0.0053, -0.2419, -0.1754, +0.4957, -0.6494,
+ -0.1602, -0.1358, +0.2751, -1.3709, -0.3958, -1.4701, -0.0427,
+ -1.6050, -0.3034, +0.2151, -0.6053, -1.0677, -0.5643, -0.7845,
+ +0.3169, -0.8565, -0.3574, +0.2891, +0.1122, -0.2884, +0.0601, -0.4517
+ ],
+ [
+ +0.5794, +0.2631, +0.0298, -0.1887, -0.6058, +0.4974, +0.0394,
+ +0.2606, -0.0979, +0.2046, -0.1194, +0.2263, -0.2702, -0.1877,
+ +0.2569, -0.2315, -0.9000, -0.3146, -0.0264, +0.4439, -0.2352,
+ -0.9247, +0.1092, -0.2865, +0.1680, +0.1662, -0.0617, +0.2461,
+ +0.3578, +0.3580, +0.0366, +0.3635, -0.5039, -0.2711, +0.0653,
+ +0.0065, -1.0248, -0.0090, +0.2204, -0.5041, -0.0247, -0.2344,
+ -0.6278, -0.8120, -0.0303, +0.3207, -0.2989, +0.1933, -0.1498,
+ +0.0319, +0.1813, -0.8244, -0.5803, +0.2969, +0.0516, -0.7916,
+ +0.2017, +0.0585, +0.1980, -0.1696, +0.3148, +0.1424, -1.3858, -0.2667
+ ],
+ [
+ -0.1941, -0.6240, -2.0568, -0.4370, -0.2328, -0.0722, +0.1253,
+ +0.2146, -0.3976, +0.1229, -0.1581, -0.0012, +0.1981, -0.0432,
+ +0.3407, -0.6734, +0.3886, +0.6251, -0.5550, -0.1302, +0.4913,
+ +0.2797, -0.5856, -0.5146, +0.0478, -0.3227, -1.5350, -0.0298,
+ -0.0659, +0.3368, +0.3931, -0.0328, -0.9625, -0.2308, +0.2069,
+ -0.8179, -0.0210, -0.2816, -0.0345, -1.0297, +0.2480, +0.3974,
+ -0.8667, +0.1481, +0.3191, +0.2165, -0.3631, -0.5387, -0.0522,
+ -0.0564, +0.2433, +0.3049, -1.3699, -0.0584, -0.2832, -0.6592,
+ +0.0884, -0.2148, +0.0559, -0.9336, -0.2033, -0.4094, +0.3269, -0.4964
+ ],
+ [
+ +0.0753, +0.1742, +0.0289, +0.2070, +0.1448, -0.2884, -0.3095,
+ +0.1798, +0.0199, -0.2820, +0.1938, -0.3718, -0.3645, -0.3529,
+ -0.3720, -0.0512, +0.0513, +0.2669, -0.2589, +0.1347, -0.1360,
+ +0.0911, +0.3276, +0.1716, -0.2404, +0.1529, +0.1362, -0.5175,
+ -0.2299, -0.7689, -0.3936, +0.5067, +0.1310, -0.1135, -0.3412,
+ +0.1108, +0.1786, +0.0673, -0.0204, -0.3017, -0.2068, -0.0664,
+ +0.4354, -0.2405, -0.2007, -0.0767, +0.2006, -0.2971, -0.1813,
+ +0.1541, +0.2968, -0.1119, +0.0695, -0.1098, -0.1175, +0.0256,
+ -0.3372, +0.1161, -0.0643, -0.0223, -0.1124, +0.0984, -0.2127, +0.2459
+ ],
+ [
+ -1.0418, -0.7575, -0.4414, -0.7391, +0.5002, -0.1492, -0.4713,
+ -0.9001, -0.1078, -0.1626, +0.1688, -0.3508, -0.0691, +0.0143,
+ +0.4832, -0.5588, +0.1924, +0.2538, -0.1200, -0.0766, -0.5754,
+ -0.1720, +0.6831, -0.3890, -0.0020, -0.6173, +0.5652, -0.2394,
+ +0.5254, +0.6080, -0.6162, -1.4693, +0.4980, +0.4190, +0.0770,
+ +0.7358, -0.1511, -0.4138, -0.0947, +0.1821, +0.0477, -0.9686,
+ -0.0194, -0.2626, +0.6581, -0.2775, -0.4984, -0.2816, +0.4898,
+ -0.7165, -0.2212, +0.3316, +0.3437, -0.3604, -1.0851, -1.0551,
+ -0.5356, -0.8371, +0.0848, -0.4796, -0.3950, +0.3524, +0.6147, +0.0963
+ ],
+ [
+ -0.1117, +0.0358, +0.3472, -0.1657, -0.6318, -0.5969, +0.4199,
+ -0.1558, +0.0856, -0.3948, -0.8222, -0.4227, -0.0461, -0.0458,
+ -0.4246, -0.1711, -0.0217, +0.0392, -0.2153, +0.5657, +0.5179,
+ +0.1690, -1.1408, -0.8345, -0.0868, +0.5821, +0.0440, -0.6810,
+ -0.2952, +0.3344, +0.1719, -0.2792, -0.0611, -0.4510, -0.2232,
+ -1.1814, -0.3142, +0.1828, -0.1726, -0.0683, +0.0175, +0.4286,
+ -0.1024, +0.0233, -1.0238, +0.4454, +0.2450, +0.1602, -0.6960,
+ -0.7975, -0.1214, -0.0340, -0.4455, +0.1809, -0.8249, +0.1098,
+ -0.5579, +0.3200, +0.1753, -0.1689, +0.0027, +0.0572, +0.0126, -0.2266
+ ],
+ [
+ -0.1541, +0.2923, -0.2675, +0.0141, -0.2878, -0.2558, -0.6803,
+ -0.4920, -0.0482, +0.2163, -0.2285, -0.1143, +0.1724, -0.2392,
+ +0.0384, -0.7696, -0.5254, -0.2088, +0.4050, +0.1970, -0.2508,
+ +0.1567, -0.1317, +0.2986, +0.1892, -0.7880, -0.0051, -0.1918,
+ +0.1953, -0.0103, +0.2693, -0.5871, -0.7306, -0.0499, +0.0851,
+ -0.5956, +0.4699, -0.0072, -0.1728, +0.1598, +0.0234, -1.2646,
+ -0.1123, +0.0051, -0.0769, -1.4065, -0.1744, -0.0151, -0.2550,
+ -0.1064, +0.1078, +0.0256, -0.4517, +0.2327, -0.0821, -0.1661,
+ +0.0991, -0.4721, +0.2160, +0.3123, -0.2508, -0.8949, -0.6991, +0.3514
+ ],
+ [
+ +0.0703, -0.1692, -1.4867, -0.0076, -0.2931, -0.1692, +0.2276,
+ +0.2554, +0.4607, -0.0033, -0.5308, -0.1111, -0.2342, -1.2702,
+ -0.0528, +0.0717, -0.3220, -1.3547, +0.1024, +0.0170, +0.4253,
+ +0.2123, -0.1259, -0.3122, -0.0105, -0.1530, -0.0172, +0.1871,
+ -0.2647, -0.4114, -0.3456, +0.0040, -0.6042, -0.3889, -0.4615,
+ -0.4490, +0.2165, +0.5019, +0.1494, +0.4083, -0.3297, -0.4118,
+ -0.4185, -0.1609, -1.2773, -0.6846, +0.5723, -0.8063, -1.1917,
+ +0.1809, +0.1200, +0.3350, -0.3911, -0.6569, -0.5049, -0.2564,
+ +0.2318, -0.2522, +0.4132, -0.0193, +0.2003, +0.4302, -0.8441, -0.4850
+ ],
+ [
+ -0.0068, +0.1774, +0.0754, -0.1137, +0.1380, -0.1756, +0.0479,
+ +0.1636, -0.0450, -0.0059, +0.0132, +0.0796, -0.0633, +0.1532,
+ -0.5575, +0.0712, +0.3744, +0.0354, -0.0290, +0.4456, +0.2901,
+ +0.4112, +0.3827, +0.4580, -0.1335, +0.3195, +0.4608, +0.6066,
+ -0.3994, -0.8452, -0.9019, +0.8846, -0.7821, -0.3973, -0.7044,
+ -0.5552, +0.1131, +0.1128, +0.2313, -0.0934, -0.1934, -0.2593,
+ -0.1353, -0.4150, -0.3226, +0.3543, -0.1122, -0.7826, -0.3823,
+ -0.1661, +0.3273, -0.2386, +0.3994, +0.2439, -0.1369, +0.1377,
+ +0.6842, -0.1323, -0.1286, -0.7267, -0.1476, +0.2956, -1.1468, -1.1240
+ ],
+ [
+ +0.4587, -0.7120, -1.2147, +0.4533, +0.2276, +0.1187, +0.0242,
+ -0.1101, -0.4575, +0.4281, -0.1702, +0.4025, -0.3204, -0.3382,
+ +0.0152, -0.3671, +0.5063, +0.0993, -0.5994, +0.7286, -0.1769,
+ +0.0241, -0.1544, -1.1380, -0.0154, -0.1003, +0.2631, -0.3019,
+ -0.4871, -0.4790, +0.1549, +0.0706, -0.4589, +0.1127, +0.0359,
+ -1.3804, +0.1469, +0.2458, +0.1503, -0.8209, +0.2133, +0.3083,
+ -0.9755, -0.1969, +0.7787, +0.3313, +0.1551, -0.1931, +0.1911,
+ -0.5686, +0.1347, +0.0831, -0.1930, +0.1631, -0.2833, -0.7028,
+ -0.1118, +0.1533, -0.3999, -0.4258, -0.9083, -0.2582, +0.1941, +0.0233
+ ],
+ [
+ +0.0318, -0.8817, -1.4912, -0.0615, -0.2420, -1.2041, +0.2243,
+ +0.0201, -0.4026, -0.0492, -1.1668, -0.4146, -0.1817, -0.3084,
+ -0.1083, +0.1698, +0.2102, +0.4088, -0.0380, +0.1766, +0.1979,
+ +0.1506, -0.0227, -0.3307, +0.0935, +0.1202, +0.1487, +0.3542,
+ -0.3225, -0.8973, -0.2828, +0.2174, +0.0593, -0.3961, +0.5630,
+ -0.6109, -0.2253, +0.4927, -1.3722, +0.5185, -0.2207, +0.0805,
+ -0.4203, -0.4720, -0.6695, +0.5880, +0.2328, -0.2068, -0.6150,
+ -0.2285, -0.7370, -0.7668, +0.3113, +0.2548, -0.5908, +0.0268,
+ +0.0115, -0.6208, -0.2927, -0.3607, +0.1788, +0.1785, +0.3288, -0.2640
+ ],
+ [
+ +0.3848, -0.7088, -0.5749, +0.1465, -1.2500, +0.0894, +0.0777,
+ +0.1599, -0.1955, +0.1559, -0.7550, +0.0516, -0.1624, +0.1289,
+ -0.0537, -0.6007, -0.3695, -0.0942, -0.0091, +0.1988, +0.3324,
+ -0.2406, -0.5028, -0.7058, -0.0122, +0.1081, +0.2517, +0.1361,
+ -0.5815, +0.0485, +0.0734, +0.0126, +0.1104, +0.3183, +0.3643,
+ -0.0232, +0.1123, +0.0566, -0.0732, -1.0371, -0.2023, -0.3095,
+ -0.0496, +0.2435, +0.0358, +0.1252, -0.0470, +0.1997, +0.1537,
+ +0.2705, -0.1455, -0.4738, -0.1437, -0.2477, -0.0010, +0.1878,
+ -0.3148, +0.3925, +0.0561, -0.6492, +0.2474, +0.0362, -0.0897, -0.0669
+ ],
+ [
+ +0.4270, +0.3770, +0.1042, -0.1881, -0.1886, -0.3124, -0.1310,
+ +0.4075, +0.1730, +0.1946, +0.0432, +0.4997, -0.2206, +0.0528,
+ -0.2293, +0.0143, +0.3952, +0.0471, -0.4042, +0.2191, +0.2432,
+ +0.2490, +0.3498, +0.1874, -0.1504, +0.4387, +0.1808, +0.4898,
+ -0.3061, -0.3669, -0.6956, +0.2347, -0.3228, -0.6154, +0.1517,
+ -0.1794, -0.5862, +0.2166, -0.0318, +0.1555, -0.5109, -0.2037,
+ -0.0856, -0.7037, -0.3461, +0.5705, +0.3204, -0.3547, -0.2938,
+ +0.1567, +0.1097, -0.0829, +0.1561, +0.1868, -0.1200, +0.0785,
+ +0.3374, +0.6903, +0.3010, -0.6605, +0.1897, +0.5542, -0.3416, -0.4434
+ ],
+ [
+ +0.0792, -0.0354, +0.1346, -0.0867, -0.3061, -0.1105, -0.1961,
+ +0.3380, +0.2322, +0.1389, +0.3620, +0.1611, +0.1719, +0.1811,
+ -0.2072, +0.0334, -0.3774, -0.2193, +0.2164, +0.1568, +0.0684,
+ +0.2052, +0.0536, -0.1594, +0.0561, +0.2893, -0.5556, +0.3248,
+ -0.6442, -0.5264, -0.0596, +0.3401, -0.4276, -0.0385, -0.1273,
+ +0.0564, +0.0775, +0.3581, -0.1403, +0.1570, -0.0367, -0.1462,
+ +0.1820, -0.0586, -2.0140, +0.2617, +0.2951, -0.0837, -0.2212,
+ +0.1362, -0.1088, +0.5008, -0.5582, +0.0823, -0.2323, -1.4969,
+ +0.0935, +0.1385, +0.2140, -0.0230, -0.1270, -0.1048, +0.0824, +0.2496
+ ],
+ [
+ +0.2433, -0.2738, -0.6610, -0.0505, -0.2477, +0.3417, +0.5587,
+ -0.5406, -1.0247, -0.2288, +0.3152, +0.1982, +0.0772, +0.1352,
+ -0.4929, +0.2685, -0.2318, +0.0696, +0.0467, -0.2719, -0.2102,
+ +0.3232, +0.6245, -0.0790, -0.0616, +0.0617, -0.1172, -0.1969,
+ -0.2093, -0.2784, +0.6245, +0.0007, +0.4830, -0.2599, +0.4948,
+ +0.6130, -1.0589, +0.6332, -0.0488, +0.2545, -1.2056, -0.5316,
+ -0.0954, +0.3171, -0.2520, +0.2887, +0.0818, -0.1944, -0.2920,
+ -0.1329, -0.5170, -0.2719, +0.0334, -0.2360, +0.4558, +0.3121,
+ +0.4630, -0.5016, +0.2215, -0.5113, +0.4688, +0.3660, +0.3881, -0.0949
+ ],
+ [
+ -0.2656, +0.3331, +0.1076, +0.4581, -0.1431, -0.3597, -0.5184,
+ +0.3444, -0.1091, -0.8341, +0.1024, -0.4100, -0.1841, -0.2893,
+ +0.2359, -0.1603, +0.1739, +0.0252, -0.2123, -0.0169, -0.5213,
+ +0.0193, +0.4833, -0.1353, -0.0798, -0.3748, +0.0164, -0.6037,
+ -0.1706, -1.1654, +0.0855, -0.3299, +0.1365, -0.0167, +0.1727,
+ +0.2777, -0.2126, -0.2516, -0.4917, -0.4254, -0.5338, +0.2868,
+ +0.4736, +0.4043, +0.1799, +0.5764, -0.4045, +0.4918, +0.0200,
+ +0.2983, +0.1779, +0.1119, -0.0803, +0.0530, -0.0388, -0.0848,
+ -1.1362, -0.7623, -0.6830, +0.2258, -0.3375, -0.5304, -0.0166, -0.0452
+ ],
+ [
+ +0.3656, -0.0786, -1.3351, +0.4419, -1.4259, +0.3107, +0.1254,
+ -0.3197, -1.0404, -0.0778, -0.7287, -0.8611, -0.0762, -0.8058,
+ -0.1075, +0.0800, -0.3792, +0.0459, -0.0407, -0.0736, -0.0587,
+ +0.0415, +0.0496, -0.1451, -0.0132, -0.0385, +0.1978, -0.3532,
+ -0.2219, -0.6179, +0.8095, -0.9253, -0.0623, -0.8459, -0.2542,
+ +0.1622, -0.5230, +0.4588, -0.5261, -0.4698, -0.3448, -0.7056,
+ +0.0831, +0.5875, -0.4304, -1.2342, +0.1449, +0.3140, -0.8756,
+ -0.6573, +0.2131, -0.5328, -0.0440, -0.2245, +0.0357, +0.4620,
+ -0.5595, -0.3738, -0.7502, +0.1694, -0.1364, +0.0650, +0.0636, +0.0344
+ ],
+ [
+ -0.0606, +0.0726, +0.0580, -0.7201, +0.0616, -0.2663, -0.5110,
+ -0.3657, -0.3247, +0.2932, +0.0176, -0.2670, +0.0671, +0.0998,
+ +0.4772, -1.4650, -0.3015, -0.4687, -0.4883, +0.2534, +0.3658,
+ +0.0559, -0.4296, -0.1036, -0.0094, -0.2585, +0.0756, +0.2631,
+ +0.2918, -0.1307, -0.0181, +0.0034, -0.2567, -0.5368, +0.2606,
+ -0.3876, +0.5663, -0.4215, +0.2809, +0.0201, +0.4246, +0.1693,
+ -1.1285, -0.0438, -1.0839, -0.1515, -0.0892, -0.7921, -0.0792,
+ +0.4657, +0.4911, +0.0949, +0.0362, +0.2820, -1.4115, -0.3908,
+ +0.0311, -1.3656, -0.6728, +0.2379, -0.1602, -0.6410, +0.6788, -0.0510
+ ],
+ [
+ -0.5191, +0.3638, +0.0075, -0.0052, +0.3951, +0.1660, -0.0268,
+ -0.1166, +0.8735, +0.3597, -0.3420, +0.1475, +0.2089, -0.2733,
+ -0.1302, +0.0650, -0.1682, -0.6237, -0.1886, +0.1425, +0.1127,
+ -0.0607, -0.8113, -0.4995, +0.0277, -0.1803, -0.2508, +0.0372,
+ -0.3036, -0.4915, +0.1037, +0.0229, -0.2382, -0.2354, -0.1711,
+ +0.1846, -0.8776, -0.0200, -0.4414, -0.1533, +0.0448, -0.2010,
+ +0.0688, -0.3020, -0.0526, +0.1589, +0.3231, +0.2847, -0.8578,
+ +0.2167, +0.0969, -0.2852, -0.6027, +0.1368, +0.1651, -0.2152,
+ +0.1624, +0.3639, +0.1221, -0.4960, +0.1362, -0.0557, -0.4168, -0.2864
+ ],
+ [
+ +0.6175, +0.2864, -0.3944, -1.0445, -0.5126, +0.4037, +0.2065,
+ +0.1380, +0.2727, +0.3778, +0.0995, +0.2318, -0.0628, +0.3280,
+ -0.0223, +0.0671, -0.7848, +0.3413, +0.1067, -0.3424, -0.6270,
+ -0.2365, -0.3945, -0.1812, -0.0288, -0.4210, -0.2331, +0.4286,
+ +0.9716, +0.3043, -0.3778, +0.2830, -0.3521, +0.2004, +0.2613,
+ -0.1126, -0.5060, -0.5227, -0.0945, -0.8172, -0.5810, +0.3176,
+ -0.0357, -0.6075, -0.5641, -0.2488, -0.0749, -0.1395, +0.5087,
+ +0.4870, +0.3374, -0.4190, -0.2451, +0.4110, +0.3360, -0.0793,
+ +0.2368, +0.1880, +0.1418, -0.5637, -0.6581, -0.2530, -1.2775, -0.5173
+ ],
+ [
+ +0.2575, +0.5610, -0.5591, +0.4868, -0.6510, -0.4951, -0.1665,
+ -0.7622, -0.4095, +0.0202, -0.4084, +0.7634, +0.0548, -0.1287,
+ -0.5385, -0.5446, -1.2329, -0.5231, +0.0580, +0.1868, -0.5969,
+ -0.4468, -0.3048, -0.6629, -0.0188, -0.4573, -0.2831, -1.3261,
+ -0.3051, -0.4240, +0.2223, -1.0709, +0.0737, -0.0383, +0.1114,
+ +0.4315, -0.8949, +0.2700, -0.0884, -0.0519, +0.1506, -0.5043,
+ -0.9217, +0.1245, -1.1364, +0.3721, -0.0370, +0.0862, -0.4580,
+ -0.1029, +0.0867, -0.1142, -0.1955, +0.2370, -0.1568, -0.8279,
+ -0.0199, -0.5395, +0.0016, -0.5594, +0.1911, -0.2403, +0.4911, -1.0443
+ ],
+ [
+ -1.3302, -0.9338, +0.3871, -1.1495, -0.3531, -0.1944, -0.8389,
+ -0.8362, -0.3735, -0.1939, -0.3993, -1.1031, -0.2929, -0.3900,
+ +0.1848, -0.8209, -0.7968, -0.8029, -0.1552, -0.2470, -0.0961,
+ -0.9054, -0.8644, -0.2718, +0.1205, -0.7466, +0.5260, -0.8186,
+ +0.2249, -0.1852, +0.1637, +0.2386, -0.3861, -0.1152, +0.7676,
+ -0.3567, +0.2007, -0.0614, +0.1410, +0.2211, -0.2671, +0.0567,
+ +0.1667, -0.3056, -0.5998, -1.5851, -0.1660, -0.1601, +0.2225,
+ +0.6939, +0.1670, +0.4183, +0.0228, +0.5104, -0.9676, -0.6234,
+ +0.1827, -0.2717, -0.2918, +0.1188, -0.0111, -0.6147, +0.4209, +0.0278
+ ],
+ [
+ +0.1161, +0.2482, +0.2554, +0.4476, +0.0995, -0.4997, +0.2332,
+ +0.9127, +0.3242, -0.8211, +0.0737, -0.1947, -0.1772, -0.6136,
+ -0.5493, +0.2106, +0.1126, -0.3909, -0.0581, -0.0024, +0.1720,
+ -0.2446, -0.1968, -0.1427, -0.1429, +0.2843, -0.5226, +0.4872,
+ -0.0392, -0.2645, -0.6053, -0.5143, +0.4939, -0.1568, -0.1001,
+ -1.0052, -0.5236, -0.1548, -0.4120, +0.2023, -0.5504, -0.2983,
+ +0.0447, -1.5144, -0.1567, +0.2201, +0.1278, -0.2537, +0.1308,
+ -0.1034, +0.6555, -1.3159, -0.5089, -0.1758, -0.3958, -0.5218,
+ -0.1935, +0.2361, +0.2255, -0.7272, -0.0587, -0.2821, -0.3442, -0.7232
+ ],
+ [
+ -0.3517, -0.0203, -0.3070, -1.2829, +0.3473, +0.4040, -0.1731,
+ -0.2593, +0.0120, -1.7168, +0.0700, +0.0111, -0.0112, +0.0938,
+ -0.2550, -0.0387, -0.9967, -0.0670, -0.1163, -0.0396, -0.6377,
+ -0.9166, +0.1814, -0.1000, -0.2425, -0.0557, -0.3294, +0.4148,
+ +0.3240, +0.1026, -0.1858, -0.0817, -0.0452, +0.2382, -0.6017,
+ +0.0693, +0.1167, -0.9697, +0.0599, -1.1097, -0.0638, +0.7294,
+ +0.2900, -0.6312, -0.5011, +0.2075, +0.0598, -0.4969, -0.1090,
+ -0.1907, +0.0369, +0.0796, -1.7630, -0.1289, +0.1517, -1.3118,
+ -0.8149, -0.2056, +0.1837, -0.0746, -0.6321, -0.6908, -0.0132, +0.0751
+ ],
+ [
+ -0.6365, -0.6129, -0.0568, -0.9972, -0.1083, -0.5357, -0.1754,
+ -0.4249, -0.3845, -0.4516, +0.1213, +0.6502, +0.1079, +0.2016,
+ -0.2369, +0.2815, -0.3741, -0.0515, +0.1369, -0.3568, +0.1390,
+ -0.7787, -0.1987, -1.0299, +0.1383, +0.1656, -0.7985, -0.6206,
+ +0.3338, +0.0575, -0.7736, -0.2891, +0.1845, -0.3902, -0.4144,
+ +0.4074, +0.1418, -0.3710, +0.2686, +0.0234, -0.2382, -0.4719,
+ -0.0803, -0.5591, +0.3811, -1.2136, -0.8015, -0.3746, -0.0117,
+ -1.8425, +0.0330, -0.2085, +0.1446, -0.1752, -0.5046, -1.0435,
+ +0.1141, -0.0602, +0.4022, +0.4310, +0.2164, -0.1623, -0.1944, -0.1913
+ ],
+ [
+ -0.5695, -0.3372, -0.2433, -1.2988, -0.6181, +0.0353, +0.4011,
+ -0.3847, -0.0820, +0.1582, -0.4111, +0.0552, +0.0906, +0.0849,
+ +0.0692, +0.1922, -0.0549, -1.7126, -0.2257, +0.1049, +0.0016,
+ -0.6541, -1.0900, -0.2897, -0.2057, -0.7505, -0.7495, +0.1641,
+ +0.3909, -0.1974, +0.1989, -0.0289, -0.6525, +0.2379, +0.2185,
+ -0.7424, +0.3704, -1.3808, -0.4839, -0.1950, -0.3002, -0.1963,
+ +0.0819, -1.7138, -0.7822, -1.4837, -0.1470, +0.0372, -0.0416,
+ +0.0395, -0.2169, +0.4130, +0.1063, +0.7070, -0.0286, -1.1673,
+ -0.3685, -0.7736, +0.0467, +0.2205, +0.0719, -0.5629, -0.1000, -0.7227
+ ],
+ [
+ -0.0742, +0.2908, +0.0301, +0.2182, -0.0747, -0.1263, -0.1355,
+ +0.2109, -0.2850, -0.5664, +0.1393, -0.3777, -0.1310, +0.1102,
+ +0.3325, -0.1378, -0.0709, +0.1402, +0.0943, -0.0407, -0.3467,
+ +0.0916, +0.2023, -0.1731, -0.1292, +0.1054, -0.0246, -0.2775,
+ +0.0886, +0.3904, +0.0465, -0.5304, -0.0224, +0.1768, -0.2666,
+ +0.2306, +0.1383, -0.7646, +0.0099, -1.2146, -0.9118, -0.5281,
+ +0.1534, +0.3789, -0.0579, -0.1973, -0.1614, +0.6662, -0.3768,
+ +0.3651, +0.4518, +0.1664, -0.1549, +0.1844, +0.1412, +0.0283,
+ -0.7128, -0.8330, -1.7285, -0.1793, -0.2031, -0.1453, +0.2164, +0.2915
+ ],
+ [
+ -0.4528, +0.3647, +0.1067, -0.1699, -0.5783, +0.1129, -0.1196,
+ -1.6987, +0.2552, +0.0092, -0.2868, -0.1119, -0.0707, -0.0441,
+ +0.3715, +0.1826, -0.7670, -0.7732, +0.0356, -0.3435, -0.8718,
+ -1.0227, -0.6381, -0.2767, -0.1146, -0.9304, -0.2226, +0.4722,
+ +0.2540, -0.7784, +0.5070, +0.1428, -0.6285, -0.1488, -0.6175,
+ +0.2040, +0.2312, -0.1978, +0.0764, -0.3868, +0.9002, +0.2344,
+ -0.5108, -0.2623, -0.8658, -0.6194, +0.1982, -0.6725, -1.8083,
+ +0.2282, +0.1429, +0.3556, -0.0452, +0.3160, -0.3793, -0.6729,
+ +0.7203, +0.1603, -0.3994, -0.2190, -0.7442, -0.0352, -0.7935, -0.1473
+ ],
+ [
+ -0.8168, -0.0091, -0.0508, -0.4927, -0.6616, +0.4340, -0.2432,
+ +0.4167, +0.3489, +0.8354, +0.2251, +0.0112, -0.0185, -0.6260,
+ -0.2298, -0.0221, -0.6862, -0.2349, +0.2170, +0.1041, -0.6343,
+ -0.8665, +0.1858, -1.4852, -0.0523, -0.8654, -0.5574, -0.3615,
+ -0.3560, -0.3082, -1.4751, -0.5826, +0.1229, +0.0924, -0.1141,
+ -0.0477, +0.1553, -0.3143, -0.5285, -0.7833, +0.2824, -0.4220,
+ +0.1819, -0.2719, -0.0280, -0.6713, -0.8150, -0.5180, -0.1413,
+ +0.2325, -0.3501, +0.0866, -0.2519, +0.3551, -0.4227, -0.1018,
+ -0.9312, -0.2401, +0.4466, -0.2421, -0.4953, -0.9608, -0.3090, +0.0437
+ ],
+ [
+ -0.3678, -0.0514, +0.8817, -0.7280, -0.1600, +0.8120, -0.4446,
+ -0.1063, -0.5102, +0.1453, -0.0061, -0.1726, +0.0986, +0.2938,
+ +0.1933, +0.3513, +0.5222, +0.1550, -0.0421, +0.1425, -0.1413,
+ +0.1639, -0.8166, -0.1317, -0.4997, -0.0874, -0.3524, -0.8873,
+ -0.9856, +0.6431, +0.1933, +0.0048, -0.0601, +1.0241, +0.3887,
+ -0.7046, +0.4948, -0.7165, +0.0877, +0.0682, +0.6019, +0.5806,
+ +0.3123, -0.1842, -0.1036, +0.3439, -0.4009, -0.4758, +0.2913,
+ +0.0956, +0.6178, -1.4622, -0.1621, -0.7775, -0.0004, +0.2367,
+ -0.2088, -0.9526, -0.1860, +0.1470, +0.1572, -0.1658, +0.1708, +0.5259
+ ],
+ [
+ -0.2214, +0.1985, -0.1847, +0.5871, -0.3763, +0.0672, -0.1033,
+ -0.0671, +0.1542, +0.0275, -0.5201, +0.1248, +0.1134, -0.3788,
+ +0.0484, -0.5302, -0.0118, -0.8965, +0.0713, +0.0392, +0.1628,
+ -0.0572, -1.8384, -0.3889, -0.2469, +0.4550, -0.0606, +0.0431,
+ -0.0217, -0.4960, +0.1855, -0.1257, +0.2440, +0.0600, +0.2227,
+ -0.6121, -0.2051, +0.0859, -0.4757, -0.2172, -0.1453, +0.1773,
+ -0.3348, +0.1459, +0.1331, -0.0931, +0.0132, +0.2765, -0.3224,
+ -0.7257, -0.0038, -0.1957, -0.6276, -0.1183, +0.0673, +0.3088,
+ -0.0822, +0.1390, +0.4112, +0.0519, +0.3311, +0.2228, -0.4378, -0.5721
+ ],
+ [
+ -0.0147, -0.0421, +0.0189, -0.4632, -0.1887, +0.1763, +0.2966,
+ -0.2942, -0.1684, +0.0008, +0.3991, -0.1310, +0.2420, +0.3445,
+ +0.0718, -0.2459, -0.4664, -0.7893, +0.0726, -1.0375, -0.7542,
+ -0.5141, +0.3281, -0.5370, -0.4788, -0.4261, +0.1905, +0.0993,
+ +0.4738, +0.1131, +0.1462, -0.1149, -0.8987, -0.3439, -0.0783,
+ +0.3170, +0.2363, -0.2870, -0.1533, -0.1604, +0.2246, -0.9061,
+ -0.3147, +0.0034, -0.0893, -0.1349, -0.3582, +0.0769, +0.3767,
+ -0.1624, -0.3113, -0.3842, +0.2768, +0.5184, +0.1937, +0.6202,
+ +0.2389, +0.0061, +0.2531, -0.1111, -0.3178, -0.1828, -0.2073, -0.2022
+ ],
+ [
+ -0.1047, -0.1899, -0.0452, -1.5021, -0.0903, -0.5365, -0.7039,
+ -0.8838, +0.0651, -0.0976, -0.5219, -0.2925, +0.1947, -0.0408,
+ +0.0430, -0.5362, -0.3390, -0.2032, -0.3870, -1.5461, -0.4847,
+ -0.8721, +0.0815, +0.0294, +0.0019, -0.1992, -0.0342, -0.7489,
+ +0.3711, -0.1925, -0.3552, -0.0407, -0.0402, -0.4258, -0.1176,
+ -0.6723, +0.4815, -0.2728, +0.1984, -0.4091, -0.3322, -0.0223,
+ -0.4487, -0.6132, -0.7094, -0.5729, -0.3616, -1.4608, -0.1466,
+ -0.2963, -0.1808, +1.0996, -1.1116, +0.0384, +0.1127, -1.0002,
+ -0.3117, -0.4126, +0.1461, -0.2834, +0.1687, -1.2180, +0.8404, +0.3414
+ ],
+ [
+ -0.2871, -0.2753, +0.3318, -0.0631, -0.0329, -0.2655, +0.1154,
+ +0.1341, -0.3528, -0.4633, -0.4270, +0.1776, +0.1154, -0.0745,
+ -0.3922, +0.0375, +0.0055, +0.4779, -0.1397, -0.5729, -0.1113,
+ +0.0881, -0.0655, -0.4586, -0.0322, +0.1184, -0.5583, -0.4987,
+ -0.0660, -0.1451, +0.1862, -0.8150, +0.8184, -0.0894, -0.3762,
+ -0.5304, -0.5791, +0.0317, -0.2269, +0.2771, -0.1284, -0.3164,
+ -0.5405, +0.1469, -0.8860, +0.4223, +0.1829, -0.3194, -0.4208,
+ +0.4972, -0.7205, -0.7719, -0.3450, +0.5980, -0.1395, -0.3528,
+ -0.1897, +0.1412, +0.1881, -0.0785, +0.3184, -0.3845, -0.3870, -0.1074
+ ],
+ [
+ -0.0549, -0.1759, -1.4543, -0.4064, -0.4019, +0.0416, +0.2107,
+ -0.9047, -0.5796, +0.0453, -0.2060, +0.7131, +0.1083, +0.0712,
+ +0.0948, -0.7550, -1.0484, -0.1334, -0.3905, +0.3899, -0.6879,
+ -0.9365, +0.3175, -0.2515, -0.0216, -0.6523, -0.5432, -0.3200,
+ +0.2436, +0.4666, +0.2695, +0.6725, -0.3633, -0.4047, +0.0874,
+ +0.2482, +0.0669, +0.0321, -0.0457, +0.2833, +0.4448, -0.1799,
+ +0.0688, +0.0473, +0.0295, +0.4890, -0.1082, -0.2163, +0.2725,
+ -0.0772, -0.0288, +0.4464, -0.2413, +0.0908, +0.3795, -0.7329,
+ +0.0918, -0.0568, +0.4359, -0.1642, -0.4720, -0.6958, +0.3310, -0.9285
+ ],
+ [
+ -0.3428, +0.3394, +0.2910, +0.0395, +0.1968, -0.3811, -0.3117,
+ +0.2441, +0.2823, -0.4930, +0.1645, +0.1595, -0.2763, +0.2406,
+ -0.3192, -0.4154, -0.2809, +0.0606, -0.1039, +0.2498, -0.4704,
+ -0.1710, -0.3512, -0.0781, -0.1085, -0.2105, -0.1707, +0.1695,
+ +0.2557, -0.8382, -0.4814, -0.3560, +0.0130, -0.0411, -0.5253,
+ +0.1622, +0.0977, -0.3241, +0.3357, -1.1972, -1.0786, +0.0531,
+ -0.0801, -0.1700, -0.1637, -0.3555, +0.0159, +0.3452, -0.2490,
+ -0.0398, +0.3255, +0.0474, -0.2646, +0.2222, -0.0094, -0.4791,
+ -0.7316, -0.1143, -0.5465, -0.2249, -0.4003, -0.4671, -0.0495, +0.1696
+ ],
+ [
+ -0.4032, -0.7569, -0.6099, -0.1711, -0.8909, +0.2922, +0.1176,
+ -0.3625, -1.0356, +0.2123, -0.6401, +0.1968, -0.3508, +0.1569,
+ -0.0021, -0.8648, -0.0136, +0.0362, -0.4099, +0.0140, -0.3279,
+ +0.0350, +0.1094, -0.4495, -0.1535, -0.8482, -0.3956, +0.0348,
+ -0.8475, -0.1615, +0.4068, +0.2318, -0.3285, -0.4544, +0.3332,
+ +0.4241, -0.1228, +0.1105, +0.2951, -0.1227, -0.0585, -0.1504,
+ +0.0110, -0.4835, +0.0051, +0.2351, -0.7890, -0.3031, -0.1653,
+ -0.0390, -0.2326, -0.3724, +0.1074, +0.0847, -0.0288, -0.0392,
+ +0.1232, +0.3832, -0.0923, +0.2702, -0.0836, -0.6782, +0.1941, -0.5479
+ ],
+ [
+ -0.0042, -0.1946, -0.1632, +0.2652, -0.3281, -0.5539, +0.1933,
+ -0.5138, -0.7291, -0.0916, +0.0651, -0.0960, -0.0087, -0.6420,
+ -0.1012, -1.2801, +0.0314, +0.3125, -0.1892, +0.0743, -0.2332,
+ +0.0198, +0.1641, +0.1603, +0.0527, -0.1782, +0.2653, -0.9144,
+ -0.2789, +0.2436, -0.0685, +0.8306, -0.1436, -0.3050, -0.1886,
+ +0.1350, -1.0503, -0.2253, -0.2741, +0.2681, -0.4613, -0.7832,
+ +0.5836, +0.0801, -0.5491, +0.1075, +0.3780, +0.3248, -0.2623,
+ +0.0749, +0.1353, -0.6015, +0.3448, -0.0809, +0.0375, +0.2001,
+ -0.2588, -0.2804, -0.2702, +0.2283, +0.1124, +0.4594, -0.4324, +0.1485
+ ],
+ [
+ +0.1532, +0.2848, -0.2427, +0.4166, +0.0042, -0.3085, +0.1124,
+ +0.2537, +0.1375, -0.2485, -0.0234, -0.0071, -0.0783, -0.2518,
+ +0.1560, -0.5850, +0.1183, -0.0517, -0.1053, +0.3356, +0.3028,
+ +0.2722, +0.1897, +0.2332, -0.3597, +0.5258, -0.0684, -0.0984,
+ -0.2643, -0.5880, +0.1289, +0.0015, -0.1563, -1.0911, -0.2512,
+ -0.4506, +0.0817, +0.1627, -1.0543, +0.6363, -0.2562, -0.5514,
+ -0.2316, +0.0717, -0.1111, -0.1945, +0.1628, -0.0464, -0.4399,
+ -0.2649, +0.1594, +0.0358, -0.1435, +0.1108, +0.1648, +0.4697,
+ -0.0951, +0.1059, -0.5489, -0.4333, -0.0550, -0.2629, -0.9481, -0.0023
+ ],
+ [
+ -0.1565, +0.0574, -0.2594, +0.1234, +0.1356, -0.2661, +0.3433,
+ +0.2905, -0.1498, -0.0338, +0.3885, -0.0082, +0.0051, -0.8434,
+ +0.2996, -0.1082, -0.2098, -0.4112, -0.1268, -0.1134, +0.2039,
+ +0.0491, -0.0465, -0.5719, -0.1081, -0.0628, -0.5965, +0.3252,
+ -0.0130, -0.3893, -0.0323, +0.1651, -0.5723, +0.4407, +0.0223,
+ -0.1040, -0.2432, +0.0811, -0.1804, +0.2986, +0.0872, -0.0198,
+ +0.1289, -0.7460, -0.4659, +0.3831, -0.0848, -0.8659, -0.4278,
+ +0.1593, -0.2717, -0.2745, -0.4147, -0.4569, -0.4038, -0.3464,
+ +0.0218, -0.1718, +0.2309, +0.1343, +0.2253, -0.1355, -0.4830, -0.4628
+ ],
+ [
+ +0.0450, -0.7682, -0.5959, +0.1884, -0.3429, -0.2553, +0.7554,
+ -0.1022, +0.4099, -0.1219, -0.2093, -0.0878, +0.0561, -0.5284,
+ +0.0385, -0.7532, +0.5020, -0.9372, -0.1928, -0.3592, -0.0536,
+ -0.1005, -0.1540, -0.2265, -0.1188, +0.1608, +0.1528, +0.2769,
+ +0.5073, -0.1996, -0.1063, +0.1040, -0.8756, -0.0927, -0.0733,
+ -0.4302, -0.4747, +0.4669, -1.0292, -0.2093, -1.6550, -0.7398,
+ -0.0037, -0.0352, -0.7409, +0.0588, +0.1492, +0.1683, -0.3111,
+ +0.1539, -0.2438, -0.8038, +0.1800, +0.0742, +0.2182, +0.2555,
+ +0.1701, -0.2382, -0.0567, -0.2451, -0.3627, -0.0496, -0.0007, +0.0642
+ ],
+ [
+ -0.0198, -0.7084, -1.7288, +0.0023, -0.6159, -0.3045, +0.2740,
+ -0.6177, -0.9246, -0.7641, -0.0082, -0.1067, -0.1914, -0.1873,
+ +0.3149, -0.3414, +0.2478, +0.5272, +0.0465, -0.2181, +0.2295,
+ +0.1319, -0.0236, -0.2259, -0.3665, +0.1407, +0.5191, -0.2611,
+ -0.0468, +0.2089, -0.1337, -1.2692, +0.2063, -0.2235, +0.2870,
+ -1.0765, +0.2921, +0.0708, -0.8893, +0.1605, -0.4512, -0.1917,
+ -0.1650, -0.1710, +0.2144, -0.1577, -0.0188, -0.2185, -0.2129,
+ -0.3773, -1.1166, -0.8290, +0.2877, +0.1461, -0.1932, +0.4364,
+ -0.2597, -0.6060, +0.3258, -0.1753, +0.3740, +0.1653, +0.3116, +0.1972
+ ],
+ [
+ -0.5676, -0.1738, +0.0645, -1.0766, +0.5088, -0.2353, +0.1632,
+ +0.0342, +0.6782, -0.1393, -0.1100, -0.4369, +0.1336, +0.2995,
+ -0.5347, +0.4146, -0.0427, -0.2986, -0.0927, +0.0586, +0.5212,
+ -0.0742, -0.0939, -0.4191, -0.0830, -0.0546, -0.3702, +0.6367,
+ +0.0227, -0.0992, -0.2374, -0.0286, -0.3807, +0.0304, -0.2574,
+ +0.0564, +0.0096, +0.1621, +0.1392, -0.3874, -0.0431, +0.2932,
+ +0.3008, -0.3351, -1.0291, +0.9737, +0.1879, +0.4559, -0.2085,
+ +0.1174, +0.6974, +0.1809, -1.4216, -0.7912, -1.2257, +0.1453,
+ -0.2233, +0.3229, +0.4583, +0.0773, -0.7117, -0.3845, +0.1082, +0.0987
+ ],
+ [
+ +0.0781, -0.0814, +0.8480, +0.2264, -0.4587, -0.3083, +0.1459,
+ +0.4196, +0.3756, -0.1326, +0.0951, -0.2471, -0.1196, -0.8551,
+ +0.0014, -0.2029, +0.2577, +0.2734, -0.0681, -0.4470, +0.5168,
+ +0.1951, +0.0949, -1.0213, -0.0389, +0.2296, +0.4116, +0.1783,
+ -0.4069, -0.2838, -0.1370, +0.0335, -0.0403, -0.0137, +0.4868,
+ +0.1037, +0.3783, +0.1564, -0.1589, +0.3586, +0.0252, -0.2580,
+ +0.1670, -0.4183, -0.0371, +0.0142, +0.2253, -1.0320, -0.2583,
+ -0.1020, -0.2032, -1.3460, +0.5840, -0.0893, -0.6009, +0.5548,
+ -0.0857, -0.0794, +0.3571, +0.0167, +0.0949, +0.1082, -0.2736, -0.3984
+ ],
+ [
+ +0.1488, +0.0836, -0.1156, -0.0946, -0.6624, +0.3870, +0.1203,
+ +0.2345, +0.5957, -0.0864, +0.0939, +0.3911, -0.3770, -0.7077,
+ -0.1206, -0.2049, -0.5693, -1.1134, -0.1524, +0.1622, -0.1211,
+ -0.6374, -0.6248, -1.2622, +0.0899, -0.1572, -0.2152, +0.6604,
+ +0.7116, -0.3532, +0.2550, +0.6011, -0.1052, +0.2644, -0.0520,
+ -0.2045, -1.3817, +0.4718, +0.1422, -0.1959, -0.4853, +0.3969,
+ -0.1666, -1.0437, -0.2013, -0.4767, -0.2118, +0.4010, -0.4163,
+ +0.5423, -0.0842, -0.4901, -0.3661, +0.3607, +0.4009, +0.0245,
+ +0.2585, +0.3218, +0.3151, -0.4333, -0.9903, -0.3832, -0.6528, -0.9357
+ ],
+ [
+ +0.2625, -0.3163, -0.7011, -0.4750, -0.2169, -0.4875, -0.7199,
+ +0.4407, +0.0992, +0.3363, -0.3765, +0.1178, -0.1361, +0.0589,
+ -0.2783, -0.0918, +0.8017, -0.1301, -0.0942, +0.5582, +0.3169,
+ -0.1525, -1.0656, -0.9893, +0.0477, +0.0623, -0.8920, +0.7155,
+ +0.1733, +0.6024, -0.1510, -0.2588, -0.9339, +0.0646, +0.1528,
+ -1.4100, -0.4579, +0.1205, +0.1494, -0.5505, +0.2527, +0.6798,
+ -0.0354, +0.1972, -0.0864, -0.0724, +0.4457, -0.1612, -0.0747,
+ -0.8515, +0.5947, +0.0358, -1.5359, -0.0754, +0.1504, +0.1272,
+ -0.2733, -0.6504, +0.1311, -0.6455, +0.3241, -0.7097, -0.2899, +0.1537
+ ],
+ [
+ -1.1608, -0.5298, -0.8712, +0.1991, -0.3332, +0.3643, +0.0401,
+ -0.4816, +0.3851, +0.2349, -0.6814, +0.1716, -0.2337, -0.0912,
+ +0.4335, -0.1547, -0.4001, +0.3222, -0.1337, +0.3072, +0.2498,
+ -0.2764, -0.8538, -0.2515, -0.0439, +0.1265, -0.5853, +0.0693,
+ -0.4379, +0.1737, +0.3439, -0.7150, +0.3867, +0.3087, +0.4529,
+ -0.6548, -0.2920, -0.0996, -0.9976, -0.3262, +0.7263, +0.7688,
+ -0.9637, +0.0227, +0.3281, +0.2599, -0.6599, -0.0804, +0.2021,
+ -0.4105, -0.8758, +0.5409, -0.3671, -0.0064, +0.3239, -0.5062,
+ -0.1013, +0.0167, -0.2186, -0.4367, -1.0176, -0.3509, -0.0338, -0.1166
+ ],
+ [
+ -0.2009, -0.0097, -0.3805, +0.5547, +0.0211, -0.1902, +0.2175,
+ +0.2475, -0.1842, -0.5084, +0.4752, +0.4515, -0.0791, -0.5530,
+ -0.1438, +0.0275, +0.0589, +0.2926, +0.0454, -0.1496, +0.1475,
+ -0.1997, +0.1834, -0.5198, +0.0427, -0.2978, -0.2438, +0.0810,
+ +0.3660, +0.0816, -0.5628, -0.0037, +0.4582, +0.5978, -0.0285,
+ +0.1455, -0.7267, -0.5732, -0.0079, -0.0751, -0.8395, -1.2686,
+ +0.2954, -0.2310, +0.4056, -0.0743, -0.2228, +0.0327, +0.2061,
+ +0.2131, -0.2174, +0.1368, -0.5607, -0.1470, +0.2396, -0.4317,
+ +0.5534, -0.3621, -0.1064, -1.2382, +0.3209, -0.1634, -0.9480, +0.3144
+ ],
+ [
+ -0.1292, -0.5636, -0.0849, +0.2092, -0.1442, -0.2223, +0.1724,
+ -0.6844, -0.8701, -0.3775, -0.3263, -0.2123, +0.0666, -0.6740,
+ +0.4411, -0.6332, +0.3243, +0.2527, -0.0565, +0.1122, +0.4365,
+ +0.2004, +0.5247, +0.2099, -0.0063, +0.1774, +0.5491, -0.4683,
+ -0.0755, +0.6953, +0.0733, -0.6102, +0.1488, -0.2186, +0.4960,
+ +0.2464, -0.2218, -0.2068, -0.5311, +0.4264, +0.5527, +0.2815,
+ -0.3011, -0.2885, +0.1760, -0.4510, +0.2082, -0.3399, -0.2715,
+ -0.2917, -0.4012, -0.6663, +0.6144, +0.3065, -0.6742, +0.2289,
+ +0.0560, -0.6837, +0.0275, -0.1482, +0.6406, +0.1464, +0.0440, +0.3607
+ ],
+ [
+ -0.2100, -0.3766, -0.3248, -0.0815, -0.0021, -0.0053, +0.1080,
+ +0.1588, -0.0212, +0.0710, -0.1382, +0.0091, +0.0343, -0.8511,
+ -1.4211, +0.4568, -0.2851, -0.6204, +0.1094, -0.5432, -0.0860,
+ -0.2730, -0.6808, -0.3779, -0.1227, -0.1347, +0.0673, +0.0427,
+ -0.4947, -0.0973, -0.3803, -0.1468, +0.1988, -0.2611, -0.6531,
+ -0.1605, -0.9337, +0.5437, +0.0989, +0.1534, -0.4737, -0.8900,
+ -0.6949, -0.1503, -0.9317, +0.3230, +0.2311, -0.3696, -0.4520,
+ -0.7193, +0.6298, -0.2834, +0.5434, -0.5763, +0.3341, -0.1008,
+ +0.2521, -0.1212, -0.2856, +0.0286, +0.1565, -0.1973, -0.9579, +0.2266
+ ],
+ [
+ -0.3733, -0.5246, -1.0401, -1.1247, +0.5040, +0.1447, -0.3600,
+ -0.5734, -0.9212, -0.3597, +0.2485, -0.3560, -0.0752, -0.8746,
+ +0.4507, -0.5267, +0.1474, +0.3419, +0.0363, -0.7705, -1.6857,
+ -1.1070, +0.2625, -1.0731, +0.1143, +0.1023, -0.9064, -0.5451,
+ -0.5312, +0.0702, -0.2498, -1.3055, +0.1746, +0.5512, -1.0339,
+ +0.1665, -0.0061, +0.3917, +0.3936, -0.0938, -0.3131, -0.5685,
+ +0.1470, -0.5130, +0.4499, -0.3169, -0.1906, -0.3272, +0.1276,
+ +0.3542, -0.8497, +0.0924, +0.2336, +0.0205, +0.5533, -0.6078,
+ -0.0380, -0.9867, +0.3744, -0.4039, -0.2097, -0.6184, -0.4652, +0.0281
+ ],
+ [
+ -0.7440, -1.0423, +0.2391, -0.7264, +0.6529, +0.1477, -0.6196,
+ -0.4762, +0.0692, -0.4353, +0.6195, -0.3501, +0.0457, +0.5445,
+ +0.3201, +0.5907, +0.1408, +0.5189, +0.2457, -0.1996, -0.0750,
+ -0.8873, -0.3630, -0.2106, -0.0367, +0.3119, -0.3941, -0.7667,
+ +0.2979, -0.1940, -1.1527, -0.7601, +0.3334, +0.7463, +0.0006,
+ +0.5900, +0.4330, -0.2191, +0.1961, -0.1740, -0.0606, -1.9663,
+ -0.0980, -0.3602, +0.2108, -0.8138, +0.2321, -0.0849, +0.5843,
+ -0.1114, +0.1376, +0.0711, -0.2334, -0.4425, -0.4017, -0.9668,
+ -0.2785, -1.0386, +0.1323, -0.3491, -0.1183, -0.1991, +0.1755, +0.2324
+ ],
+ [
+ -1.6279, -0.5764, -0.5582, -0.1969, -0.2668, +0.0346, -0.5277,
+ -0.4330, -0.3943, +0.3645, -0.1540, +0.0062, -0.0567, -0.0784,
+ +0.1743, -0.9562, -0.4454, +0.0533, -0.1731, +0.1988, +0.1024,
+ +0.5358, -0.4556, -1.0002, -0.1435, -0.2930, -0.4634, -0.2278,
+ -0.3642, +0.3626, +0.5493, +0.1137, -0.1669, -0.4225, +0.0216,
+ +0.4361, -0.1621, -0.1015, -0.0550, -0.3966, +0.5804, +0.1967,
+ -0.3464, +0.0925, +0.3493, +0.1171, -0.3405, -0.0503, +0.1499,
+ -0.3313, -0.0033, +0.0960, -0.6710, +0.2601, -0.1169, -1.5937,
+ -0.0615, -0.1506, -0.2239, +0.1024, -0.2309, -0.4043, +0.4463, -1.0894
+ ],
+ [
+ -0.2373, -1.4598, -0.1174, -0.1045, +0.4946, -0.5140, +0.0110,
+ -0.6460, -1.3452, +0.4370, -1.0515, -0.7801, -0.2640, +0.0359,
+ -0.0097, -0.4043, +0.1002, -0.0268, -0.0773, -0.0390, +0.0679,
+ -0.2875, -0.9561, -0.2837, -0.1344, +0.1141, +0.2607, -0.1805,
+ -0.2482, +0.4783, -0.0732, -0.3817, +0.3229, -0.1179, +0.3825,
+ -0.3490, +0.6231, -0.3663, -0.2762, +0.1450, -0.0651, +0.3529,
+ -0.6646, -0.0485, +0.6340, -0.1721, -0.0388, +0.1370, +0.3559,
+ -0.1751, -0.3544, -0.2360, +0.1969, -0.0265, -0.5621, +0.1465,
+ -0.5286, -0.0378, -0.3572, -0.2107, +0.1881, -0.3776, -0.1373, -0.2395
+ ],
+ [
+ -0.0932, -0.1324, -0.7774, +0.7236, -0.0517, +0.2264, -0.0171,
+ -0.3843, -1.8551, -0.2552, +0.2186, -0.1668, -0.0405, -0.7226,
+ +0.3290, -0.4577, +0.6845, +0.2283, +0.0772, +0.3389, -0.1607,
+ +0.2051, +0.2808, -0.1648, -0.1542, -0.1327, +0.3047, -0.1349,
+ -0.3720, +0.5004, +0.1875, -0.3262, +0.7620, +0.2608, -0.6428,
+ +0.5077, -0.8593, +0.1150, -0.6590, +0.5739, -0.3998, -0.2555,
+ +0.4572, +0.5381, +0.2333, -0.3406, +0.3267, -0.2062, -0.4765,
+ +0.0695, -0.7520, +0.3144, +0.2924, +0.0593, -0.2462, -0.2207,
+ +0.1864, -0.6530, +0.3565, -0.2062, -0.0916, +0.1603, -0.1901, +0.0146
+ ],
+ [
+ +0.5634, +0.0527, -0.4892, +0.2440, -0.1720, +0.2785, -0.4833,
+ +0.1367, -0.1087, -0.1074, -0.2101, +0.2272, -0.2405, +0.2242,
+ +0.4896, -0.5147, +0.1469, +0.2632, -0.2786, -0.5737, -0.2000,
+ -0.3146, +0.1852, -1.6770, -0.0606, -0.6669, -0.6540, +0.3910,
+ +0.1855, +0.2526, -0.2044, +0.2109, -0.5512, -0.2409, +0.1259,
+ +0.5317, -0.5607, -0.0788, +0.0273, -0.1690, +0.1662, +0.0275,
+ -0.4170, -0.7013, -0.0454, +0.4406, -0.5298, -0.3473, +0.0638,
+ -0.3749, +0.2545, +0.5678, +0.5063, +0.3236, -0.7996, +0.3285,
+ -0.1605, +0.6192, +0.1014, +0.1821, -0.5310, -0.5324, +0.1416, -0.3316
+ ],
+ [
+ -1.1046, -0.7047, -0.2575, -0.7403, -0.7298, -0.2453, -0.3595,
+ -0.4102, -0.3522, +0.5069, -0.3525, +0.0370, +0.0301, +0.2036,
+ +0.1020, -0.2437, +0.2750, +0.4183, -0.0769, -0.2143, +0.4041,
+ -0.1546, -0.3924, -0.4053, -0.1305, -1.6502, -0.5113, -0.4471,
+ -1.4570, +0.0472, +0.2965, +0.2012, -1.2503, -0.4947, +0.0608,
+ +0.0305, +0.2824, -0.0230, -0.5519, +0.3479, +0.1785, -0.3687,
+ -0.1119, -0.2599, -0.3071, -0.4963, -0.8701, +0.0014, +0.2138,
+ -0.1607, -0.7962, -0.3856, +0.0298, +0.2767, -0.5021, -0.8125,
+ +0.1187, -0.2955, +0.0602, +0.2604, +0.1913, -0.7938, +0.4153, -0.4320
+ ],
+ [
+ -0.1053, -0.4955, -0.7817, +0.4661, -0.5876, -0.0594, +0.3703,
+ +0.0458, -0.2497, +0.1020, +0.4331, -0.1484, -0.1813, -0.4629,
+ +0.4557, +0.1618, -0.1633, -0.0155, -0.0498, +0.2643, +0.4639,
+ +0.2317, +0.0692, +0.2114, +0.0785, +0.3615, +0.3779, -0.1974,
+ -0.2165, +0.0856, +0.0563, +0.1860, -0.7703, +0.0791, +0.0535,
+ +0.1625, +0.1107, +0.1564, +0.0604, +0.5328, +0.2965, -0.4956,
+ -0.0350, -0.8169, -0.1578, -0.3033, +0.3697, -0.2652, -0.0895,
+ +0.2893, -1.2192, -0.3056, -0.5532, -0.6461, -0.9112, -0.5628,
+ +0.5037, +0.0736, +0.1086, +0.0716, +0.5142, +0.1312, -1.4517, -0.9905
+ ],
+ [
+ -0.9468, -0.7466, -0.6471, -0.1362, -0.8800, +0.5892, +0.5213,
+ -0.6689, +0.2229, -1.6990, -0.1504, -0.1068, +0.0205, +0.2356,
+ +0.5575, -0.4093, -0.0981, -0.9981, +0.0432, -0.6207, -0.0574,
+ -0.1144, -1.5140, -0.3693, -0.1618, +0.3839, -0.1877, -0.2322,
+ +0.0598, +0.2673, +0.3659, -1.0235, +0.0875, +0.3404, -1.0691,
+ -1.6803, -0.2115, -0.6276, -0.5968, -0.7992, +0.0821, -0.6022,
+ -0.0708, +0.2164, +0.5098, -0.1063, -0.2642, +0.3782, +0.3025,
+ -0.7081, +0.1065, -0.5805, -1.1473, -0.4245, +0.3123, +0.2769,
+ +0.4162, -0.4652, -0.7961, +0.0205, +0.1451, -0.4086, -0.1521, -0.2852
+ ],
+ [
+ -0.7144, -0.0732, -0.2513, -0.5200, +0.2989, +1.0393, -0.0999,
+ +0.6432, -0.2806, -0.3070, +0.5141, -0.0163, -0.0070, -0.5330,
+ +0.1894, -0.1748, -0.2329, +0.3600, +0.4255, -0.6582, -1.3598,
+ -0.8585, +0.1014, -0.4106, -0.0970, +0.1253, -0.1873, -0.3545,
+ +0.2180, +0.3920, -0.5099, +0.0616, -0.3497, +0.2023, -0.8214,
+ -0.1101, +0.6518, -0.4036, +0.1847, -1.2271, +0.2813, -1.0571,
+ +0.6299, +0.2067, -0.6461, -0.6766, -1.4846, +0.0878, +0.6149,
+ -0.1618, -0.3680, -0.4017, -0.7612, -0.2911, -3.0760, -0.0799,
+ -0.6366, -0.2699, +0.3534, +0.0080, -1.2127, -0.5772, -0.8138, -0.3230
+ ],
+ [
+ +0.0332, +0.2400, -0.4718, +0.1539, +0.1194, -0.0690, +0.2228,
+ +0.1942, +0.1187, +0.2018, +0.4571, +0.3205, -0.2239, -0.5064,
+ +0.1089, -0.1322, -0.4595, -0.4284, -0.1388, -0.0142, -0.0337,
+ -0.1693, +0.3553, -0.6581, -0.0025, -0.1231, -0.4583, +0.2712,
+ +0.1195, +0.1075, -0.1298, +0.1162, +0.2405, +0.1785, -0.0615,
+ -0.0789, -0.5330, -0.1870, -0.0264, -0.0452, -0.1919, -0.0952,
+ +0.3738, -0.2498, -0.2696, +0.4355, +0.1340, -0.4136, -0.2625,
+ +0.1043, +0.2227, -0.2964, +0.0329, -0.0459, +0.3446, -0.3150,
+ -0.0285, -0.1389, -0.0620, -0.3741, -0.0209, +0.0344, -0.4535, +0.3100
+ ],
+ [
+ -0.3163, -0.4723, -0.0250, -0.0141, +0.4464, -0.1986, -0.6116,
+ -0.0829, -0.1127, -0.1741, +0.3716, -0.5599, -0.0702, +0.4810,
+ +0.2091, -0.0865, +0.1534, -0.2891, -0.3830, -0.1924, -0.0542,
+ -0.0241, -0.1366, +0.0385, -0.1856, +0.5328, -0.4052, -0.5755,
+ -0.2612, +0.0013, -0.0076, -0.2590, +0.3901, -0.4172, -0.1419,
+ +0.0362, +0.1212, -0.3479, -0.1679, -0.0086, -0.1725, +0.0736,
+ +0.0087, +0.1469, +0.0006, +0.1689, -0.3634, -0.1821, +0.3467,
+ -0.2033, -0.1277, +0.1919, +0.1260, -0.1244, -0.2993, -0.0904,
+ -0.1687, +0.3754, +0.2097, -0.5879, -0.0770, +0.0359, +0.2110, -0.1712
+ ],
+ [
+ -0.3661, -0.2717, +0.1113, +0.2665, -0.0972, -0.5824, +0.2890,
+ -0.1308, -0.0929, -0.0011, +0.2813, -0.1148, +0.0119, -0.0529,
+ -0.0646, -1.4966, +0.4980, +0.0945, +0.1389, -0.4049, -0.2027,
+ -0.0673, +0.1332, +0.7332, +0.1248, -0.0770, +0.6605, -0.8541,
+ -0.0439, -0.1973, -0.4820, -0.0423, -0.2129, -0.0853, -0.6524,
+ -0.0321, -0.0372, +0.3873, +0.0421, -0.4772, -0.5575, -0.5932,
+ +0.1917, +0.2110, +0.1637, -0.3029, -0.2104, -0.0282, -0.7481,
+ +0.0828, +0.0379, +0.2106, -0.0853, -0.2235, -0.1073, +0.5198,
+ -0.2518, -1.3097, -0.3292, +0.1675, +0.0255, -0.1867, -0.6809, -0.4100
+ ],
+ [
+ +0.3530, -0.2818, -0.8931, -0.6490, -0.0029, -0.0079, +0.6413,
+ -0.4325, -0.2703, -0.5681, +0.2736, -0.2060, -0.2772, +0.0567,
+ -0.1602, +0.0456, -0.2931, +0.1224, +0.0146, +0.6612, +0.0332,
+ -0.2383, -0.3551, -0.4960, +0.0080, +0.0682, +0.2126, +0.0375,
+ -0.1039, +0.2998, -0.4285, +0.1969, +0.2692, +0.2157, +0.1096,
+ +0.1654, -0.6327, +0.4191, -1.3065, +0.1224, +0.5497, +0.2013,
+ +0.1524, +0.0798, -0.0325, -0.2407, -0.2019, -0.7491, -0.3803,
+ -0.1791, -1.0558, +0.3998, -0.2989, +0.1077, -0.4348, +0.0519,
+ -0.2329, -0.1133, +0.0053, +0.2635, -0.4516, -0.0578, -0.3698, -0.1016
+ ],
+ [
+ +0.6371, -0.1203, +0.0076, -0.8131, -0.0454, -0.8196, -0.9530,
+ +0.0536, -0.0904, -0.6379, +0.0735, +0.4852, -0.0525, +0.5745,
+ +0.1264, -0.3008, -0.7915, -0.0787, +0.1571, +0.1630, -0.3364,
+ -0.1717, +0.5771, -0.6814, -0.2517, -0.3498, -0.3729, -0.4342,
+ -0.5237, -0.6116, -0.1791, -0.0410, +0.0610, -0.2450, -0.8010,
+ +0.5793, -0.5352, +0.1076, -0.1877, -0.1534, +0.3871, +0.0020,
+ +0.1915, -0.3309, +0.0250, -0.5323, -1.2959, -0.9239, +0.2443,
+ +0.0734, -0.2273, +0.0469, +0.2829, +0.2647, -0.5502, -0.4885,
+ -1.0957, +0.1740, +0.1821, -0.6767, -0.2402, -0.3386, +0.1601, +0.3032
+ ],
+ [
+ -0.9192, +0.1419, -0.0422, -0.8396, -1.4337, -0.4047, +0.4867,
+ -0.1729, +0.0987, +0.2949, -0.1027, +0.1376, +0.0276, -0.3454,
+ +0.1000, +0.1415, +0.1384, -0.4045, -0.3747, -0.0164, +0.2935,
+ -0.1466, -0.1396, +0.0236, -0.0539, +0.1790, -0.2958, +0.2800,
+ -0.6574, +0.0546, -0.3582, -1.0463, +0.1917, +0.1586, -1.2121,
+ -0.7189, -0.4901, +0.6121, -0.2627, +0.1610, -0.0404, +0.1463,
+ -0.2310, -0.3012, +0.1397, +0.8620, -0.0025, -0.9045, -0.4128,
+ -0.1460, +0.3187, -2.0256, -0.4127, +0.2568, +0.7488, -0.0511,
+ -0.1044, +0.0262, +0.2524, +0.0832, +0.2267, +0.2748, -0.4902, +0.3688
+ ],
+ [
+ +0.1430, +0.0566, +0.6816, -0.3206, -1.4961, +0.1194, +0.6902,
+ +0.0898, -0.2031, +0.1232, +0.0439, +0.1807, -0.0578, -0.0846,
+ -0.1607, +0.0681, -0.0610, -0.5653, +0.0072, -0.5820, -0.0853,
+ -0.3235, -0.4972, +0.0032, -0.2038, -0.2900, -0.1359, +0.0540,
+ -0.0303, -0.6849, -0.9005, -0.1212, +0.0606, +0.1388, -0.4231,
+ -1.0739, +0.1928, +0.0319, +0.0958, +0.0125, -0.1298, -0.2588,
+ +0.1088, -0.5559, -0.3151, +0.0548, +0.3297, -0.5271, -0.7640,
+ -0.0341, +0.1411, -0.4929, -0.1423, -0.0565, +0.2080, +0.0836,
+ -0.3868, -0.1338, +0.1035, -1.4365, +0.1114, -0.2450, -0.7043, +0.3546
+ ],
+ [
+ +0.2535, -0.0369, +0.4675, +0.1631, -1.1942, -0.2561, -0.0358,
+ -1.2841, -0.7228, -0.7758, -1.0097, -0.9734, +0.0736, +0.0120,
+ +0.2161, -0.4861, +0.1287, +0.5726, -0.1021, +0.0230, +0.2227,
+ +0.0172, -0.3978, +0.2238, -0.0154, -0.0980, +0.2639, +0.4450,
+ -0.1750, +0.1290, +0.3401, +0.0108, +0.3784, -0.5999, +0.7053,
+ -0.2275, -0.1755, -0.8104, +0.1894, +0.4153, +0.3092, +0.1734,
+ -0.3326, -0.1536, -0.1178, -0.6143, -0.1548, -0.2079, +0.0667,
+ +0.1950, -0.4622, -0.4300, +0.4255, -0.0521, -1.0740, -0.2555,
+ -0.3026, -1.4444, -0.7026, +0.3971, +0.2106, +0.2773, -0.1475, +0.1711
+ ],
+ [
+ -0.7103, -0.2924, -0.1677, +0.5409, -0.8698, +0.1309, +0.1154,
+ -0.6516, -0.9558, -0.9140, -0.0917, +0.0043, -0.1487, +0.0357,
+ +0.3957, -0.1346, +0.6243, +0.0267, -0.1561, -0.9322, +0.5103,
+ -0.2402, +0.2321, -1.1931, -0.1977, +0.0085, -1.2352, +0.2785,
+ -0.5084, +0.3258, +0.3364, +0.2619, -0.0041, -0.1554, -0.0281,
+ -0.4433, +0.2035, -0.0982, -0.0065, +0.4423, +0.2874, -0.4494,
+ -0.0345, -0.3386, -0.4039, -0.8893, -0.1554, -0.2474, -0.1889,
+ -0.1272, +0.2077, -1.2152, +0.4811, +0.1376, +0.1043, +0.3282,
+ +0.0409, +0.0068, +0.1769, +0.1182, +0.4116, -0.3562, +0.0513, -0.5300
+ ],
+ [
+ -0.1572, -1.5188, -1.5678, -0.4130, -0.4267, -0.1431, +0.1554,
+ -0.3178, -0.7728, +0.2314, -0.2010, +0.2888, +0.1788, -0.1780,
+ +0.0944, -0.9144, +0.5334, +0.2888, -0.2076, +0.1253, +0.2449,
+ +0.1610, -0.2281, +0.0742, -0.0978, +0.2734, -0.3029, -0.2320,
+ +0.1220, +0.0550, +0.1580, -0.1043, -0.2656, -0.0400, +0.2219,
+ -0.6095, +0.1252, -0.1372, +0.3713, -0.5300, +0.1172, +0.2025,
+ -0.4247, +0.0746, +0.1929, +0.0514, +0.2209, -0.5462, -0.2288,
+ -0.7486, +0.2197, +0.1359, -0.7125, -0.8333, -0.5579, -0.8019,
+ -0.5522, -0.2105, +0.1643, -1.0014, -0.4503, -0.6657, +0.4036, -0.0555
+ ],
+ [
+ -0.0590, -0.3719, -0.5114, +0.2530, -0.7208, -0.0563, +0.3854,
+ +0.3026, +0.0735, +0.3427, +0.6002, -0.1396, -0.1402, +0.1080,
+ +0.1864, +0.3067, -1.0581, -1.9660, -0.2471, -0.0337, +0.0124,
+ -0.2047, -0.6474, -0.8498, +0.0491, +0.0070, -0.1226, +0.0656,
+ -0.2951, +0.0360, -0.9327, -0.2177, -1.0216, +0.6137, -0.5219,
+ -0.3685, -0.0321, -0.2387, +0.6478, -0.0755, -0.0629, -0.7876,
+ +0.2509, -0.3656, -0.1480, +0.1127, +0.5233, -1.2403, +0.1726,
+ +0.3162, +0.3171, -0.6025, -0.6811, -0.9313, -0.1579, -0.1299,
+ +0.1423, -0.1796, +0.2760, -0.4841, +0.1697, -0.1206, -1.3476, -0.4628
+ ],
+ [
+ -0.3120, -0.7815, -0.7293, +0.2830, -1.2078, +0.3774, +0.5226,
+ -0.7750, -0.7630, +0.6087, +0.6374, +0.2126, -0.1801, -0.1649,
+ -0.0703, +0.0150, -0.5099, -0.8238, +0.2890, -0.5040, +0.0895,
+ -0.2675, -1.6283, -0.6663, +0.1520, +0.1787, -0.1078, +0.0191,
+ +0.2750, -0.6022, -0.2075, +0.1815, -0.0741, +0.4324, -1.1463,
+ -0.3964, +0.4130, -0.8703, -0.1329, -0.4860, -0.3910, +0.1145,
+ +0.1338, -0.1027, +0.2230, +0.2237, +0.0151, +0.3517, -0.5960,
+ -0.1026, +0.0241, +0.0157, -0.3517, -0.0960, +0.2909, +0.2758,
+ -0.2046, -0.0833, -0.1670, -0.4800, +0.3463, -0.9654, -0.4277, -0.4589
+ ],
+ [
+ -0.1478, +0.1582, -0.2973, -0.1952, -0.1098, +0.5831, +0.6361,
+ +0.3629, -0.1146, -0.6157, +0.5632, +0.4363, +0.0612, -0.9039,
+ +0.1119, -0.5786, -0.5540, +0.0398, +0.1752, -0.5577, -0.6667,
+ -0.2905, +0.2213, -0.0194, +0.3635, -0.6965, +0.0050, +0.0740,
+ +0.1895, +0.1548, -0.5477, +0.4813, -0.6568, +0.7340, -1.0991,
+ +0.0799, +0.1582, +0.0278, +0.5434, -0.1960, +0.4060, -0.6551,
+ -0.0725, -0.4377, -0.7184, +0.1424, -0.8283, +0.7254, +0.4389,
+ +0.5734, +0.2364, -0.5897, -0.0238, -0.0007, +0.3947, -0.0760,
+ +0.1847, +0.1770, +0.0928, +0.3543, -0.4835, -0.3019, -0.9959, +0.0583
+ ],
+ [
+ +0.1443, +0.2220, +0.1527, -0.3340, +0.2000, -0.1948, -0.2900,
+ +0.3642, +0.1534, -0.0776, +0.1768, -0.1703, -0.2562, -0.2758,
+ -0.4396, +0.0234, -0.1917, +0.1102, -0.2345, -0.1229, +0.0281,
+ +0.0845, +0.1131, +0.4417, +0.0569, -0.3473, +0.0394, -0.0056,
+ +0.0946, +0.0011, -0.7753, +0.1805, -0.1408, +0.1301, +0.0846,
+ -0.4318, -0.3021, +0.0477, +0.0908, +0.0013, -0.3767, +0.2696,
+ +0.4063, -0.3381, -0.7599, +0.1141, +0.3743, -1.1590, +0.0345,
+ +0.2245, +0.2459, -0.2822, -0.4002, -0.7271, -0.1023, -0.3171,
+ -0.1637, +0.2897, +0.1085, -0.4487, -0.0477, +0.1013, +0.0479, +0.0018
+ ],
+ [
+ -1.0487, -0.2101, +0.2740, +0.0018, -0.1096, -0.8838, -0.4168,
+ -0.3155, -0.2515, -0.1041, -0.0137, +0.3740, -0.1076, +0.2306,
+ -0.4726, +0.0436, -0.3551, +0.3825, -0.2449, +0.4380, -0.7459,
+ +0.2044, -0.5208, -0.7803, -0.0959, -0.2527, +0.0630, -0.9097,
+ -0.0458, -1.0599, +0.3440, -0.3823, +0.0603, -0.7298, +0.3327,
+ +0.3867, -0.2603, +0.0369, +0.6102, -0.0971, -0.0400, -0.2093,
+ -0.3939, +0.2720, +0.4138, +0.0643, -1.0037, -0.2460, +0.1148,
+ -0.3138, -0.1753, -0.0530, -0.8875, +0.3475, -0.3792, -0.8626,
+ -0.3554, -0.2610, +0.0977, -0.1185, -0.3172, -0.0645, +0.0849, +0.3102
+ ],
+ [
+ +0.6196, -0.2248, +0.3701, +0.3871, +0.1780, -0.8845, -1.1825,
+ -0.2375, -0.3429, +0.1191, +0.4072, -0.4555, -0.1496, +0.1067,
+ +0.0234, -0.8369, -0.0937, -0.0319, -0.2486, +0.0657, -0.6954,
+ +0.2187, +0.3412, +0.2551, -0.3422, -0.0815, -0.2930, -0.2226,
+ -1.1675, +0.5878, -0.5601, +0.1259, -0.0683, -0.2040, -0.0079,
+ -0.1074, -0.1578, -0.1415, -0.1203, -0.9654, +0.7452, +0.0246,
+ -0.3484, -0.0277, +0.1140, +0.1730, -1.0210, -0.5052, +0.3313,
+ -0.2379, +0.1376, +0.1366, +0.3220, +0.2231, -0.7424, -0.1786,
+ -1.4978, -1.3279, -0.3878, -0.0794, -1.7559, -0.0926, +0.2841, +0.0046
+ ],
+ [
+ -0.0346, +0.2532, +0.3598, -0.0466, +0.0500, +0.0986, -0.4646,
+ -0.2297, -0.4361, -1.7196, +0.2609, -0.4030, -0.2188, -0.2671,
+ -0.1898, +0.1210, +0.6077, +0.1553, +0.0702, +0.1467, -0.2473,
+ +0.1862, +0.3394, +0.2467, -0.4418, -0.1372, +0.5745, -0.3004,
+ +0.1039, +0.1269, -0.4942, +0.1940, +0.5131, -0.2525, -0.7989,
+ +0.2016, +0.3945, -0.1058, -0.6304, -0.6872, -0.1522, +0.6897,
+ -0.0695, +0.1169, -0.0974, +0.0709, -0.2866, +0.2668, -0.0795,
+ +0.3041, -0.1889, +0.1018, +0.2852, +0.4602, -0.1846, +0.5833,
+ -0.1721, +0.6602, -0.6977, -0.2847, -0.0483, +0.0897, -0.0469, +0.1863
+ ],
+ [
+ -0.0781, -0.3706, +0.2251, +0.2849, +0.0941, -0.2094, +0.6678,
+ -0.0101, +0.0424, -0.0293, +0.2295, -0.1194, +0.0675, +0.0213,
+ -0.1025, +0.3390, +0.1805, -0.2866, +0.2053, +0.2851, +0.4197,
+ -0.1941, -0.4910, +0.2821, -0.2832, -0.1295, -0.0805, +0.1562,
+ +0.2949, -0.3321, -0.7247, -0.4742, +0.3879, +0.2745, -0.3844,
+ -0.6716, -0.3245, +0.4906, -0.2705, -0.2982, -0.1698, -0.7898,
+ +0.1142, -0.1942, -0.3603, -0.1740, +0.3400, -0.0506, -0.3486,
+ -0.2486, -0.0503, -0.3264, -0.5077, -0.0445, +0.1496, +0.2111,
+ -0.6167, -0.3732, -0.9418, -0.7983, +0.0077, -0.2045, -0.7608, +0.1405
+ ],
+ [
+ +0.2049, +0.1535, +0.2128, -0.4164, -0.2544, -0.6106, -0.7504,
+ -0.3578, -0.2596, -1.0701, +0.0292, -0.1886, -0.1032, -0.5208,
+ +0.0134, -0.3110, -0.7516, +0.4388, +0.0340, +0.0624, +0.0834,
+ -0.0516, -0.1133, -0.7225, -0.2224, -0.5351, -0.0026, -0.6803,
+ -0.0265, -0.1342, -0.2246, +0.2535, -0.5135, -0.4462, +0.3514,
+ -0.0025, +0.1148, -0.5111, -0.2767, -0.1291, +0.2889, +0.1646,
+ +0.4116, -0.5003, -0.1414, +0.4581, -0.0032, +0.2815, -0.1550,
+ -0.1487, -0.2589, -0.7931, -1.5351, +0.6082, -0.8509, -0.5817,
+ +0.3463, +0.1935, +0.4886, +0.3674, -0.1345, -0.5708, -0.5943, -1.0342
+ ],
+ [
+ -0.4535, -0.7263, +0.1911, -0.1976, -0.0240, -0.2905, -0.3329,
+ -0.2344, +0.1119, -0.7598, +0.2671, -0.0547, +0.0231, -0.1666,
+ -0.1475, -0.9600, -0.2575, -0.5557, -0.0586, +0.1305, -0.7248,
+ -0.1328, -0.0749, -0.1792, -0.0993, +0.0632, +0.0370, -0.0350,
+ -0.2100, -1.0003, -0.2526, +0.4889, -0.0268, -1.0811, -1.0744,
+ -0.2632, +0.6099, +0.1728, -0.3989, -0.4078, +0.4547, -2.1630,
+ +0.0652, -0.1967, +0.0211, -0.7390, -1.2135, -0.2196, -0.0140,
+ -0.4225, -0.0909, +0.3659, +0.2051, +0.1075, -0.2806, -0.2124,
+ -0.0317, +0.0040, -1.0535, -0.0977, -0.0551, -0.4167, -0.4222, -0.5449
+ ],
+ [
+ -0.5821, +0.1573, +0.3883, -0.0208, +0.0267, -0.1548, +0.0036,
+ +0.0238, +0.2573, -0.2390, +0.1001, -0.4440, +0.1714, +0.4488,
+ -0.0916, -0.0133, +0.0881, +0.1937, +0.0243, +0.0557, -0.0183,
+ -0.3184, -0.0971, +0.1885, -0.1141, -0.0808, +0.2792, +0.3806,
+ +0.1167, -0.0970, -1.1862, -0.3819, -0.0736, -0.2230, -0.2072,
+ -0.4767, +0.3344, -0.4753, +0.4085, -0.9508, -1.3361, -0.5341,
+ -0.2721, -0.2227, -0.2407, -0.2488, +0.0815, +0.0050, -0.0188,
+ +0.1103, +0.3057, -0.1838, +0.1879, +0.0258, -0.0092, +0.2777,
+ -2.1384, -0.0154, -0.0746, +0.1013, -0.0875, -0.4639, -0.1884, +0.3613
+ ],
+ [
+ -0.3665, -0.1782, +0.0419, -0.2690, -0.3408, +0.7867, +0.3313,
+ -0.9157, +0.4388, -0.4855, -1.2508, -0.4405, -0.2233, +0.0522,
+ +0.4611, -0.3997, -0.5933, -1.3610, -0.3253, -0.1574, +0.0802,
+ -0.4449, -0.6778, -0.3988, -0.2578, -0.7707, -0.7587, -0.0789,
+ -0.0164, +1.0809, +0.1280, -0.4027, -1.1598, +0.7488, -0.6504,
+ +0.0912, +0.5017, -0.1733, -0.5198, -0.7894, -0.0064, -1.4117,
+ +0.1238, -1.8378, -0.0063, +0.7132, -0.0657, -0.0301, +1.1850,
+ -0.3432, -0.5329, +0.2786, -0.8299, -0.5956, +0.0208, -0.4721,
+ +0.2628, -0.3157, +0.1742, -0.8047, +0.0856, +0.2113, -0.6971, -0.1566
+ ],
+ [
+ -0.6693, -0.1809, +0.0884, -0.1358, +0.5172, -0.0687, -0.0120,
+ -0.3826, -0.5306, -0.0103, +0.8560, -0.3482, +0.0860, +0.3675,
+ -0.5334, -0.0405, +0.2357, -0.2945, -0.4034, +0.3049, -0.6580,
+ -0.2272, -0.5667, -0.0805, -0.0008, +0.3024, -0.2402, -0.5567,
+ +0.2349, -0.4490, -0.3248, +0.3113, -0.0458, +0.5295, -0.8893,
+ -0.1700, +0.1197, -0.0317, +0.2407, -0.3567, -0.3077, -0.4958,
+ +0.3886, +0.4175, -0.0700, -0.4049, +0.3392, -0.1947, +0.7443,
+ +0.2133, +0.3215, +0.0441, -0.5935, -0.3116, -0.0350, -0.7650,
+ -0.6026, -0.3508, -0.1284, -0.9857, -0.1828, -0.2976, -0.2231, -1.0016
+ ],
+ [
+ +0.0507, -0.0567, +0.2445, -0.0756, -0.0082, +0.4970, -0.0516,
+ -0.0301, +0.3676, -0.1720, +0.0047, -0.3551, -0.0340, -0.0532,
+ -0.4424, -0.3569, -0.0102, -0.1321, +0.1088, -0.2266, -0.8376,
+ -0.6879, +0.5277, +0.1749, +0.0183, -1.0760, -0.5535, +0.1199,
+ +0.0335, -0.4466, +0.0450, -0.9575, -0.7582, +0.5908, -0.6280,
+ +0.5010, -0.0937, +0.4709, +0.1345, -0.1088, -0.4050, -0.9498,
+ +0.1079, -0.0437, -0.1768, -0.8175, +0.3442, -0.0402, -1.4693,
+ +0.2791, +0.1296, -0.0762, +0.0142, -0.9085, +0.3446, +0.1278,
+ -0.0685, -0.5707, +0.4476, +0.0823, -0.4022, -0.5325, -0.5841, -0.2564
+ ],
+ [
+ +0.0898, -1.1540, -0.9679, -0.3278, +0.1902, -0.3525, +0.0045,
+ -0.2419, -0.9443, +0.2821, -0.4016, -0.3287, -0.0096, -0.2795,
+ +0.3097, -0.2414, +0.1993, -0.0236, -0.2561, -0.1521, +0.1322,
+ +0.0188, +0.2566, -0.7166, -0.0330, +0.1491, -0.1133, +0.1535,
+ -0.2132, -0.2450, -0.3134, -0.0497, -0.4828, -0.0163, +0.0998,
+ -0.0427, +0.0128, +0.4167, -0.4010, +0.3123, +0.1781, -0.0243,
+ -0.1447, -0.4638, -0.6196, +0.1720, -0.1308, -0.7977, -0.4340,
+ -0.3038, -0.9074, -0.1848, +0.1264, +0.0249, -0.5808, -0.0785,
+ -0.1180, -0.6689, +0.4223, -0.0547, +0.3043, +0.1254, +0.2954, -0.2502
+ ],
+ [
+ +0.0870, +0.0780, -0.0389, +0.1600, -0.0364, +0.2506, +0.0564,
+ +0.2378, +0.0033, -0.1340, -0.1532, +0.3440, -0.4366, -0.1984,
+ +0.0098, +0.1903, +0.0752, -0.1213, +0.0378, -0.1293, +0.0029,
+ -0.1710, +0.1367, -0.0665, -0.0351, -0.1341, -0.1123, -0.2100,
+ -0.0160, -0.0597, -0.2886, +0.1219, -0.0732, +0.2243, -0.3820,
+ -0.1373, -0.0118, +0.0217, +0.2059, +0.0855, -0.0949, -0.0514,
+ -0.0669, -0.3338, -0.4548, -0.0133, +0.0292, -0.0179, +0.1236,
+ +0.2291, +0.2861, -0.2900, -0.0856, -0.2934, +0.0034, -0.3797,
+ +0.0143, +0.0729, +0.0875, +0.2393, -0.0385, -0.1214, +0.0479, -0.0652
+ ],
+ [
+ -0.7501, -1.1375, -0.2978, -0.8633, -0.8919, +0.2189, -0.5857,
+ -0.2409, +0.0604, -0.0567, -0.1097, +0.2126, +0.0844, -0.3906,
+ +0.3503, -0.9469, +0.0383, -0.3880, +0.1532, -0.7949, +0.2010,
+ -0.3122, -0.3812, -1.0744, -0.0195, -0.4764, +0.2610, -0.7452,
+ +0.1366, +0.2796, +0.2770, -0.2790, -0.7372, -0.2902, -0.7949,
+ -0.1160, -0.1794, -0.6606, -0.0722, -0.1698, +0.1217, +0.2441,
+ +0.2072, -0.3946, +0.1858, -0.1417, -0.9906, -0.2096, -0.0386,
+ -0.3452, +0.3401, -0.3946, -0.0491, +0.0953, -0.5440, -0.9668,
+ -1.4922, +0.0952, +0.2255, -0.0070, -0.0929, -0.6225, +0.2984, -0.1608
+ ],
+ [
+ +0.0875, -0.8502, +0.2431, -1.4256, -0.0134, -0.5211, +0.1531,
+ -0.3139, -0.2330, -0.0786, -0.0809, -0.1122, -0.1306, -0.0140,
+ +0.4723, -0.6809, -1.0225, +0.1196, +0.1491, -0.2224, -1.9714,
+ -1.6552, -0.0284, -0.6446, +0.1878, -0.0111, +0.2549, -0.5032,
+ +0.2373, -0.2167, +0.0885, -0.0815, -0.8509, -0.9426, -0.4842,
+ +0.2617, +0.0947, +0.8169, -0.0459, +0.1221, -0.0595, -0.5754,
+ -0.5843, -1.3281, +0.1531, -1.3252, -0.7069, -0.5561, +0.1954,
+ +0.0952, -0.5631, +0.2066, +0.7464, +0.1565, -1.3679, -0.5306,
+ +0.1436, -0.5271, -0.1679, -0.0539, +0.5787, -0.2023, +0.3189, -0.4968
+ ],
+ [
+ +0.0315, -1.1600, -0.1894, +0.1841, -0.0069, -0.9793, -0.0278,
+ -0.9642, -1.0357, +0.5406, -0.1473, +0.2056, -0.3358, +0.3904,
+ -0.0970, -1.3872, +0.2364, +0.2908, +0.0140, -0.1797, -0.0895,
+ +0.1147, +0.0184, +0.2090, -0.2029, -0.0183, +0.3583, -0.6774,
+ -0.3236, +0.4919, +0.1323, -0.3519, +0.2735, -0.4859, +0.1274,
+ +0.0592, +0.0293, -0.0612, -0.2484, +0.0962, -0.4288, +0.5136,
+ -0.6259, +0.2224, +0.2347, +0.0524, -0.0633, +0.0179, +0.0616,
+ -0.9062, -0.1752, -0.0501, +0.3795, +0.4146, +0.0351, +0.3203,
+ -0.0841, -1.0873, -1.3012, -0.3519, +0.3106, +0.3838, +0.1764, -0.1131
+ ],
+ [
+ -0.0067, +0.0395, -0.7516, -0.2958, -0.1750, +0.4141, -0.3325,
+ -0.3768, -0.4620, +0.8233, +0.3492, -0.0237, +0.0106, -0.8323,
+ +0.3937, -0.1977, -0.4075, -0.2006, -0.0474, +0.3061, +0.0789,
+ -0.2584, -0.0647, +0.1114, +0.0884, +0.4178, -0.6012, -0.1629,
+ +0.4286, +0.4013, -0.9800, -0.6920, +0.3876, +0.7810, -0.7333,
+ -0.0620, -0.2162, -0.4436, -0.1308, +0.0799, -0.0925, -1.3182,
+ +0.3494, -0.7913, +0.1979, +0.5827, +0.2238, +0.0280, +0.0497,
+ -0.0354, -0.0631, +0.8220, -0.1120, -0.2673, +0.1897, -0.6081,
+ -0.1298, -0.7712, -0.2133, -0.6315, -0.3532, -0.9268, +0.2826, +0.2492
+ ],
+ [
+ -0.6092, -0.1699, +0.0756, -1.0743, +0.7791, -0.0013, +0.0261,
+ +0.0341, +0.0039, -1.3614, +0.0474, +0.1043, -0.1149, -0.3031,
+ -0.1387, -0.2534, -0.1865, -0.0783, +0.0465, +0.1722, +0.0714,
+ -0.3566, -0.3526, -0.3374, -0.2516, +0.0578, -1.6820, +0.6733,
+ +0.1903, +0.3942, +0.0378, -0.0427, -0.0685, +0.2141, -0.7520,
+ -0.5861, -0.1980, -0.8542, -0.2299, -0.4345, -0.1855, -0.1432,
+ +0.3582, -0.4741, -0.5136, +0.3023, -0.0360, -0.0623, +0.1555,
+ -0.1655, +0.2128, -0.4508, -1.2209, -0.0260, +0.0659, -1.1528,
+ +0.2362, -0.5791, -0.2722, -0.1899, -0.1704, +0.0203, -0.7536, +0.2306
+ ],
+ [
+ -0.1456, +0.4228, -0.2169, -0.1864, +0.2956, +0.0975, -0.4902,
+ -0.4168, -0.0061, -0.0129, +0.5856, +0.0718, -0.1802, -0.3765,
+ +0.3940, -0.0377, -0.1783, +0.1068, +0.1506, +0.1025, -0.4088,
+ +0.1379, +0.4524, -0.2770, +0.0499, +0.0828, +0.0832, +0.1792,
+ -0.0652, +0.3557, +0.1142, +0.1000, +0.5156, -0.0644, -0.2629,
+ -0.4445, +0.2076, +0.1216, +0.3907, +0.0722, -0.0435, -0.1319,
+ +0.2939, +0.1871, -0.1707, -0.1241, +0.0260, -0.0176, +0.7158,
+ +0.0326, +0.2360, -0.0155, -0.2790, -0.0850, -0.0872, +0.0258,
+ +0.1475, -0.2429, -0.3992, -0.5970, -0.0884, +0.0104, +0.2510, -0.3747
+ ],
+ [
+ -0.1019, +0.0217, +0.0604, +0.2556, +0.0670, -0.2470, -0.0896,
+ +0.0972, -0.5061, -0.0539, -0.1494, -0.6850, -0.1314, +0.4489,
+ +0.3238, -0.1830, -0.3250, -0.4818, +0.1131, +0.0809, -0.1849,
+ +0.0768, -0.4203, -0.1073, +0.0289, +0.0777, -0.2676, -0.1635,
+ +0.2819, -1.1156, +0.4612, -0.5983, +0.2212, -0.2626, -0.3611,
+ -0.8076, +0.0604, +0.1751, -0.1189, -0.8877, +0.1995, -0.5779,
+ +0.1674, +0.1556, -0.4025, -0.7868, -0.6574, -0.0562, -0.3712,
+ -0.0835, +0.2261, -0.0039, -0.0864, +0.1381, -0.2375, -0.1138,
+ +0.0788, -0.7128, -2.4133, +0.2474, -0.5965, +0.0887, -0.3717, +0.1583
+ ],
+ [
+ -0.0173, -0.8841, -0.1036, -0.4535, -0.0171, -0.5824, -0.0683,
+ -0.1105, -0.6359, +0.0860, -0.4490, +0.1697, -0.1639, +0.2569,
+ +0.2831, +0.2610, -0.6809, -0.4909, -0.5067, -0.2111, +0.0006,
+ -0.9312, -0.1564, -0.0030, -0.4018, -1.0880, -0.2422, -0.5496,
+ +0.4572, -0.2074, +0.5928, -0.6699, +0.2007, -0.1501, +0.6496,
+ +0.0006, -0.8182, +0.1627, -0.9395, -0.1071, -0.1078, +0.5001,
+ -0.9152, -0.0298, +0.2665, -0.2468, +0.3327, +0.1171, +0.2442,
+ -0.4903, -0.3593, +0.0516, -0.2479, +0.0401, +0.2455, +0.1927,
+ +0.4553, -0.4156, +0.4963, -0.4824, -0.7662, +0.1025, -0.1231, -0.0549
+ ],
+ [
+ -0.5653, -0.0579, +0.0711, +0.1978, +0.1483, -0.2487, +0.5816,
+ -0.2505, -1.0865, -0.3124, +0.4662, +0.3429, +0.1187, +0.3957,
+ -0.3051, -0.2266, -0.5454, -0.4433, +0.1236, -0.2226, +0.1168,
+ -0.1802, -0.2434, -1.0033, -0.3189, +0.1394, -0.7433, +0.5946,
+ +0.1073, -0.4106, -0.5485, -0.5361, +0.3073, +0.3227, -0.6396,
+ -0.2144, +0.3187, -1.2617, +0.1526, -0.4829, +0.1673, -0.4504,
+ +0.3942, -0.6261, +0.1535, +0.1946, -0.2928, -1.2917, -0.4011,
+ +0.0209, -0.2192, +0.1189, -0.2842, -0.3277, -0.0050, +0.1858,
+ -0.7773, -0.1619, -0.2147, -0.6281, +0.3831, -0.8085, -0.6315, +0.4716
+ ],
+ [
+ -0.8026, -0.3107, +0.0903, +0.0076, +0.4653, +0.2245, +0.1581,
+ +0.3757, +0.3310, -1.2516, -0.1040, -0.6431, +0.0373, +0.0716,
+ +0.1643, -0.6158, -0.0895, +0.2540, -0.1583, -0.0699, +0.1837,
+ +0.4705, -0.9086, -0.0468, -0.2022, +0.2916, -0.3869, +0.1620,
+ -0.2646, -0.1511, -0.2067, -0.3882, -0.6044, -0.1775, -0.8657,
+ +0.2309, +0.3567, +0.0654, +0.5363, +0.0686, -0.0198, -0.9192,
+ -0.1272, +0.5987, -0.0621, -0.3943, -0.0519, -0.5483, +0.0777,
+ -0.5409, -0.0296, +0.0010, +0.2560, -0.1014, -0.8840, -0.4932,
+ -0.2339, -1.0472, -0.4789, -0.2379, -0.6807, -0.0958, +0.2527, -0.5875
+ ],
+ [
+ +0.0894, +0.2394, +0.4565, +0.5095, -0.9334, -1.2892, -0.8885,
+ +0.0167, +1.0713, -0.3041, -0.7280, +0.2223, -0.5221, -0.0032,
+ -0.0743, +0.1534, +0.5751, -0.1298, -0.1282, -0.4674, +0.5752,
+ +0.2239, +0.4114, +0.3252, -0.1642, +0.2532, +0.3494, -0.8035,
+ -0.2348, +0.3177, -0.5218, +0.0481, -0.3052, -0.9177, +0.1627,
+ +0.6603, -0.7468, +0.0274, +0.0626, +0.0355, -0.2757, +0.2697,
+ +0.4732, -0.2061, -0.0190, +0.5470, -0.5898, -0.8168, -0.0884,
+ -0.4522, -0.1064, -0.8207, +0.2726, +0.1109, -0.2514, +0.1580,
+ +0.6825, +0.7124, +0.8108, +0.2258, -0.1274, +0.2130, -0.3830, -0.9575
+ ],
+ [
+ +0.0671, +0.2013, -0.4460, -1.0518, -0.0167, +0.1024, +0.0547,
+ +0.3296, +0.0516, +0.0503, +0.1956, -0.0536, +0.0108, -0.2160,
+ +0.1852, -0.0177, -0.4770, -0.2327, -0.2887, +0.2862, -0.0357,
+ +0.0026, -0.6428, -0.5677, -0.0354, -0.0304, -0.1272, +0.1630,
+ -0.1319, -0.1122, +0.3381, +0.0000, -1.0265, +0.1319, -0.2374,
+ -0.1598, -0.0059, +0.1722, +0.2300, +0.1748, -0.0167, -0.0891,
+ +0.0350, -0.4563, -0.5325, +0.0078, -0.2475, +0.1184, +0.0133,
+ +0.2512, +0.3639, -1.5981, -0.5117, -0.2703, +0.0222, -0.5620,
+ -0.1466, -0.1626, -0.3288, -0.0070, +0.0508, -0.3687, -0.4245, -0.2751
+ ]])
-weights_final_w = np.array([
-[ -0.6826, +0.0812, +0.5225],
-[ -0.2533, +0.7043, +0.6677],
-[ +0.0684, +0.6807, +0.4726],
-[ +0.4605, +0.3736, -0.3187],
-[ +0.4913, +0.0049, +0.4186],
-[ +0.3066, +0.3756, -0.3588],
-[ -0.3078, +0.3643, -0.0335],
-[ -0.5433, +0.5926, -0.1254],
-[ -0.2532, +0.7950, -0.1380],
-[ -0.6121, -0.3012, +0.0149],
-[ +0.3181, +0.0973, +0.1705],
-[ +0.2236, -0.1020, +0.3147],
-[ -0.0038, -0.3193, +0.1068],
-[ +0.3799, -0.0215, -0.0715],
-[ +0.3440, -0.2333, -0.1001],
-[ +0.1852, +0.7445, +0.4295],
-[ +0.4888, -0.0469, -0.1287],
-[ +0.0297, -0.3913, -0.5198],
-[ -0.0092, -0.1013, +0.2193],
-[ +0.2590, +0.0846, +0.0886],
-[ +0.0744, +0.4771, -0.3553],
-[ +0.2019, +0.1670, -0.1630],
-[ -0.4549, -0.6127, +0.5951],
-[ -0.2582, -0.6401, -0.6541],
-[ +0.0248, +0.0646, +0.1598],
-[ +0.2109, -0.0794, -0.2444],
-[ +0.2435, -0.4159, -0.2927],
-[ -0.0713, +0.2441, -0.4683],
-[ -0.0737, +0.2075, +0.4609],
-[ +0.3240, -0.4084, -0.4554],
-[ +0.3463, +0.4490, -0.2689],
-[ +0.5252, -0.3714, +0.2808],
-[ +0.5561, +0.1137, -0.0258],
-[ +0.6168, +0.0587, -0.1059],
-[ -0.0737, -0.6782, -0.4729],
-[ -0.6030, -0.2577, +0.4194],
-[ +0.4061, -0.1966, +0.2603],
-[ -0.1265, +0.3940, +0.0447],
-[ +0.2460, +0.3328, +0.1654],
-[ -0.1878, +0.6672, +0.0333],
-[ +0.5618, -0.1013, -0.2911],
-[ +0.8250, -0.0788, -0.3731],
-[ +0.2661, -0.2775, +0.2854],
-[ -0.1036, +0.2179, -0.6408],
-[ -0.5371, -0.7837, +0.1141],
-[ +0.4754, -0.0923, +0.1714],
-[ +0.0448, +0.4901, -0.1578],
-[ +0.8797, +0.3316, +0.4349],
-[ +0.1514, -0.4129, -0.3333],
-[ +0.2847, +0.2285, +0.1408],
-[ +0.0045, +0.3333, +0.0694],
-[ +0.1553, -0.5147, +0.0549],
-[ -1.0765, -0.5130, +0.1472],
-[ +0.0808, -0.2612, +0.2591],
-[ +0.5104, +0.3062, +0.3979],
-[ -0.0758, -0.4512, -0.4422],
-[ +0.3236, +0.4479, -0.1759],
-[ +0.2181, -0.0028, +0.5615],
-[ -0.0254, -0.1924, +0.4608],
-[ -0.1566, +0.5634, -0.2498],
-[ -0.0042, +0.5403, +0.0272],
-[ +0.1206, +0.3941, -1.1469],
-[ +0.7642, -1.0114, +0.4905],
-[ +0.5071, +0.2270, +0.0046]
+weights_dense2_b = np.array([
+ +0.0266, +0.3395, +0.0968, +0.0097, +0.0443, -0.1722, -0.2537, +0.1501,
+ +0.0233, -0.0174, +0.1783, -0.0513, -0.1531, -0.2145, +0.0299, -0.1589,
+ +0.1143, +0.1132, -0.2700, -0.0481, +0.2876, +0.1824, +0.2418, +0.1009,
+ -0.1451, +0.1637, +0.1703, +0.0336, -0.1405, -0.0162, -0.1158, +0.1691,
+ -0.0223, -0.1828, +0.2352, +0.0209, -0.1362, -0.2636, +0.1271, -0.0936,
+ -0.1436, +0.0606, +0.1311, -0.0989, -0.2877, +0.2593, +0.0781, -0.1118,
+ -0.1264, +0.2478, +0.2398, -0.1515, +0.0959, -0.0821, -0.1740, +0.1116,
+ -0.0682, +0.1743, +0.1746, -0.1950, -0.0951, +0.2190, -0.0294, +0.1950
])
-weights_final_b = np.array([ +0.4868, -0.0987, -0.0946])
+weights_final_w = np.array([[-0.6826, +0.0812, +0.5225],
+ [-0.2533, +0.7043, +0.6677],
+ [+0.0684, +0.6807, +0.4726],
+ [+0.4605, +0.3736, -0.3187],
+ [+0.4913, +0.0049, +0.4186],
+ [+0.3066, +0.3756, -0.3588],
+ [-0.3078, +0.3643, -0.0335],
+ [-0.5433, +0.5926, -0.1254],
+ [-0.2532, +0.7950, -0.1380],
+ [-0.6121, -0.3012, +0.0149],
+ [+0.3181, +0.0973, +0.1705],
+ [+0.2236, -0.1020, +0.3147],
+ [-0.0038, -0.3193, +0.1068],
+ [+0.3799, -0.0215, -0.0715],
+ [+0.3440, -0.2333, -0.1001],
+ [+0.1852, +0.7445, +0.4295],
+ [+0.4888, -0.0469, -0.1287],
+ [+0.0297, -0.3913, -0.5198],
+ [-0.0092, -0.1013, +0.2193],
+ [+0.2590, +0.0846, +0.0886],
+ [+0.0744, +0.4771, -0.3553],
+ [+0.2019, +0.1670, -0.1630],
+ [-0.4549, -0.6127, +0.5951],
+ [-0.2582, -0.6401, -0.6541],
+ [+0.0248, +0.0646, +0.1598],
+ [+0.2109, -0.0794, -0.2444],
+ [+0.2435, -0.4159, -0.2927],
+ [-0.0713, +0.2441, -0.4683],
+ [-0.0737, +0.2075, +0.4609],
+ [+0.3240, -0.4084, -0.4554],
+ [+0.3463, +0.4490, -0.2689],
+ [+0.5252, -0.3714, +0.2808],
+ [+0.5561, +0.1137, -0.0258],
+ [+0.6168, +0.0587, -0.1059],
+ [-0.0737, -0.6782, -0.4729],
+ [-0.6030, -0.2577, +0.4194],
+ [+0.4061, -0.1966, +0.2603],
+ [-0.1265, +0.3940, +0.0447],
+ [+0.2460, +0.3328, +0.1654],
+ [-0.1878, +0.6672, +0.0333],
+ [+0.5618, -0.1013, -0.2911],
+ [+0.8250, -0.0788, -0.3731],
+ [+0.2661, -0.2775, +0.2854],
+ [-0.1036, +0.2179, -0.6408],
+ [-0.5371, -0.7837, +0.1141],
+ [+0.4754, -0.0923, +0.1714],
+ [+0.0448, +0.4901, -0.1578],
+ [+0.8797, +0.3316, +0.4349],
+ [+0.1514, -0.4129, -0.3333],
+ [+0.2847, +0.2285, +0.1408],
+ [+0.0045, +0.3333, +0.0694],
+ [+0.1553, -0.5147, +0.0549],
+ [-1.0765, -0.5130, +0.1472],
+ [+0.0808, -0.2612, +0.2591],
+ [+0.5104, +0.3062, +0.3979],
+ [-0.0758, -0.4512, -0.4422],
+ [+0.3236, +0.4479, -0.1759],
+ [+0.2181, -0.0028, +0.5615],
+ [-0.0254, -0.1924, +0.4608],
+ [-0.1566, +0.5634, -0.2498],
+ [-0.0042, +0.5403, +0.0272],
+ [+0.1206, +0.3941, -1.1469],
+ [+0.7642, -1.0114, +0.4905],
+ [+0.5071, +0.2270, +0.0046]])
+
+weights_final_b = np.array([+0.4868, -0.0987, -0.0946])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py
index 08245626b..572d495ca 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidBulletEnv_v0_2017may.py
@@ -2,502 +2,7856 @@
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], 256)
- assert weights_dense2_w.shape == (256, 128)
- assert weights_final_w.shape == (128, 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], 256)
+ assert weights_dense2_w.shape == (256, 128)
+ assert weights_final_w.shape == (128, action_space.shape[0])
+
+ def act(self, ob):
+ ob[0] += -1.4 + 0.8
+ 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):
- ob[0] += -1.4 + 0.8
- 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("HumanoidBulletEnv-v0")
- env.render(mode="human")
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
- env.reset()
+ env = gym.make("HumanoidBulletEnv-v0")
+ env.render(mode="human")
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ env.reset()
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ obs = env.reset()
+
while 1:
- frame = 0
- score = 0
- restart_delay = 0
- obs = env.reset()
-
- while 1:
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- score += r
- frame += 1
- time.sleep(1./60.)
+ a = pi.act(obs)
+ obs, r, done, _ = env.step(a)
+ score += r
+ frame += 1
+ time.sleep(1. / 60.)
- 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
+ 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.2289, +0.2584, +0.2595, +0.0173, +0.1293, -0.2980, +0.1410, +0.0982, +0.0216, +0.3724, +0.2204, -0.0734, -0.2420, -0.3443, -0.2738, -0.3825, +0.1504, -0.0930, -0.2680, +0.0685, +0.1592, +0.2534, -0.0787, -0.0426, +0.2591, +0.2134, -0.1631, +0.5168, +0.1444, +0.2736, +0.3623, -0.3472, +0.0393, -0.3056, +0.3850, -0.5231, +0.4511, +0.4223, -0.0905, +0.2265, +0.1662, +0.1092, +0.0426, -0.0209, +0.3260, -0.1788, +0.5045, -0.0254, +0.6684, +0.4659, +0.2193, +0.6121, -0.1771, +0.3024, +0.3233, -0.3380, +0.1834, +0.1947, +0.2840, -0.0212, +0.0610, +0.0254, -0.0687, +0.3342, -0.2010, +0.4851, -0.5739, -0.3228, -0.2242, +0.6149, +0.2704, -0.1006, +0.3950, -0.2684, +0.0090, -0.2419, +0.1112, -0.0795, +0.0021, -0.0317, +0.1345, -0.2847, +0.2323, +0.5374, -0.0119, -0.2098, +0.2074, +0.1693, +0.4537, -0.1453, +0.2661, -0.2997, +0.1043, -0.2340, +0.4472, -0.0415, +0.6437, +0.0279, +0.1609, +0.3353, -0.2240, -0.5433, -0.0053, +0.1863, +0.1038, +0.3337, +0.3889, +0.4159, -0.0836, -0.0826, +0.0872, -0.1362, +0.0061, -0.2982, -0.0074, -0.1452, -0.0655, -0.1369, -0.0493, -0.1082, -0.4080, +0.4732, +0.1229, +0.3087, -0.1222, +0.3846, +0.0719, -0.4536, +0.1202, -0.3903, -0.0445, +0.4052, +0.2922, +0.1095, +0.0317, +0.0974, +0.1149, -0.3794, +0.4364, -0.1597, +0.2889, +0.2431, +0.6867, +0.5117, -0.2517, +0.2835, -0.0365, +0.3303, +0.2569, +0.3636, -0.0945, +0.1853, -0.1341, +0.2595, -0.0174, -0.3227, +0.1999, +0.2348, +0.5826, -0.0480, +0.1449, +0.3866, +0.4740, +0.2486, +0.5011, -0.0334, +0.0953, +0.1072, -0.0901, -0.3235, +0.3258, +0.3003, +0.1229, -0.2257, -0.1920, -0.2025, -0.2022, +0.0843, +0.4563, -0.2654, +0.3158, -0.3102, +0.1105, -0.1171, +0.0465, -0.0692, +0.2824, +0.2598, -0.0289, -0.7774, +0.3501, -0.0635, +0.2257, -0.1644, +0.4091, -0.1967, +0.1614, +0.5468, +0.1365, +0.5054, +0.1986, +0.1368, +0.0886, -0.1305, +0.4297, +0.2482, -0.1914, -0.2909, +0.1784, +0.0690, +0.0224, +0.0378, +0.4991, -0.3410, +0.4281, -0.4574, +0.1952, -0.0444, -0.1939, +0.1637, +0.2385, +0.1354, +0.1817, -0.3849, +0.1909, +0.6585, +0.0997, +0.1376, +0.3598, +0.0611, +0.0124, -0.1492, -0.0659, -0.2671, -0.3925, +0.2333, +0.4184, -0.1364, -0.0361, -0.5937, -0.0327, -0.1142, -0.3334, +0.2963, +0.2350, -0.2600, +0.2784, -0.0720, -0.1594, -0.2652, +0.3922, +0.7291, -0.1830, +0.2253, +0.1965, +0.1972],
-[ +0.2244, +0.6008, -0.2907, -0.1769, -0.1935, +0.0902, +0.3499, +0.0213, +0.1343, -0.4925, -0.0996, -0.2332, -0.0739, -0.3686, -0.8946, +0.0956, +0.0229, -0.1700, -0.1541, -0.1738, -0.2712, +0.2399, -0.9785, +0.0332, -0.1472, +0.2317, -0.2498, -0.5549, +0.2247, +0.1835, +0.3699, +0.4326, +1.0277, +0.5037, +0.1917, -0.0519, +0.6952, +0.0699, +0.5892, -0.2437, +0.4122, +0.8816, +0.1263, -0.2072, +0.7932, +0.1292, -0.0770, +0.0025, +0.5216, -0.0476, +0.1862, +0.5225, -0.1914, +0.2424, +0.9420, +0.3432, +0.0285, +0.1507, +0.1983, -0.3111, -0.2958, -0.3750, -0.3894, +0.4764, -0.0933, -0.1671, -0.3327, -0.1734, +0.3197, -0.2884, +0.0234, -0.3527, -0.4019, +0.4847, +0.8950, +0.1055, +0.1383, +0.2209, -0.0691, +0.6060, +0.3265, -0.0979, -0.2110, +0.6802, -0.4336, -0.6381, -0.1507, +0.4082, -0.1635, -0.0835, -0.0082, +0.5745, -0.2450, +0.7778, -0.2730, -0.6112, -0.0839, -0.0785, -0.6745, -0.1420, +0.4217, +0.3215, -0.2859, +0.3225, +0.0936, +0.0283, -0.1876, +0.4980, -0.4691, -0.0344, +0.1162, +0.1886, -0.1320, +0.4492, +0.0019, -0.0631, +0.2038, -0.3549, +0.2250, -0.2285, -0.0618, -0.0311, +0.7220, +0.0530, -0.3637, +0.2023, -0.3015, +0.1247, +0.2858, -0.2926, +0.2305, +0.2896, +0.1855, -0.3343, -0.1031, -0.3579, -0.6165, -0.3269, +0.0746, +0.2497, -0.3880, -0.5785, -0.7582, -0.1729, -0.3449, -0.1357, -0.5979, -0.7973, +0.1202, +0.6009, -0.0103, -0.0233, -0.0987, +0.4404, +0.4355, -0.0934, -0.0910, -0.0382, -0.0268, +0.0425, +0.0329, +0.7613, +0.1151, +0.1962, +0.3848, +0.6449, +0.0600, +0.8192, +0.2580, +0.4444, -0.5772, -0.1268, -0.0429, +0.0785, +0.1237, +0.5161, -0.3665, +0.0825, +0.1226, +0.4157, +0.4844, -0.5870, -0.6568, +0.1661, +0.0846, +0.9718, +0.8856, +0.4171, -0.4568, -0.0714, +0.0394, -0.1495, +0.1462, -0.1572, +1.3937, +0.1682, +0.4968, -0.3699, +0.0710, +0.2328, +0.4747, -0.4286, +0.4434, -0.0531, +0.8446, +0.0101, -0.4317, -0.2297, +0.4299, -0.1323, +0.4804, -0.2152, +0.0161, +0.0560, -0.3013, +0.2911, +0.3542, +0.3124, +0.3897, +0.1082, +0.2437, +0.0183, +0.2230, +0.0093, +0.1507, -0.3895, -0.2750, +0.0991, +0.1170, -0.5877, +0.4045, +1.0306, -0.1141, -0.0084, +0.3079, +0.4545, +0.0084, +0.1517, -0.0344, +0.4704, -0.2666, -0.0728, -0.0447, +0.4098, -0.4524, -0.4638, -0.4063, -0.2521, -0.2830, +0.1845, -0.3146, +0.4381, -0.0215, +0.2613, -0.1182, +0.4527],
-[ +0.1845, -0.1290, +0.0236, -0.1312, +0.0155, -0.6011, -0.0454, +0.0183, -0.0613, -0.1651, +0.0204, -0.2374, +0.1045, -0.2035, -0.2268, +0.2069, +0.0483, -0.3226, -0.2196, +0.0847, +0.1314, +0.0426, -0.4253, -0.0748, -0.1497, -0.1902, +0.3815, +0.1306, +0.0276, -0.2593, -0.0081, +0.1098, -0.0062, -0.1922, -0.0409, -0.2615, +0.1296, +0.0267, -0.1602, -0.4755, +0.0039, +0.2688, -0.0225, -0.1433, -0.0383, -0.0131, +0.0675, +0.1684, +0.1298, +0.3818, -0.0260, +0.1636, -0.2338, +0.0062, +0.1756, -0.1825, +0.1473, -0.2689, -0.1376, -0.0224, +0.2016, -0.2086, +0.0723, +0.2100, -0.3345, +0.1170, -0.4292, -0.1302, -0.1132, +0.0030, -0.3599, -0.1974, -0.4807, +0.0184, -0.0768, -0.0310, -0.2677, -0.0838, -0.0072, -0.1049, -0.2841, -0.2426, +0.2338, +0.0917, -0.1451, -0.3906, -0.0315, +0.1058, -0.0429, +0.1218, +0.0590, +0.0446, -0.0043, -0.0168, -0.0899, -0.3793, -0.3134, +0.0907, -0.5332, -0.0995, -0.0256, -0.2710, -0.0487, -0.0059, +0.0274, -0.1885, +0.3208, +0.0437, -0.0411, -0.3716, -0.5700, +0.0576, +0.0903, -0.1064, -0.1600, +0.1009, -0.1957, -0.0539, -0.2426, -0.5847, -0.2240, +0.0023, -0.2533, -0.2903, -0.0328, +0.1289, +0.0927, -0.2596, +0.2300, -0.4833, -0.1772, +0.3817, -0.1000, -0.2391, -0.2917, -0.3748, +0.0640, +0.0005, +0.1664, +0.0173, +0.2214, -0.2440, +0.0039, +0.2924, +0.3009, +0.0540, -0.3460, +0.1538, +0.3727, -0.0801, +0.0130, -0.0963, -0.0172, +0.0524, -0.1681, +0.1478, -0.1827, +0.2902, +0.2376, +0.0703, -0.3115, -0.0634, +0.0512, +0.1366, +0.0646, -0.0811, -0.1668, +0.1052, -0.1976, -0.1411, -0.1401, +0.0263, -0.0454, -0.0315, -0.1376, +0.0403, +0.1526, -0.0385, +0.0782, -0.1382, +0.0399, -0.1812, -0.3915, -0.1615, -0.0648, -0.3724, +0.1436, -0.1380, -0.4987, -0.1783, +0.2295, -0.4115, -0.2025, -0.3245, -0.3584, -0.1729, -0.0822, -0.0460, -0.1321, -0.3484, -0.4094, -0.1418, +0.0986, -0.2276, -0.0267, -0.1027, -0.1794, -0.1338, -0.2575, -0.2837, -0.0241, -0.2849, -0.2569, -0.0871, -0.0534, +0.1427, +0.1857, -0.1384, -0.3600, -0.1343, -0.0075, +0.1601, +0.1113, -0.1131, -0.1716, -0.2434, +0.1357, -0.1294, -0.2366, -0.0562, -0.1674, -0.0974, -0.1556, -0.5273, -0.1928, -0.0431, +0.1909, +0.0233, +0.2048, -0.2176, -0.1908, +0.0150, +0.1610, +0.0468, -0.1319, +0.0579, +0.4051, -0.2020, +0.0208, -0.5383, +0.1756, +0.0117, -0.2675, -0.1795, -0.1730, -0.1394],
-[ -0.5736, -0.8805, -0.0769, -0.0851, -0.5427, +0.1977, +0.0607, -0.3635, +0.5918, +0.1243, -0.0683, -0.5963, +0.2201, -0.1754, -0.1193, +0.2689, +0.2383, -0.1014, +0.2498, +0.0947, -0.3494, -0.0848, -0.3292, +0.0194, -0.1043, +0.4501, +0.5483, -0.0839, +0.2682, +0.5032, -0.0208, -0.0950, +0.2171, +0.2045, -0.3694, +0.3404, -0.0883, +0.2092, -0.2164, -0.1036, +0.2583, -0.0949, +0.0715, -0.3988, +0.0751, -0.1982, +0.5441, +0.0172, +0.3297, -0.6622, -0.1357, -0.5829, -0.2161, -0.6473, -0.0565, +0.6117, -0.0156, +0.6255, -0.1497, -0.1722, +0.1335, +0.6251, +0.3700, -0.5719, -0.2368, -0.0315, +0.0146, -0.8732, -0.2498, -0.1137, +0.2604, -0.1385, -0.8775, -0.5170, -0.2435, -0.3753, +0.2906, +0.0193, -0.5174, -0.3639, -0.2548, -0.5402, -0.8794, -0.5529, -0.0559, -0.1246, -0.0725, -0.0145, -0.7285, -0.0017, -0.1507, +0.3688, -0.1245, -0.3651, +0.3866, -0.1138, -0.0853, +0.0368, -0.4360, -0.1958, -0.1419, +0.1774, +0.0723, -0.3591, -0.4659, +0.3450, +0.3742, -0.1436, +0.0044, +0.2917, -0.5689, -0.5904, +0.1288, -0.4701, -0.2539, -0.6716, +0.2295, -0.4429, -0.0556, -0.0518, +0.2292, -1.7909, +0.1799, -0.1646, +0.3310, +0.0519, -0.1858, +0.0612, +0.0647, +0.1269, +0.1987, -0.0585, -0.2811, -0.8582, -0.6569, -0.3871, +0.1939, +0.1120, -0.0105, -0.3577, -0.0086, -0.2489, +0.4663, -0.1103, +0.0332, -0.6252, -0.2411, -0.0892, -0.4744, +0.1257, +0.1445, +0.1788, +0.0429, -0.2699, +0.4812, +0.4112, +0.2460, -0.0158, -0.6195, -0.7866, +0.7380, -0.1607, -0.9005, -0.3402, +0.1250, +0.0292, -0.5294, +0.2517, -0.1519, +0.6130, -0.3528, -0.4301, -0.2510, +0.5858, +0.0060, +0.0751, +0.0733, +0.2363, -0.6337, -0.0453, -0.3818, -0.0374, -0.0048, -0.4378, -0.0780, -0.1101, +0.1504, +0.4377, -0.3238, +0.2260, -0.4677, +0.1361, -0.0218, +0.2108, -0.0987, +0.3155, +0.6500, +0.2126, -0.2016, +0.3768, +0.6421, +0.2673, +0.1952, +0.0513, -0.0657, +0.2197, +0.2465, +0.2605, +0.3151, +0.0719, -0.6572, +0.4819, +0.2985, -0.1793, -0.1759, -0.3330, -0.5562, +0.1846, -0.1096, -0.5457, -0.6485, -0.4409, -0.4658, -0.0819, +0.1681, -0.3892, +0.4901, -0.3008, -0.7256, +0.1596, +0.0896, -0.3508, +0.4520, -0.5112, -0.3458, -0.6592, -0.9615, +0.1979, +0.2483, +0.1385, -0.0924, -0.2448, +0.4041, +0.5250, +0.1655, -0.5895, -0.4537, +0.3295, -0.4612, -0.1340, -0.5730, -0.2680, +0.4814, +0.0250, -1.0258, +0.1863],
-[ -1.0573, +0.3035, -1.0110, +0.1281, -0.5940, -0.0072, +0.4667, +0.7137, +0.0810, -0.8921, -0.1219, -1.0541, -0.7295, +0.7648, +0.1772, -0.1785, -1.0871, -0.1349, +0.3227, +0.6328, -0.8310, +0.8725, -0.4619, -0.3077, +0.8552, -0.3231, -0.1156, -0.5372, -0.4023, +0.8194, -0.8025, -0.5804, +0.5964, -0.0932, +0.5116, -0.2766, +0.1760, -0.1303, +0.6465, -0.0711, -0.1220, -0.5499, +0.1202, +0.1071, +0.2686, -0.1856, -0.2504, +0.0925, -0.4784, +0.9105, -1.1430, -0.5899, -0.1242, +0.5508, +0.7145, +0.2748, -0.3478, -0.7003, +0.4850, +0.1385, +0.3943, +0.2670, -0.4550, +0.0036, -0.5703, -0.8350, -1.1953, -0.0970, +0.3308, +0.7714, +0.1061, +2.0960, +0.0376, -0.7406, +0.0789, +1.5258, +0.9057, +0.4235, -0.5466, +0.1064, +0.2408, +0.7252, -0.2936, +0.4144, -0.3486, -0.7981, +0.0240, -0.1555, +0.9355, -0.4706, -0.7375, +0.9309, +0.7671, -0.0113, -0.2764, -0.0366, +0.2126, +0.6469, -0.4462, -0.2112, +0.6839, +0.4796, -0.1490, +0.8926, -0.2453, +0.0598, -0.0021, +0.3849, +0.4954, -0.1375, -0.1142, +0.8535, +0.8888, -0.3101, +0.7679, -0.5564, -0.2071, -0.3134, -0.0526, -0.1788, +0.3544, +0.6677, +0.3217, -0.6103, -0.0902, +0.3894, +0.8153, -0.5409, -0.0261, +0.7648, +0.3098, +0.5138, -0.1609, +0.3192, +0.4370, -0.1330, -0.0368, +0.8144, -0.1377, +0.9899, +0.2202, +0.5290, +0.4051, +0.0875, +0.4018, -0.0897, +0.4689, +0.1784, +1.2015, -0.2091, +0.3738, +0.7411, -0.1037, -0.2531, +0.3753, +0.1518, -0.1351, +0.3109, +0.2514, +0.2564, -0.2295, +0.5837, +0.1827, -0.1766, +0.1354, -0.0895, +0.8237, +0.4432, -0.3878, -0.0831, +0.7593, -0.9360, -0.4304, +0.0854, -0.9559, +0.1652, +0.2593, +0.3457, -0.5038, -0.1274, +0.4108, -0.0822, -0.1254, +0.4618, -0.0763, -0.4831, -0.4356, +0.5051, -0.4981, +0.2556, -0.1951, +0.5189, +0.0342, +0.2521, +0.1616, -0.0889, -0.0898, +0.3080, +0.2350, -0.2451, +0.2174, +0.3621, +0.7812, +0.8774, +0.7318, +0.1353, +0.0450, -0.8271, +0.5002, -0.7626, +1.3003, +0.4312, -0.6138, -0.1886, -0.2482, -0.5597, -0.0913, +0.0901, -0.3340, +0.4610, -0.7099, +0.3496, +0.3531, +0.2044, -0.1057, +0.8731, -0.6409, +0.5075, +1.0426, -0.7513, -0.3445, +0.1368, -0.0996, +0.4420, +0.2574, +0.2526, +0.2479, +1.3376, -0.0922, +0.2117, -0.1829, -0.0796, +1.4092, -0.2412, +0.0230, +0.3997, -0.3151, +0.0822, -0.7801, -0.5236, +0.0178, -0.9243, -0.5063, +0.5279, -0.2153, +0.6347],
-[ +1.4703, +1.2982, -0.0402, -0.2425, +0.2475, -0.0634, +0.4494, -0.7865, -1.3634, -0.1417, -0.2296, -0.4785, -0.1649, -0.8603, +0.2584, +0.1614, -0.3570, -0.9330, +0.6203, -0.0622, +0.7080, +0.0465, +0.0007, -0.3840, -0.0692, +0.8238, -0.9584, +0.8456, -0.8160, +0.4813, +0.3511, -0.0667, +0.7182, -0.5514, +0.3622, -2.3828, +0.6020, +0.0268, +0.3220, -0.4798, -0.1588, -0.6060, +0.0455, -0.1433, -0.5643, -0.4139, +1.0605, -0.3742, +2.4072, +1.2664, +0.1790, +0.8069, -0.1647, +0.2396, +0.6662, -1.2914, -0.2594, +0.4644, +0.3116, -0.1614, -0.7359, -0.9930, -0.4012, +0.1121, -1.4436, -0.0692, -0.3936, -0.4506, -0.8123, +1.3841, +1.2088, +0.9410, +0.1766, -0.7999, +0.2004, +0.2158, -0.4015, -0.0484, -0.3474, +0.0076, -0.7156, -0.5177, +0.8020, -0.1543, +0.0434, -0.2892, +0.1293, +0.5121, +1.2537, -0.1804, +0.2232, -0.3681, -0.4471, -0.5221, +0.0472, -0.4809, +0.5478, -0.3337, +0.0365, -0.6143, +0.7588, -0.4842, +0.1022, +0.4930, +0.5103, +0.7343, +1.5783, +0.8545, -0.9636, -0.3476, +0.5063, +0.0514, +0.3894, -0.8884, +0.0449, +0.5949, -0.2352, +0.4529, +0.2948, +0.0390, -0.7291, +0.1560, +0.0583, -0.0293, +0.0597, +0.1500, +0.7947, -1.3192, -0.1611, -1.8176, +0.9184, -0.4718, +0.7685, -0.1878, -0.3281, -0.4007, -1.2232, -1.0534, +0.7252, -0.6923, +0.3817, +0.7918, +0.4028, +0.9145, -0.0126, +0.1591, -0.2679, +1.3580, +0.0393, +0.1672, -0.4754, +1.0527, -1.0403, +0.6002, +0.1479, +0.5369, -0.1762, +0.2856, +0.3766, +0.0768, -0.3013, +1.0575, +0.6036, +0.1491, +0.6333, -0.2535, +0.1049, +1.1164, -0.3730, -1.5166, +0.5125, +0.1594, +1.6473, -0.6655, +0.4091, +0.3638, -0.5117, -0.2984, +0.3496, -0.3595, -0.3811, -0.7337, -0.0616, +0.0449, -0.2416, -0.0535, -1.3687, +0.3001, +0.0840, -1.5971, +0.7260, -0.0056, +0.3636, -0.3623, +0.2754, -0.6047, -1.2724, +0.5213, -0.0817, +1.6422, -0.2038, +0.5006, +0.7695, +0.9680, +0.4044, +0.9807, -0.1294, -0.6531, -0.7634, +0.1569, +1.2350, +1.2254, +0.7556, -0.2483, +0.0008, +0.2024, +1.1261, +0.0476, -0.1030, +0.8195, -0.2271, +0.2323, +0.3329, -0.5824, -0.1342, +1.5237, +1.2337, -0.8420, -0.3239, -0.1192, -0.3712, -0.4645, -1.4312, -0.8121, -1.2723, -0.3935, -0.0198, -0.0735, +0.7791, -1.3631, -0.8079, +0.0497, -1.1443, +0.1149, -1.0024, -0.7783, +0.5146, -0.0900, +0.2533, -0.3197, +0.8769, +0.6185, -0.4478, -0.2109, +0.9331, +0.1720],
-[ +0.1914, +0.2367, -0.1629, -0.2121, -0.4821, +0.2042, -0.6208, -0.6690, -0.5308, +0.2751, +0.0058, +0.7246, +0.5435, -0.0560, -0.5556, -0.0165, +0.6507, +0.2775, +0.0431, -0.1270, +0.5966, +0.0977, +0.2673, -0.3136, -0.6983, +0.5473, -0.4528, -0.0306, +0.1088, -0.0717, +0.8475, +1.1961, +0.2308, -0.5281, -0.0913, +0.1937, +0.9934, -0.0981, -0.0031, +0.0337, +0.2783, -0.9124, +0.4286, -0.3317, +0.1689, +0.1181, +0.3386, +0.0006, -0.3645, -0.7711, -0.0095, +0.3991, -0.1333, -0.6688, +0.4254, +0.0559, +0.2671, +0.5579, -0.9046, -0.2728, -0.4878, -0.5582, +0.2866, -0.2315, +0.2442, +0.7093, +0.4266, +0.2287, +0.1558, -0.3636, +0.5561, -1.4425, -0.1192, +0.6250, -0.3334, -0.3746, -0.1556, -0.0636, +0.1641, +0.2846, +0.2501, -0.3944, -0.4040, -0.1150, -0.6399, +0.1609, +0.5772, +0.5262, -0.0361, +0.7536, +0.2497, -0.7278, +0.1851, -0.0259, -0.7170, -0.3231, -0.2127, -0.1993, -0.2452, +0.3888, +0.2922, -0.4279, -0.3269, +0.0756, +0.1988, -0.1777, -0.0172, -0.0312, -0.1341, +0.0269, +0.1057, -0.1237, -0.6615, +0.2952, +0.0767, -0.0778, -0.5447, +0.0285, +0.6785, -0.1794, +0.0174, -0.1047, -0.1765, +0.5859, -0.0837, -0.5167, -0.4280, +0.1787, +0.1762, -0.3390, +0.6731, +0.3160, +1.4737, -0.6632, +0.2942, -0.0664, -0.2121, -0.3356, -0.5989, +0.4079, -0.2348, +0.1857, -0.9283, +0.1377, -0.0273, +0.2580, +0.9982, -0.2876, -0.4685, +0.2032, +0.2644, -0.0163, -0.6819, -0.9446, -1.0937, +0.3750, -0.1436, -0.7771, +0.1031, -0.7357, -0.2943, +0.1850, -0.7978, -0.0747, +0.1661, +1.1391, -0.7675, -0.0677, +0.3038, +0.0354, -0.4304, +0.3333, +0.1617, +0.3656, +1.2621, -0.3526, +0.0040, +0.2239, +0.4336, -0.3180, +0.1273, +0.0488, -0.3459, -0.8226, +0.1833, +0.2386, -0.0214, +0.4261, -0.1491, +0.0678, -0.3771, -0.3311, +0.1703, +0.2722, +0.1684, +0.0372, -0.3637, -0.0246, -0.1785, +0.1548, -0.7042, -0.2042, -0.3849, +0.1776, -0.0536, -0.1493, -0.6161, +0.1739, -0.1201, +0.2798, +0.4395, -0.3635, +0.2738, +0.3116, -0.3052, +0.5248, +0.4516, -0.4132, -0.0536, -0.2435, +0.3823, +0.0218, +0.8631, -0.2524, +0.4060, -0.9034, +0.8162, -0.0182, -0.6250, +1.1502, +0.3362, +0.2115, -0.3169, -0.6787, -0.3379, +0.1962, -0.0973, -0.4042, -0.7209, +0.4764, -0.3201, -0.6573, -0.3488, -0.4370, -0.4269, +0.1515, +0.6850, -0.0542, +0.4701, +0.4224, -0.1287, +0.2937, +0.3044, +0.0041, +0.2738, -0.7350],
-[ -0.5305, -1.0649, -0.0954, -0.2799, -0.3787, +0.9727, -0.0627, -0.2684, +0.5308, -0.2507, -0.2276, -0.2753, +0.7152, -0.1676, -0.6453, +0.2848, -0.5792, -0.4101, +0.4678, +0.5229, -0.5333, +0.2654, -0.1755, -0.2015, -0.1202, +0.7424, -0.0436, -0.7146, -0.3689, +0.3063, -0.0962, -0.5648, +0.3302, +0.8726, +0.4133, +0.3269, -0.3124, -0.3711, +0.0620, +0.1089, +0.7904, -0.6871, +0.1509, -0.6424, +0.6935, +0.1535, -0.2352, +0.2431, +0.2551, -0.9536, -0.6756, -0.5438, +0.5175, +0.0297, +0.3081, +0.7367, -0.5743, +0.5190, -0.6644, -0.2655, -0.8614, +0.5008, +0.1180, -0.6145, +0.0548, -0.0824, +0.1499, -0.4286, -0.2922, +0.1617, +0.4914, -0.1181, -0.0810, -0.5932, -0.1382, +0.2021, -0.2492, +0.4315, -0.3313, -0.7047, -0.1362, -0.6261, -0.8227, -0.2876, -0.3360, -0.0240, +0.4826, -0.3108, -1.4351, -0.0640, -0.0199, +0.5721, +0.2496, -0.3540, -0.6179, -0.1694, +0.3353, -0.1535, -0.2695, +0.0006, -0.0797, +0.6059, -0.0136, -0.1401, -0.1369, +0.5776, -0.3561, -0.7428, +0.1167, -0.2765, +0.2429, -0.5045, +0.2792, -0.3781, +0.1033, -0.2574, -0.1043, -0.2264, +0.4170, +0.4963, +0.1617, -1.0455, +0.0243, +0.7325, +0.1549, +0.2681, -0.0576, +0.7945, -0.1418, +0.9368, -0.4814, -0.5513, -0.3667, -0.9507, -0.5204, +0.1824, -0.0299, -0.3973, -0.1318, +0.1508, +0.6482, -0.3319, +0.3144, -0.0892, -0.4015, -0.1038, -0.0171, -0.1544, +0.0384, +0.0638, +0.1878, +0.4846, +0.3388, -0.2064, +0.0282, +0.0187, -0.2866, +0.2655, +0.1010, -0.3126, +0.2875, -0.2012, -0.5520, -0.7519, -0.0311, -0.4679, -0.2289, -0.1862, -0.6687, -0.0894, -0.4530, -0.4726, +0.2286, +0.4884, +0.2238, -0.4041, +0.4382, +0.0763, +0.2040, +0.1290, -0.1270, -0.3557, -0.3726, +0.2727, +0.1078, -0.3465, -0.1650, +0.1213, +0.1463, +0.4907, -0.6272, +0.2849, -0.1256, -0.0692, -0.1280, +0.6426, +0.8455, -0.2999, +0.2388, +0.3314, +0.0211, +0.1282, +0.7080, +0.2266, -0.4417, -0.5596, +0.0456, +0.0472, -0.0761, +0.3607, +0.0925, +0.5921, +0.5351, -0.1387, -0.0664, +0.0244, +0.0458, -0.1461, +0.4734, -0.3399, +0.1727, -0.3891, -0.2727, +0.1968, +0.3090, -0.2189, +0.0718, -0.4483, -0.5429, -0.1845, -0.6284, +0.1738, +0.0977, +0.1842, +0.1739, -0.5167, -1.2017, +0.1491, +0.6558, +0.4300, +0.8097, +0.0739, -0.3018, -0.1147, +0.2953, +0.2045, -0.2690, -0.2379, -0.3909, -0.1637, -1.1258, -0.3999, +0.3399, +0.0625, -1.1293, +0.3265],
-[ +0.2985, -0.6516, +0.4775, -0.0140, -0.4299, -0.1279, -0.3789, -0.8213, -0.0525, +0.0010, +0.0503, -0.2211, +0.0995, +0.1976, -0.4291, +0.0379, +0.2930, +0.3705, -0.2469, -0.0770, +0.4237, +0.4334, +0.2506, -0.2329, -0.4291, +0.1146, +0.0874, +0.3548, +0.0268, +0.0869, +0.3078, +0.0402, -0.4679, +0.8574, -0.3867, +0.0835, +0.6660, -0.4280, -0.6492, -0.1042, -0.6310, -0.0259, -0.0944, +0.1484, +0.0317, -0.0098, -0.0450, +0.5161, +0.0257, +0.0005, -0.0494, +0.0465, -0.2364, +0.1916, +0.5391, +0.0028, +0.9037, -0.0930, +0.2142, +0.1406, -0.1165, -0.0293, +0.3984, -0.4787, -0.0384, +0.1164, +0.1826, -0.3080, +0.0997, +0.6248, -0.1437, -0.1716, -0.3102, -0.0448, -0.3595, +0.9930, -0.2071, +0.9864, +0.3101, +0.1298, -0.1277, -0.2569, -0.3749, -0.5782, -0.2509, +0.3860, +0.4451, +0.1810, -0.1763, +0.1142, -0.1178, +0.6319, +0.5940, +0.3328, -0.0479, -0.4712, -0.1765, -0.1778, -0.2369, +0.2725, -0.2929, -0.2874, -0.1177, +1.2907, +0.3847, -0.2287, +0.2036, +0.0735, +0.3001, -0.2437, +0.2036, -0.3419, +0.4514, +0.2280, -0.2737, +0.3508, -0.1208, -0.4684, +0.0684, +0.0490, +0.3631, -0.3185, +0.0020, -0.1861, -0.0268, -0.1274, -0.0160, -0.1210, +0.1408, +0.4183, -0.3518, -0.4569, +0.1282, -0.2319, +0.2512, -0.3592, +0.0540, -0.6120, -0.1856, -0.0308, +0.1304, -0.3050, +0.4704, +0.3629, +0.4371, -0.0915, -0.2140, -0.1166, +0.2194, +0.2926, -0.3646, -0.5791, +0.3207, -0.0810, +0.1578, -0.3067, -0.3441, +0.4426, +0.1421, -0.4309, +0.1017, -0.1754, +0.3775, +0.0048, -0.1489, +0.2823, +0.4104, +0.5312, -0.4843, -0.3423, -0.7578, -0.0118, +0.0645, +0.2197, +0.3624, -0.0137, +0.5216, -0.4339, +0.1736, +0.3054, +0.5684, +0.4813, +0.2408, +0.0112, -0.0637, -0.1112, +0.4575, -0.4203, -0.2375, -0.1869, -0.1914, +0.5073, -0.2876, +0.2371, +0.3740, +0.8589, +0.1326, +0.0220, -0.0639, +0.1505, -0.3579, -0.1986, +0.6998, +0.1042, -0.2976, -0.0343, -0.2863, -0.0873, -0.3928, -0.3351, +0.0212, +0.3023, -0.1197, +0.1894, +0.1328, -0.0621, +0.5685, +0.1133, +0.0837, -0.2829, -0.4764, +0.0455, +0.7453, +0.1416, +0.3608, +0.1513, +0.8440, +0.1792, +0.6390, +0.0493, +0.4155, -0.2832, -0.0157, +0.0372, +0.0957, +0.8445, -0.2723, +0.3604, -0.4921, +0.8836, +0.2896, -0.0577, -0.4621, +0.1412, +0.1202, -0.1868, -0.0938, +0.0032, +0.4614, -0.0066, +0.1586, +0.0146, +0.0698, +0.1539, -0.3187, +0.2030],
-[ +0.1593, +0.0673, -0.2547, -0.4164, -0.7417, -0.0947, -0.0055, -0.3648, +0.1302, +0.0556, +0.3797, -0.0956, -0.3993, +0.4257, +0.0176, +0.1360, +0.1971, +0.2499, -0.1564, -0.1776, -0.3742, +0.1572, +0.1570, -0.1127, -0.4366, -0.0255, -0.0662, -0.2298, +0.5912, +0.0107, -0.5855, +0.8709, +0.0119, -0.4277, +0.4122, -0.0525, +0.1397, -0.3018, +0.6338, -0.1003, -0.1246, +0.1427, -0.1638, -0.2808, +0.1959, +0.7202, +0.1200, -0.2316, +0.1650, +0.2782, +0.4346, +0.0802, -0.2768, +0.4015, +0.4213, -0.2252, +0.2750, -0.4314, +0.0254, +0.3742, -0.3016, -0.2429, -0.6429, +0.3386, -0.0971, +0.1080, -0.2511, +0.2752, +0.6792, +0.0080, +0.2215, +0.0504, -0.7341, -0.1637, +0.0300, +0.3588, -0.3274, +0.1918, +0.3612, +0.5223, +0.1182, +0.6870, -0.3318, -0.2261, +0.2921, -0.4550, +0.1582, +0.2888, -0.2669, +0.1638, -0.6216, +0.6262, -0.6351, +0.4334, +0.0973, -0.1839, +0.0321, -0.5037, -0.2649, -0.0552, -0.1270, -0.2993, +0.6138, +0.4850, +0.3384, -0.5962, -0.6860, +0.0256, -0.2307, -0.2724, -0.1256, +0.6033, +0.2383, -0.0195, -0.0630, -0.4518, -0.3697, +0.8157, -0.5800, +0.7963, -0.3184, +0.0568, -0.3475, -1.0642, +0.7602, +0.5601, -0.0858, +0.3643, -0.4833, -0.2227, +0.5590, -0.0992, -0.6019, -0.1924, -0.1267, -0.0245, -0.5970, -0.4330, +0.1239, -1.0436, -0.3711, -0.3417, -0.1319, +0.4664, +0.2170, -0.1831, +0.2072, -0.1819, -0.1112, +0.5897, +0.4138, -0.1745, +0.0069, +0.5481, -0.2551, -0.1321, +0.3068, +0.1709, -0.3829, +0.3386, +0.0268, -0.1402, +0.2465, +0.6522, -0.6667, +0.5380, +0.8128, +0.0613, -0.6277, +0.2254, +0.0309, -0.1557, +0.0074, +0.0135, -0.5031, +1.1359, +0.0562, -0.6937, +0.1323, +0.5053, +0.0667, -0.5712, -0.3070, +0.7015, +0.2751, -0.2162, -0.2375, -0.5178, +0.6995, -0.2979, +0.2039, -0.2180, +0.6633, +1.0514, +0.7916, +0.4500, +0.3561, -0.2985, -0.7077, +0.0663, -0.6082, -0.4968, +0.0381, -0.3695, -0.1673, -0.1879, +0.3407, -0.1239, -0.4802, -0.1217, +0.5713, +0.3748, +0.0324, -0.2357, +0.1038, +0.2317, -0.2465, -0.1541, +0.0306, -0.1631, -0.6562, -0.1803, -0.1607, -0.1324, +0.2002, +0.0519, +0.1840, +0.2045, +0.1503, -0.2435, -0.1554, -0.1546, +0.1199, -0.7402, +0.5261, -0.2881, -0.7153, +0.8782, -0.2197, +0.3991, +0.1447, +0.2319, +0.2099, +0.3708, +0.1532, +0.0936, -0.0373, +0.3127, -0.0938, -0.2230, +0.3024, -0.2431, +0.1687, +0.5369, -0.6572, +0.0691],
-[ -0.9205, -0.6407, -0.3495, -0.1292, -0.2954, -0.2824, -0.5187, -0.1155, +0.1093, +0.0234, -0.0082, +0.0037, +0.4904, -0.0225, +0.5050, +0.2188, +0.4062, +0.0352, -0.0210, -0.7050, +0.1355, +0.6423, -0.6829, -0.3672, -0.2787, +1.0915, +0.0694, -0.4533, +0.6736, +0.2396, +0.0699, -0.7669, -0.8898, -0.5430, -0.6663, +0.1795, -0.8685, -1.0686, +0.1690, -0.0744, -0.2449, +0.3012, -0.1798, -0.3383, +0.4449, -0.8733, +0.0579, -0.1487, +0.4444, -0.7043, +0.0664, -0.0857, +0.0319, -0.1203, -0.7229, +0.1748, -0.2829, +0.8293, +0.1026, -0.2243, +0.3540, -0.1479, -0.5573, +0.2202, +0.1052, +0.1821, +0.2858, -0.2647, +0.0733, -0.5249, +0.9333, +0.1392, -0.4069, +0.2683, -0.0897, -0.1305, -0.2437, -0.2181, -0.2209, +0.0429, -0.1205, +0.1112, -0.1993, -0.0594, -0.0557, -0.3577, -1.1923, +0.0014, -0.6420, +0.1696, -0.9703, +0.7222, -0.0252, +0.1879, +0.3040, +0.2103, +0.0601, +0.0977, -0.2715, +0.2625, -0.7554, -0.0208, +0.0804, +0.1709, -0.0788, +0.2233, +0.1557, -0.4419, -0.1501, -0.1374, -0.0640, -0.0173, +0.5292, -0.3886, +0.8104, +0.1731, +0.4099, +0.0172, +0.2222, +0.4837, -0.1392, -0.2487, -0.3176, +0.9001, +0.5629, -0.0966, -0.7590, +0.7981, -0.3387, +0.1281, -0.0880, -0.1736, -0.4041, +0.2927, +0.2257, -0.2617, +0.0081, -0.0981, -0.3232, -0.8960, -0.4555, -1.0944, +0.2450, -0.6488, -0.3626, +0.3229, -0.7959, -0.9218, -0.1168, -0.0386, -0.0772, -0.3662, -0.2033, +0.5171, -0.2605, +0.2099, +0.0587, -0.1684, +0.5608, -0.2795, +0.4050, -0.2488, -0.0009, -0.3548, +0.2713, +0.2540, +0.4301, +0.1538, +0.5952, +0.0035, -0.0855, +0.1828, +0.5056, -0.0285, -0.2480, +0.3974, -0.1071, +0.7901, -0.1271, +0.0085, +0.0022, -0.0033, -0.5544, -0.3821, -0.4543, +0.5065, -0.2156, +0.4301, -0.0898, +0.0038, -0.3771, -0.1299, +0.3414, +0.2850, +0.2536, +0.2735, -0.2499, +0.1810, -0.8185, +0.2789, +0.0172, +0.1249, +0.5116, -0.3276, +0.0151, -0.1496, -0.3928, +0.0160, +0.1973, +0.6946, -1.0572, +0.2596, +0.5213, +0.1074, +0.0397, +0.0158, -0.1003, +0.0849, -0.6143, +0.0286, +0.1211, -0.3642, -0.2030, -1.3791, -0.2391, -0.0444, -0.2008, -0.4846, +0.4913, -0.1766, -0.7605, -0.6237, +0.0567, -0.2466, +0.8322, +0.1745, -0.5219, -0.2627, -0.0347, +0.0840, +0.8085, -0.8310, -0.2293, -0.5016, +0.3874, -0.3295, -1.6434, -0.0489, -0.2061, +0.2168, -0.8213, -0.3119, +0.3437, -0.3040, +0.2633, -0.6758],
-[ -0.1224, +0.1807, +0.0476, -0.1733, -0.2275, -0.6607, +0.5602, +0.2290, +0.4946, -0.3229, +0.2211, +0.5021, +0.2795, -0.4379, -0.4183, +0.0239, -0.0520, -0.3631, +0.5901, -0.8528, -0.3056, -0.0029, -0.2342, -0.2650, -0.0214, +0.1637, +0.3739, -0.1126, -0.0839, -0.1313, +0.0461, -0.5930, +0.2383, +0.3599, -0.3978, -0.2775, +0.1222, -0.6615, +0.1524, -0.2367, -0.3254, -0.1699, -0.2446, +0.0040, -0.2987, -0.0853, +0.0497, -0.1563, -0.0894, -0.0426, +0.3357, -0.5865, -0.3145, -0.2334, +0.4475, +0.6045, -0.1532, -0.5043, -0.3072, -0.2198, +0.1998, -0.1104, +0.1984, -0.0500, -0.1988, -0.0554, +0.6667, +0.2950, +0.4560, +0.0905, +0.8948, +0.4141, +0.0889, +0.2876, +0.8547, +0.0443, +0.4713, +0.0125, +0.4692, +0.0556, +0.3437, -0.2034, +0.0493, +0.0987, -0.5343, -0.5624, +0.5240, +0.6423, +0.0898, -0.3092, -0.3829, +0.4628, -0.3896, -0.2335, +0.4425, +0.1577, -0.3808, +0.7042, -0.1099, +0.2177, -0.4898, -0.2984, +0.2604, -0.0835, -0.5402, +0.0921, -0.1487, +0.1235, -0.0274, +0.1865, -0.3032, +0.1477, -0.8785, +0.2594, +0.2667, +0.1290, +0.4497, -0.5279, +0.2041, -0.2774, -0.2247, +0.1755, +0.2179, +0.2883, -0.2374, -0.2710, -0.6661, +0.2488, -0.2718, +0.3415, -0.0217, +0.1544, +0.2134, +0.0385, -0.3567, +0.1695, +0.3289, +0.5405, -0.1381, -0.5697, -0.1969, -0.0151, -0.4153, -0.3042, -0.4061, -0.9120, -0.3237, -0.4619, -0.2990, -0.3770, -0.1387, +0.0114, -0.7310, +0.1120, +0.1241, -0.2797, +0.0220, -0.0135, +0.3210, -0.6078, -0.4427, -0.1668, +0.0040, -0.6242, +0.8404, -0.5844, +0.6519, +0.2185, -0.0381, -0.3671, +0.4789, +0.0554, +0.1012, +0.0864, -0.0963, -0.3227, -0.1091, +0.5487, -0.5835, +0.2718, +0.6050, -0.0901, -0.1951, -0.1213, -0.1814, -0.2178, -0.2861, -0.3037, -0.0871, -0.4600, +0.2746, -0.5300, -0.5216, +0.7110, +0.1588, +0.0332, -0.7698, +0.7929, +0.4748, -0.0828, -0.1833, +0.0244, -0.4698, -0.2932, +0.7227, +0.3943, +0.6195, -0.4069, +0.5510, +0.4044, -0.0376, +0.1132, +0.2594, +0.2696, -0.0090, -0.5220, +0.3694, +0.2535, +0.2949, -0.3292, +0.1338, -0.1614, -0.4826, -0.6461, -0.0891, +0.6627, -0.4489, +0.1577, +0.7618, +0.4944, -0.3768, -0.0778, +0.0620, -0.2107, +0.0132, -0.1325, -0.0489, +0.2153, -0.2410, +0.1829, +0.1007, -0.1304, -0.2355, -0.7770, +0.3267, -0.3735, -0.2366, +0.1976, -0.1219, +0.3927, +0.2558, -0.0528, +0.6828, +0.6081, -0.0640, -0.1716],
-[ +0.5773, +0.4005, +0.2367, -0.2554, -0.0570, -0.3491, -0.1217, +0.1797, +0.2174, +0.2224, +0.1831, +0.3781, -0.1077, -0.4088, -0.3937, +0.1849, +0.6256, +0.1961, -0.3727, -0.1188, -0.2571, -1.0813, +0.1191, -0.0072, +0.3410, -0.1113, +0.0178, +0.0221, -0.2449, +0.1956, +0.4295, +0.0470, -1.0544, +0.3908, -0.2403, +0.0338, +0.1049, -0.1989, -0.6795, +0.1352, +0.3580, -0.0550, +0.1559, +0.1566, -0.2989, +0.3722, +0.3373, +0.1194, -0.0818, +0.0315, +0.2551, +0.0579, +0.0571, +0.2316, -0.0330, -0.4553, -0.3433, -0.1070, -0.3248, +0.3737, -1.0162, -0.2596, -0.5808, +0.0423, -0.0359, -0.5898, +0.0525, +0.4582, +0.0296, -0.4855, +0.1305, -0.5326, +0.1646, +0.2046, -0.6652, -0.1011, +0.0367, +0.0979, -0.1058, -0.8457, -0.1656, -0.5374, +0.7134, -0.6131, +0.0588, -0.5346, -0.4256, +0.2006, +0.5099, -0.5682, -0.3149, -0.1147, -0.9188, -0.0958, -0.2129, -0.6066, -0.0144, -0.2814, +0.0966, -0.1576, +0.1431, -0.1485, +0.2355, -0.1664, -0.0622, -0.0011, -0.0136, +0.1440, -0.6193, -0.1540, -0.1121, -0.2571, +0.0337, +0.5311, -0.7750, +0.2000, +0.1121, -0.1559, -0.5731, +0.3587, -0.0157, +0.0921, +0.2889, -0.0086, -0.1163, -0.1031, +0.4536, +0.0260, +0.4147, -0.0971, -0.6322, -0.1779, +0.1588, +0.1106, -0.6539, -0.1867, -0.0918, -0.4986, +0.1861, -0.8405, +0.0673, +0.1445, -0.2178, +0.0211, -0.3776, -0.2325, -0.7193, -0.2383, +0.1055, -0.3297, -0.6075, -0.0166, -0.0599, +0.3519, +0.2016, -0.1683, -0.0618, +0.0966, +0.4444, +0.0336, -0.0360, -0.0038, -0.0901, +0.0575, +0.1595, +0.0420, +0.3149, +0.1565, -0.5973, +0.0455, -0.2269, +0.7422, -0.1403, +0.1556, -0.5552, -0.1018, -0.1478, -0.1449, -0.3502, -0.3411, -0.6673, +0.1856, -0.1387, -0.0826, +0.2279, +0.3411, +0.3251, -0.8518, +0.4285, -0.3885, +0.0961, +0.2770, +0.5029, +0.0081, -0.0688, +0.2335, -0.2451, +0.0313, -0.1630, +0.4845, -0.1214, -1.0611, -0.9483, -0.0859, +0.7039, -0.0264, +0.1340, -0.3957, -0.1174, +0.1597, -0.1261, +0.0289, +0.1340, +0.1144, -0.1680, +0.3226, -0.1484, -0.3115, +0.0072, -0.3260, +0.4108, +0.1639, -0.9366, +0.4429, -0.1095, -0.2999, -0.0186, -0.5972, -0.1980, -0.2521, +0.2721, +0.2089, +0.1511, -0.1393, -0.4629, -0.8785, +0.0836, -0.2853, -0.3804, -0.4894, +0.1630, -0.3580, -0.0938, +0.3543, -0.1880, +0.4280, -0.0910, -0.1145, -0.4794, -0.0023, +0.0837, +0.2889, -0.0548, -0.1878, -0.2514, +0.2941],
-[ +0.1971, +0.1297, +0.3127, -0.1900, +0.2138, -0.5950, -0.0518, +0.5522, +0.7271, -0.4612, +0.0603, -0.0771, +0.0421, +0.2994, -0.7150, -0.6847, +0.4128, +0.2148, +0.7659, -0.1203, +0.0513, -0.6664, -0.4696, -0.1599, -0.0016, -0.2961, +0.0878, +0.1158, +0.3799, +0.1267, +0.2748, -0.7240, -0.1967, +0.8070, -0.4856, +0.2131, +0.4358, -0.0098, -0.1944, +0.7715, +0.0676, +0.2041, -1.1034, -0.3384, +0.6977, +0.1520, +0.3113, -0.3375, +0.1434, +0.0769, +0.4804, -0.4066, -0.1047, +0.1328, -0.6792, +0.1742, +0.1389, -0.0741, -0.2742, +0.1880, -0.7640, -0.3254, +0.0108, -0.5652, -0.7209, -0.2656, +0.4557, +0.1764, -0.2182, -0.3519, -0.1209, +0.1609, +0.2707, -0.0814, -0.2446, -0.1418, +0.0642, -0.4075, -0.3181, +0.1488, -0.3156, -0.0194, -0.1112, -0.0664, +0.8506, +0.0797, +0.0967, +0.0589, +0.2103, -0.1941, -0.0901, -0.1765, +0.2050, -0.5338, +0.2230, +0.0117, +0.4295, -0.6978, -0.2315, -0.1358, -0.1298, +0.1919, +0.7137, +0.4695, -0.2569, +0.3268, -0.1098, -0.6414, -0.3317, -0.5824, +0.3109, +0.5197, +0.0289, +0.2862, -0.1670, -1.1588, -0.5376, +0.7066, -0.4736, -0.6062, +0.0383, +0.4817, +0.3675, -0.2474, -0.1373, +0.6097, +0.1162, +0.0026, +0.5885, +0.5167, +0.1943, -0.2286, -0.0977, -0.0914, -0.2177, -0.4933, -0.2152, +0.3393, +0.4035, +0.4174, -0.0249, -0.1241, +0.2562, +0.2692, -0.4636, +0.2140, -0.2008, -0.2862, -0.0860, -0.3197, -0.2499, +0.4412, -0.1225, -0.0678, -0.5300, +0.0226, +0.5928, +0.4112, +0.3408, +0.3258, +0.3220, +0.6597, -0.3444, +0.3276, -0.3681, -0.4247, -0.2516, +0.2093, -0.5528, +0.0715, +0.3478, +0.5149, +0.7822, -0.1180, +0.3608, -0.1642, +0.1633, -0.3586, +0.3944, -0.3117, +0.3464, +0.2220, -0.1847, +0.2722, -0.1410, +0.6442, +0.2111, -0.5102, +0.0657, -0.0787, +0.1314, +0.1596, +0.3922, +0.4387, +0.3768, +0.0938, -0.2301, -0.4222, -0.2457, +0.1377, +0.0971, -1.0034, -0.6783, -0.2950, +0.6848, +0.3718, -0.0991, +0.3351, +0.4113, -0.0339, -0.0272, +0.1386, +0.1174, +0.5951, -1.3231, +0.1352, -0.0537, -0.0648, -0.0348, -0.3936, +0.4308, -0.5901, +0.3274, +0.4185, +0.2364, -0.0838, +0.1790, -0.2632, -0.5750, -0.3647, -0.7477, -0.3476, +0.6007, +0.2378, -0.2952, -0.8994, +0.0876, +0.5734, -0.1559, +0.1650, +0.4103, -0.0516, -0.4388, +0.6463, -0.4788, +0.0584, +0.0616, +0.1933, -0.1242, -0.5378, -0.0676, +0.5118, +0.2571, +0.5174, +0.5873, -0.0766],
-[ +0.0258, +0.0557, +0.0314, -0.1428, +0.1264, +0.2882, +0.1731, +0.0442, -0.6218, -0.1942, -0.3289, +0.2295, -0.1792, -0.3100, -0.3131, -0.3692, -0.1941, +0.5551, +0.0759, +0.0739, -0.2385, -0.4435, -0.1647, +0.3799, +0.1403, -0.2910, -0.1646, -0.1996, -0.0809, -0.3370, +0.1309, -0.1390, +0.1873, -0.1753, -0.1671, +0.0357, +0.0419, +0.1547, -0.2335, +0.3820, +0.0704, +0.1450, +0.3619, -0.4785, +0.0094, +0.2105, -0.0015, -0.4892, +0.0153, +0.1744, +0.6894, +0.0375, -0.2539, +0.3752, -0.0939, +0.0410, -0.0005, +0.0414, -0.5551, +0.0786, +0.2726, -0.2081, +0.1608, +0.0056, -0.3801, +0.2772, -0.0787, -0.3693, -0.1018, +0.1075, +0.0577, +0.1752, +0.2847, +0.1793, -0.2131, +0.1969, +0.0438, +0.0763, -0.2106, +0.1562, -0.0079, -0.0419, -0.6081, -0.3683, -0.0284, +0.0196, +0.2458, +0.0486, +0.3165, -0.1404, +0.0881, -0.2001, +0.0943, -0.2257, +0.1904, -0.2215, -0.0143, +0.1636, -0.1493, +0.0209, -0.3232, -0.1058, +0.1450, +0.2953, -0.0649, -0.1792, -0.4404, +0.0648, -0.0782, -0.0980, -0.1962, +0.0114, -0.4174, +0.1230, +0.2255, -0.4465, +0.0099, -0.0002, -0.0327, -0.2182, -0.0044, +0.1385, +0.2404, -0.1530, -0.2449, -0.1187, -0.1197, -0.0196, +0.0636, +0.2732, -0.0020, -0.3308, -0.2261, -0.2961, -0.0110, +0.1877, -0.1727, -0.0579, +0.3186, -0.1244, +0.4831, -0.3772, +0.2442, -0.5991, -0.0244, -0.0651, +0.3005, +0.2811, -0.1175, -0.1017, +0.0363, +0.1163, -0.1070, +0.2171, -0.2766, -0.1591, -0.2473, +0.2177, -0.5437, +0.2643, +0.1680, -0.2968, -0.1783, -0.3845, -0.2310, -0.1699, +0.1597, +0.0023, +0.0930, +0.3626, +0.1183, +0.3463, +0.1107, +0.1850, +0.1242, -0.0231, -0.2174, -0.2698, -0.5214, -0.3067, +0.0808, +0.6624, -0.0719, +0.0046, +0.2116, -0.0666, +0.1001, -1.0531, +0.4140, -0.6715, -0.0883, -0.2107, +0.1025, -0.2391, +0.0068, +0.5813, +0.0922, -0.7574, +0.1401, +0.1576, -0.0085, -0.2051, +0.2217, +0.0145, +0.0643, +0.2933, -0.1660, -0.0310, +0.3889, +0.2739, +0.0619, -0.0057, -0.0851, -0.3741, -0.0350, +0.0032, -0.1186, +0.3271, -0.7010, -0.0641, -0.2619, +0.2942, +0.0946, -0.2396, -0.0092, +0.2894, +0.4296, -0.1338, +0.4397, -0.3429, +0.5862, +0.2123, -0.0220, +0.0683, -0.0801, -0.2240, +0.1695, -0.0177, +0.1851, -0.2303, +0.1154, -0.0554, -0.1827, +0.0404, +0.5515, -0.3435, +0.1356, -0.6155, +0.0421, +0.4062, -0.1319, -0.1664, +0.2044, -0.3144, +0.3057, +0.5167],
-[ +0.2190, +0.5299, +0.0416, -0.0133, +0.2273, +0.1847, +0.2117, -0.3650, +0.1088, +0.7693, +0.2472, -0.1210, -0.3569, -0.1793, -0.3154, +0.2999, +0.6809, +1.1643, -0.4968, -0.0260, -0.3963, +0.2722, -0.2396, +0.0662, -0.1695, -0.3343, -0.4404, +0.2240, -0.2892, +0.3186, +0.0070, -0.3156, +0.5497, +0.1461, +0.4193, +0.5595, -0.1487, +0.2295, -0.1106, +0.8187, +0.2716, -0.3308, -0.2466, +0.7375, -0.5231, -0.8374, -0.1546, +0.8101, +0.0305, +0.4414, +0.9101, -0.0790, -0.7719, -0.1223, +0.2108, -0.3328, -0.1319, +0.0044, -0.7621, -0.2411, -0.3317, -0.3602, +0.3811, -0.5627, -0.3574, +0.1514, -0.1217, +0.1223, -0.3627, -0.3312, +0.0908, +0.3559, -0.2127, +0.4198, -0.1993, +0.5076, +0.6647, +0.6660, -0.3889, +0.3641, +0.0583, +0.6410, +0.3024, +0.7780, -0.0566, -0.0725, +0.0005, -0.6199, +0.1416, -0.1018, +0.1975, +0.0407, -0.6696, +0.1270, +0.2403, -0.0984, +0.1143, -0.1629, +0.5482, -0.5193, -0.0165, +0.5192, +0.7334, -0.1055, -0.0946, -0.2747, -0.9139, +0.5439, -0.0660, -0.1288, +0.0253, -0.3988, -0.4482, +0.7088, +0.5435, -0.5111, +0.0793, +0.0429, -0.4865, +0.4337, +0.3207, -0.1065, +0.5435, +0.0121, +0.0708, +0.4475, +0.0082, -0.0752, +0.5082, +0.5027, -0.4079, -0.1469, -0.0291, -0.2024, +0.4415, +0.6201, +0.0561, +0.7860, -0.0309, -0.4140, -0.4525, -0.0112, -0.2588, -0.1160, -0.1658, -0.3977, -0.1903, +0.0040, +0.5195, -0.5027, +0.1395, +0.3001, -0.0364, -0.0070, -0.1940, -0.0794, -0.7707, +0.0793, +0.2436, -0.2028, +0.7458, -0.4411, +0.3906, -0.3629, -0.3652, -0.1732, +0.0129, -0.1646, +0.1341, +0.3027, +0.3714, +0.8555, +0.0846, -0.1275, +0.1576, -0.5475, +0.2914, -0.4467, -1.0526, +0.4156, +0.1801, +0.5511, -0.2876, -0.3708, +0.4191, -0.5156, -0.5698, -0.2032, -0.3767, +0.9636, +0.0591, -0.2111, -0.2921, +0.2434, +0.1629, +0.5713, -0.0247, -0.3819, -0.0096, +0.1990, +0.1771, +0.1748, -0.6692, +0.6622, +0.8074, +0.1628, -0.0205, +0.2880, -0.4322, +0.2115, -0.7574, +0.6190, +0.0132, -0.2705, -0.5313, -0.2903, +0.6175, -0.2226, -0.1388, -0.5078, -0.6529, +0.2888, +0.2174, +0.3050, -0.2648, -0.1298, +0.0513, +0.0026, +0.2277, +0.6358, -0.3906, -0.3793, +0.6255, -0.4248, -0.5383, +0.2805, +0.1700, +0.1024, -0.2525, +0.0197, +0.0756, +0.2159, -0.4651, -0.3313, -0.4396, +0.4773, -0.5920, -0.1574, -0.0513, -0.7548, +0.1198, +0.6633, -0.0992, +0.4179, +0.5154, +0.1625],
-[ +0.4234, +0.4392, -0.2747, -0.2705, -0.6422, -0.0934, +0.0052, -0.0935, +0.0754, +0.1551, -0.0347, +0.1696, +0.2298, +0.1517, -0.1544, -0.7179, +0.3967, -0.4788, +0.2861, -0.2384, +0.3171, +0.3328, -0.2257, -0.2352, +0.3594, +0.1360, -0.1726, -0.0534, -0.3732, +0.4586, +0.6655, +0.1862, -0.0504, -0.5245, -0.2335, -0.1044, +0.1731, -0.4958, +0.3857, +0.1822, -0.2132, +0.2401, -0.1770, -0.3829, -0.1447, +0.0365, +0.1743, -0.0582, +0.1387, +0.1938, -0.4010, +0.2540, -0.1261, -0.1798, -0.1797, -0.3228, -0.1266, -0.0110, +0.4102, +0.1474, -0.3089, -0.3147, -0.4659, +0.7590, -0.0920, -0.0002, -0.4629, -0.1343, -0.1630, -0.1713, +0.0623, +0.1539, -0.2611, +0.2111, +0.0032, +0.0254, -0.1147, -0.5070, +0.2582, +0.4978, -0.2704, +0.2963, -0.2424, -0.2377, +0.0542, -0.5813, -0.3314, +0.0234, +0.1353, +0.1885, -0.4818, +0.4946, -0.3437, -0.0408, -0.3601, +0.1318, +0.2486, -0.3088, -0.4411, +0.5277, -0.1257, -0.4646, -0.4539, -0.0095, +0.6496, -0.1052, -0.6746, +0.3025, -0.0855, -0.1113, +0.1304, -0.2482, +0.0107, -0.3439, -0.1315, -0.2316, +0.1768, -0.2268, -0.1223, -0.5271, +0.3784, -0.5252, -0.2377, +0.1388, -0.3378, +0.2181, -0.0689, +0.2941, +0.0044, +0.1891, -0.0509, +0.0914, +0.2977, -0.1663, -0.3623, -0.0772, +0.0197, -0.2234, -0.3112, -0.0609, -0.1381, +0.0890, +0.0460, +0.0142, -0.4865, -0.1751, +0.2371, -0.1852, -0.6088, +0.0152, -0.0823, -0.1289, -0.2044, -0.7310, -0.2056, +0.1072, +0.0079, -0.1789, +0.1253, -0.2312, -0.3431, -0.1412, -0.0953, -0.3622, +0.3766, +0.3203, +0.1998, -0.1852, -0.4630, +0.1017, +0.0380, -0.3577, +0.0552, -0.0491, +0.0620, -0.2254, +0.5100, +0.3085, -0.9197, +0.0245, +0.1613, -0.2888, -0.3367, -0.7743, +0.2930, +0.5275, +0.2395, +0.3260, -0.4876, +0.1441, +0.1083, -0.2077, -0.0162, -0.0100, -0.0559, -0.0036, +0.1453, +0.0042, +0.2518, -0.2407, +0.1021, +0.0405, -0.2128, +0.0866, +0.2753, -0.2614, -0.0256, -0.6157, -0.2181, -0.3962, +0.5585, -0.2790, -0.3463, -0.2301, -0.3256, +0.1199, +0.3906, -0.2450, +0.2601, +0.2751, +0.2546, +0.3675, -0.1279, -0.3002, -0.2151, -0.3924, -0.6061, +0.0396, -0.2452, -0.3420, +0.0579, +0.4261, -0.2200, -0.0324, -0.2346, -0.5050, -0.0047, -0.1375, -0.6326, -0.2100, +0.2774, +0.0850, +0.1070, -0.2795, +0.2149, -0.4067, +0.2429, -0.1144, +0.4880, +0.0949, +0.3567, +0.0152, +0.0013, -0.2505, -0.1949, +0.0630],
-[ -0.1723, -0.1557, -0.4950, -0.3447, +0.3134, -0.3579, -0.0001, +0.0962, -0.5796, -0.4150, -0.5110, +0.4075, +0.0227, +0.0725, -0.9421, +0.6107, +0.2790, +0.1984, +0.2337, +0.5453, -0.0340, +0.3049, -0.1807, -0.1085, +0.4351, +0.4050, -0.1805, -0.2090, +0.3533, -0.0195, -0.0786, +0.8944, -0.2721, +0.7169, -0.2861, -0.1510, -0.2619, -0.3671, -0.2015, +0.2595, +0.0351, +0.2994, -0.3666, +0.2408, +0.3073, -0.0179, +0.0976, -0.3664, +0.1841, +0.0979, -0.1209, +0.2309, -0.2827, +0.3789, +0.4197, -0.0155, +0.1979, +0.2720, -0.1160, +0.4626, -0.5456, +0.0007, -0.2535, -0.1234, +0.1810, +0.1973, -0.3088, -0.1346, +0.3206, -0.1146, +0.2446, -0.3067, -0.4639, +0.1647, -0.2162, +0.3796, +0.0619, +0.6112, +0.1175, +0.5665, +0.1142, +0.3709, -0.1419, +0.1321, +0.0650, +0.1952, -0.3417, +0.3802, -0.6273, -0.0162, +0.1213, +0.0823, -0.5304, +0.9111, +0.5029, +0.8862, +0.2029, +0.2394, +0.4913, -0.2721, -0.0655, -0.0001, +0.0483, -0.5096, -0.0732, -0.4347, -0.4974, +0.0450, +0.2935, -0.1081, +0.7021, -1.1752, +0.0609, -0.9516, -0.4281, +0.0092, +0.2223, -0.7367, +0.0107, -0.5940, -0.1206, -0.0405, -0.2688, +0.0516, -0.1647, +1.0320, -0.6207, -0.2238, +0.2180, -0.1574, -0.0412, +0.1640, -0.8342, +0.5910, +0.5872, -0.1396, +0.0310, -0.4284, -0.1957, -0.5202, -0.4918, +0.1178, +0.1810, +0.2900, +0.3115, +0.0185, +0.0360, -0.0422, -0.0245, +0.0866, -0.1750, -0.2731, -0.2825, -0.5676, -0.1056, +0.3177, +0.3432, +0.2608, +0.3884, +0.5627, -0.2243, -0.0137, -0.1918, -1.0110, -0.2613, -0.0348, +0.3585, -0.6610, +0.5136, -0.0330, +0.3686, -0.6808, +0.2505, +0.3316, +0.7917, -0.1283, +0.9045, +0.1989, -0.5997, -0.9126, +0.2693, +0.3214, -0.7779, -0.7518, -0.2985, +0.6057, +0.1136, +0.2035, +0.2291, +0.2812, -0.0236, -0.9562, +0.1740, -0.0238, +0.7070, +0.0373, -0.2822, +0.1867, +0.0245, -0.3107, -0.4408, -0.2246, -0.3152, +0.5446, -0.2249, -0.4331, -0.3255, -0.4219, -0.5227, -0.0210, +0.0635, -0.2103, -0.5634, +0.8767, +0.2529, -0.1215, -0.3635, -0.1327, -0.3813, +0.4531, -0.6627, +0.1316, +0.2156, +0.1508, -0.2161, -0.1154, -0.6417, +0.8709, -0.2289, +0.0605, -0.4046, +0.3373, -0.1148, -0.6212, +0.0371, -0.1410, -0.2213, +0.8599, -0.4573, +0.6222, +0.3107, -0.1569, +0.4160, -0.0845, +0.1652, +0.0080, +0.1743, -0.0456, +0.3639, +0.2093, -0.1005, +0.0093, -0.2168, -0.7153, -0.1972, +0.7276],
-[ +0.1697, -0.3885, +0.1069, -0.0617, +0.5131, -0.1418, +0.1427, -0.5709, +0.0191, -0.0495, -0.3026, -0.1129, +0.1109, -0.0662, +0.3090, +0.3430, -0.2976, +0.1814, -0.4145, -0.1168, -0.1641, -0.3613, +0.2260, -0.3825, -0.1149, +0.5480, +0.3160, +0.1604, -0.1252, -0.1538, -0.2604, +0.2282, -0.2813, +0.1356, -0.5893, -0.1053, -0.1946, -0.7235, +0.2499, -0.6875, +0.0987, +0.0351, -0.1473, +0.0171, -0.3876, -0.1652, -0.0297, +0.1009, -0.1188, -1.0803, +0.0354, -0.3797, -0.0477, +0.2496, +0.1565, +0.0354, -1.0098, -0.0470, -0.0345, -0.2341, +0.0760, -0.0247, -0.4161, -0.0920, +0.3157, +0.5730, -0.1212, +0.0573, +0.1007, +0.1926, +0.4577, -0.2041, -0.1005, +0.1324, +0.2268, -0.3710, -0.0038, -0.2247, +0.3495, -0.3643, -0.2977, -0.5127, -0.0201, +0.1074, +0.4485, -0.2529, -0.1624, -0.2576, -0.0633, +0.5198, +0.4709, +0.2370, -0.1645, +0.0109, -0.1159, -0.1174, +0.2032, -0.2863, -0.1481, +0.0215, -0.3431, -0.7387, +0.0869, +0.2565, -0.7215, -0.2867, -0.2441, -1.6201, -0.1918, -0.1217, +0.1225, -0.1834, -0.4723, +0.2542, +0.0229, +0.2454, -0.2479, -0.0542, +0.2266, +0.0513, -0.1715, +0.3481, -0.0674, +0.0048, +0.0435, -0.0930, -0.0589, -0.1182, -0.2407, +0.1002, +0.1340, +0.5007, -0.1613, -0.1241, -0.3080, +0.1454, +0.3897, -0.2256, -0.0927, +0.1028, -0.4274, -0.2913, -0.3130, -0.9492, +0.2260, -0.4201, +0.1871, -0.0975, -0.8489, +0.7287, -0.4117, +0.1555, -0.2486, -0.6040, +0.4002, -0.2970, -0.1902, +0.1478, +0.3497, +0.0713, -0.0653, -0.5390, -0.3187, +0.2181, +0.2413, +0.5533, -0.3434, -0.1390, -0.2986, +0.1452, -0.7319, +0.0479, -0.4350, +0.2009, +0.0184, -0.5783, -0.1971, -0.0501, +0.1205, -0.6514, -0.4555, -0.1106, -0.0623, -0.1877, -0.2276, +0.0869, +0.5072, -0.1449, +0.1115, -0.3480, -0.8555, +0.0199, -0.3390, +0.2017, -0.1187, -0.3836, +0.2586, +0.0085, -0.1478, -0.1012, +0.0896, +0.4176, +0.5783, -0.2789, -0.3044, +0.0019, -0.0417, -0.0133, -0.1092, +0.0913, -0.0325, +0.2607, -0.0013, -0.0174, +0.1431, -0.1434, -0.1505, -0.0888, +0.3194, +0.0493, -0.1195, +0.3872, +0.0543, +0.6214, -1.1019, -0.3721, -0.3201, +0.3204, -0.1039, -0.0099, +0.0641, -0.3761, +0.2542, -0.1680, +0.3555, -0.0990, -0.6406, +0.2056, -0.5322, +0.1438, +0.1698, -0.4285, +0.2757, -0.2258, -0.0983, +0.1210, -0.2695, -0.0074, -0.0644, -0.0990, -1.3496, +0.1073, +0.3525, -0.0115, +0.0264, -0.2596],
-[ +0.2747, +0.5628, +0.4431, -0.4808, +0.1649, +0.5614, +0.3499, +0.3167, -0.4618, -0.0132, -0.3237, -0.2952, +0.4245, -0.1691, +0.1089, +0.1352, -0.2851, +0.1287, -0.6465, -0.2492, +0.4377, +0.2717, +0.4748, -0.5543, -0.4054, +0.1491, +0.2907, +0.6462, +0.2216, -0.4695, -0.0424, +0.2164, -0.2030, -0.4614, -0.1250, +0.0055, -0.0856, -0.1442, +0.4880, -0.2420, -0.4811, +0.1583, -0.4418, +0.9357, +0.0392, -0.6858, -0.0939, +0.5365, -0.1688, -0.7388, -0.0071, -0.3334, +0.1075, +0.2025, -0.3026, +0.3052, -0.2410, -0.0626, +0.2712, -0.0920, -0.0153, +0.2765, -0.0545, +0.2745, +0.0655, +0.3442, +0.3462, +0.3263, +0.2914, -0.5316, +0.3494, +0.0859, -0.2454, +0.2092, -0.1163, +0.3634, +0.2525, +0.5571, +0.2256, -0.5412, -0.0111, +0.0994, -0.0691, +0.3054, +0.2804, -0.0680, -0.1856, -0.1495, +0.4269, +0.2529, +0.2101, -0.0740, -0.8437, +0.3873, -0.1279, +0.0644, -0.4079, -0.5276, -0.3977, -0.4074, -0.4552, -0.3181, +0.1966, +0.1559, +0.0435, -0.1219, -0.1680, +0.0140, -0.4742, -0.2062, +0.2468, +0.0087, -0.2799, -0.2163, +0.1322, +0.1842, -0.3525, +0.1758, +0.4053, -0.0979, -0.2324, +0.4251, +0.0993, +0.1651, -0.2595, +0.1306, -0.0781, +0.1477, -0.4104, -0.1264, +0.1643, +0.3303, -0.1632, -0.5046, +0.0847, -0.0272, +0.3258, +0.0115, -0.2498, -0.0496, -0.0365, +0.2946, -0.2972, -0.5459, +0.3055, -0.0819, -0.1421, +0.1174, -0.3425, -0.0407, +0.1862, -0.0683, -0.3621, -0.1234, +0.1474, +0.0456, +0.2276, -0.2268, +0.7288, +0.0816, +0.1983, +0.1715, -0.1798, -0.5754, +0.1822, -0.1222, +0.3782, +0.1634, -0.3839, -0.1345, -0.1396, -0.4157, +0.7586, +0.0151, +0.2993, +0.6449, -0.2801, +0.0825, +0.0071, -0.2395, -0.2420, +0.3180, -0.6414, +0.1926, -0.3371, -0.2227, -0.1492, -0.2123, -0.0785, +0.4464, -0.6735, +0.7092, +0.2349, +0.2622, +0.2318, +0.2083, +0.2080, -0.6163, +0.5206, -0.2141, -0.1516, +0.3485, +0.2487, -0.3222, +0.2153, +0.4927, +0.0316, -0.0842, +0.2031, +0.4124, +0.0955, +0.2378, +0.1805, -0.3313, -0.0765, -0.2072, +0.1117, +0.4379, +0.4960, +0.1179, +0.5476, -0.4134, +0.1773, +0.3737, -0.0206, -0.3819, +0.0122, -0.3059, -0.3299, +0.1291, -0.2483, -0.0893, -0.0693, -0.1249, +0.3299, -0.4633, +0.3046, +0.1212, -0.1704, +0.2537, -0.1089, +0.1156, -0.0764, -0.1748, +0.4580, +0.2688, -0.0216, -0.3047, +0.0361, +0.0442, -0.4634, -0.0529, +0.7424, +0.0897, -0.4915, -0.2530],
-[ -0.2950, +0.4745, -0.2429, +0.2752, -0.4050, -0.0669, -0.1100, -0.2696, +0.5789, -0.3232, -0.6611, +0.0717, -0.5163, +0.1445, -0.0622, -0.0038, -0.2640, +0.3361, +0.1008, +0.4852, -0.5955, -0.1323, +0.3321, +0.3346, -0.3011, -0.0732, -1.1028, +0.0692, -1.0819, +1.2074, -1.0188, -0.2155, +0.2934, +0.0449, +0.0060, -0.8519, -0.2445, +0.3793, -0.2954, -0.1761, +0.1100, -0.1667, +0.1866, +0.0724, +0.1035, -0.1747, +0.1722, -0.3217, +0.8777, +0.5600, -0.4940, +0.0429, +0.2103, -0.0161, +0.0652, -0.0538, -0.6381, +0.0505, -0.2626, -0.8758, -0.8780, -0.3226, +0.3723, -0.0063, +0.3529, -0.2120, -0.8369, -0.4227, +0.0098, +0.6233, -0.0428, -0.0706, +0.0185, -1.4554, -0.2413, +0.1361, -0.0933, -0.2917, -0.7164, -0.2296, +0.2872, -0.6325, -0.4693, +0.5704, +0.2275, +0.1236, +0.0047, +0.2918, +0.3270, -0.3250, -0.6201, -0.2348, +0.3860, -0.0198, +0.7052, -0.5551, +0.8388, -0.0369, -0.5169, -0.3586, +0.3014, -0.1938, +0.2685, -0.0955, -0.1103, +0.2058, -0.3227, +1.0233, -0.4240, +0.1558, +0.2731, +0.0126, +0.5597, -0.0101, -0.1268, -0.3800, +0.1101, +0.2421, -0.2984, -0.2336, +0.1988, +0.3700, -0.4579, -0.0235, -0.1603, -0.7767, +0.2749, -0.5447, +0.0028, +0.0438, -0.4079, +0.1064, -0.2033, -0.1493, -0.2249, +0.2252, -0.2091, -0.2542, -0.7724, +0.2091, +0.0220, -0.2310, -0.1476, -0.3213, +0.1362, -0.2202, +0.3902, -0.1610, -1.1772, -0.2014, +0.3702, +0.0760, -0.3432, +0.2867, -0.4002, -0.5128, +0.6702, -0.3667, -0.0299, +0.1372, -0.4944, +0.3034, +0.3064, -0.1679, +0.2280, -0.5870, -0.2718, -0.5096, -0.2144, -0.9115, -0.4486, -0.0969, -0.1706, -0.2283, +0.0728, -0.0999, +0.4275, -0.0496, +0.2265, +0.6409, +0.5212, -0.2511, -0.0128, -0.5112, +0.7315, -0.6277, -0.8890, +0.1119, -0.0329, -0.4842, +0.3657, -0.0832, -0.0453, -0.4431, -0.7345, -0.4028, -0.6844, +0.2773, -0.0776, +0.5961, +0.2588, -0.1628, -0.2956, +0.6240, -0.0442, -0.1976, -0.0601, +0.0487, +0.1059, -0.4802, +0.2312, +0.1878, -0.1641, -0.3063, +0.0779, -0.5947, +0.3276, -0.1574, +0.0518, -0.8603, -0.6282, +0.0159, +0.2217, -0.0711, +0.4798, +0.0434, -0.2916, -0.1463, +0.0058, -0.0726, -0.1971, -0.1869, -0.6205, -0.2644, -0.8322, +0.5034, -0.0311, +0.2060, -0.2229, -0.0838, -0.4383, -1.3797, +0.0462, +0.3815, -0.6875, -0.0992, -0.1150, +0.5152, -0.9405, -0.1500, -0.1374, +0.1917, -0.5055, -0.9638, -0.3250, -0.2241],
-[ -0.1536, -0.3932, -0.1488, +0.0040, -0.1288, -0.1545, -0.9172, -0.2805, +0.3230, +0.1461, -0.1107, +0.2029, +0.1632, -0.2643, +0.2472, +0.3046, +0.2814, -0.1184, -0.5096, +0.0984, -0.3366, +0.2242, -0.0239, +0.4157, +0.2858, +0.1108, -0.0776, -0.1283, -0.2030, +0.1134, -0.0902, -0.1824, +0.0418, +0.3266, +0.4316, -0.2477, +0.2924, -0.0527, +0.1449, +0.2986, +0.2485, +0.1540, +0.0001, -0.8476, -0.0689, -0.1016, +0.3742, -0.1236, +0.2377, +0.3154, +0.1240, +0.2560, +0.5795, -0.3371, +0.3826, -0.2159, -0.3485, +0.1224, -0.7865, -0.3446, -0.2398, -0.2691, -0.0612, -0.2650, +0.4368, -0.7490, +0.1430, -0.6888, -0.1218, +0.1478, -0.1616, -0.4055, -0.0134, -0.2593, -0.5647, +0.1908, -0.6317, +0.7954, +0.0961, -0.5094, +0.5672, +0.1861, -0.0810, +0.6770, +0.5015, +0.6221, -0.4789, +0.2531, +0.1142, -0.3287, -0.0953, +0.1372, +0.4031, +0.0750, -0.0161, -0.2726, +0.5245, +0.3697, -0.6535, -0.4510, +0.0919, +0.0658, -0.4687, -0.0160, -1.0360, +0.3085, +0.1988, -0.0155, -0.0580, +0.6356, +0.4824, -0.0580, -0.6040, +0.1401, -0.5050, -0.3169, -0.0570, +0.2261, -0.2034, +0.2546, +0.1917, -0.2450, -0.5480, -0.0658, +0.4291, -0.0303, -0.4937, -0.4524, -0.0388, +0.3961, +0.4950, +0.0312, -0.2034, +0.5666, -0.1002, -0.5486, +0.0753, +0.0175, -0.7026, +0.3155, -0.0880, +0.2177, +0.0881, +0.2664, +0.0051, -0.2471, +0.4793, -0.2982, +0.1036, +0.1263, +0.0034, -0.4423, +0.0933, +0.3059, +0.4064, -0.3276, +0.0026, +0.0185, -0.6529, -0.6750, -0.5380, +0.1447, +0.1747, +0.3788, +0.1551, -0.0605, -0.6776, +0.2446, +0.5547, -0.0101, +0.1820, +0.1259, -0.0514, +0.0479, -0.2650, -0.1059, -0.1688, -0.1912, -0.3360, +0.2134, +0.0543, +0.5636, +0.3412, -0.5392, +0.0621, +0.4772, -0.3313, -0.4376, +0.0272, +0.1554, +0.3807, +0.4939, +0.3175, -0.4498, +0.5755, -0.0546, +0.0159, +0.0351, +0.0451, +0.3587, +0.0944, -0.0031, -0.0826, +0.2568, +0.5953, -0.6936, +0.1513, +0.0973, -0.0282, +0.1344, +0.1280, +0.0350, +0.2338, -0.0971, +0.2113, +0.0762, -0.6498, -0.7180, +0.6955, -0.6532, +0.2342, +0.3941, +0.3652, +0.0793, -0.0786, -0.0365, -0.0705, +0.3362, +0.0218, +0.3218, +0.1325, +0.0795, +0.0799, -0.3366, -0.0008, -0.7087, +0.1497, +0.1490, +0.2054, -0.3338, +0.2178, -0.5476, +0.0694, -0.3220, -0.2363, -0.6905, -0.0137, -0.0039, -0.3057, -0.0075, -0.2926, +0.3981, +0.1954, -0.6497, -0.6387, -0.5863],
-[ -0.0360, +0.2954, -0.0415, -0.1861, -0.1073, -0.0619, +0.0758, +0.2595, -0.1324, +0.0786, -0.4354, -0.2461, -0.1916, -0.2344, -0.1291, +0.2328, +0.3387, -0.0731, -0.6766, +0.1840, +0.0911, -0.1266, -0.0519, +0.1181, +0.1365, -0.0523, -0.1781, +0.2005, +0.1115, +0.1210, +0.0721, -0.1915, +0.0981, +0.0564, -0.4853, +0.2200, +0.1986, +0.2435, -0.0983, +0.2328, +0.0097, +0.2252, -0.3074, -0.2446, -0.1512, +0.0477, -0.1672, -0.1571, -0.3081, -0.0384, +0.1514, -0.0964, -0.1442, -0.3555, -0.4037, -0.3527, +0.2746, +0.0331, +0.3087, -0.4382, -0.1313, +0.1540, -0.2501, -0.0540, -0.0858, -0.3254, +0.2537, +0.1154, +0.3133, +0.2732, +0.0159, -0.0697, +0.3618, -0.2276, +0.0914, -0.6782, +0.1307, -0.1598, +0.1400, -0.3742, -0.2462, -0.1944, -0.0343, +0.4345, +0.1273, -0.2421, +0.1062, -0.0204, +0.0289, +0.3268, -0.1223, +0.1921, -0.0763, +0.2320, -0.0406, +0.2471, -0.1578, -0.3309, +0.3415, +0.1961, +0.2112, -0.1143, +0.1991, +0.0273, +0.0975, +0.2010, -0.0719, +0.1204, +0.1723, +0.1155, -0.0569, -0.1840, +0.2899, -0.0957, +0.2138, -0.0352, -0.7646, -0.4011, +0.5825, -0.0675, -0.2865, +0.2258, -0.0888, +0.4040, +0.5791, -0.3169, +0.1193, -0.2115, +0.1814, +0.2504, -0.1733, +0.0491, +0.0677, +0.2845, +0.0169, +0.0868, -0.0024, -0.0365, -0.2270, -0.4361, +0.3346, +0.2319, -0.0769, +0.2725, -0.2883, -0.1010, +0.0275, -0.1357, +0.1794, -0.2117, +0.2064, +0.1074, -0.1082, +0.0635, +0.0389, -0.7832, +0.1141, +0.1320, +0.0181, -0.1715, +0.1375, +0.4326, +0.1225, -0.0650, -0.0209, -0.2055, -0.3685, -0.2018, +0.0845, -0.1548, +0.0742, -0.0552, -0.5630, -0.0593, -0.6809, -0.0612, -0.1252, +0.0674, +0.3169, +0.2488, -0.0968, -0.2377, -0.0607, +0.3838, -0.2299, -0.5658, -0.3862, +0.3168, -0.3866, +0.0213, +0.4963, -0.6488, -0.5193, +0.5468, +0.1999, -0.2567, -0.1807, +0.1057, -0.1875, -0.1282, +0.0276, +0.4583, -0.4058, -0.0258, -0.3120, -0.1087, -0.2016, +0.1688, -0.1348, +0.2886, -0.7916, +0.0877, +0.1170, -0.3574, -0.6124, +0.2224, +0.4414, +0.0925, -0.2001, -0.0743, -0.0906, +0.0475, -0.1264, +0.2501, -0.1218, +0.1349, +0.1751, -0.2361, +0.5184, -0.1585, +0.1610, +0.1194, -0.0824, -0.1333, +0.1845, -0.4864, -0.1342, -0.0673, -0.1059, -0.1255, +0.1713, -0.2342, +0.1031, +0.0191, +0.0026, -0.0553, -0.1135, +0.2985, +0.2850, +0.4020, -0.1087, +0.0884, -0.3541, +0.3092, +0.0849, -0.2151],
-[ +0.2371, -0.0086, -0.2611, +0.5156, +0.0931, +0.0796, +0.1728, +0.0679, -0.5360, -0.0178, -0.4290, +0.0138, -0.1435, -0.2081, -0.2986, +0.6750, +0.3418, +0.3486, -0.2263, +0.1717, -0.2510, -0.3704, +0.1700, +0.7958, +0.2257, +0.0034, -0.4423, -0.0504, -1.1018, -0.4064, -0.4251, +0.1119, -0.6379, +0.4920, +0.8266, +0.0255, +0.3594, +0.4602, +0.3663, -0.0724, -0.1700, -0.3765, +0.3345, -0.3255, -0.0887, +0.9938, -0.3264, -0.0687, -0.1137, -0.0124, -0.0392, -0.0047, +0.5795, -0.4190, +0.4339, +0.0758, -0.0027, -0.1153, +0.1485, +0.4894, +0.1099, -0.2054, +0.6032, -0.0731, -0.2392, +0.1160, -0.1188, -0.0067, +0.2892, -0.4823, -0.0291, +0.4673, -0.3526, -0.0929, +1.1909, +0.2589, -0.0504, -0.3820, -0.1289, +0.3804, +0.1888, +0.2932, -0.2874, -0.2412, -0.0845, +0.2648, -0.0194, +0.1119, +0.0614, +0.5552, -0.3978, +0.3185, -0.9749, +0.1223, -0.1325, +0.0353, -0.3382, -0.4137, -0.2405, -0.2323, +1.0141, -0.4834, +0.3897, -0.1186, -0.0549, -0.2652, -0.0160, +0.8072, +0.3652, -0.5397, +1.1077, -0.4531, +0.0320, +0.7525, +0.3837, -0.1597, -0.5915, -1.0873, +0.2604, -0.1406, +0.0787, +0.4561, +0.0474, -0.1794, +0.3019, +0.3779, +0.0220, +0.2327, -0.7537, +0.1829, -0.2856, +0.0857, -1.0650, -0.3748, -0.2974, -0.7783, +0.8731, -0.1243, -0.1016, +0.1358, -0.3743, +0.9547, -0.7992, -0.6159, -0.1482, -0.3578, +0.1896, +0.5530, +0.4486, +0.4260, +0.5332, -0.0449, +0.2954, +0.1244, +0.3628, -0.2508, -0.7484, -0.8054, -0.0311, -0.1260, +0.7015, -0.0675, -0.0999, -0.0363, -0.0300, -0.4767, -0.1877, -0.4087, -0.0022, -0.7186, -0.5304, +0.5916, +0.5709, +0.0832, -0.7458, +0.5229, +0.4158, -0.0808, -0.0479, -0.1827, -0.0359, +0.1044, -0.6888, +0.3843, +0.3503, -0.0043, -0.0708, +0.2169, -0.2123, +0.0380, +0.1926, -0.5396, +0.0643, +0.1430, +0.2271, -0.5528, +0.0703, +0.1330, +0.2271, -0.2817, -0.5850, +0.4538, -0.2435, -0.1733, +0.7802, +0.4799, -0.4109, +0.5072, -0.3197, +0.6073, +0.6545, +0.1636, +0.0254, +0.6118, -0.3745, +0.7355, -0.5632, -0.6298, -0.0379, +0.4363, -0.5521, +0.6507, -0.0700, +0.1930, -0.8462, -0.1050, -0.3672, +0.1103, +0.2060, -0.7312, -0.6317, +0.1302, +0.0955, -0.5235, +0.3899, -0.0225, -0.0077, +0.4365, +0.2099, +0.2631, -0.2255, -0.6623, +0.1293, -0.6884, -0.2619, -0.1395, -0.1443, +0.6374, +0.8680, +0.8132, +0.7087, -0.2445, +0.4986, -0.0446, -0.0006, -0.8373],
-[ -0.4495, +0.0435, +0.4813, +0.1369, -0.3641, -0.2529, +0.4496, -0.0242, -0.2999, -0.3478, -0.2722, -0.0916, +0.1491, -0.1968, -0.2539, +0.1463, -0.2696, +0.2267, +0.2962, +0.5283, +0.0416, +0.7199, -0.0238, +0.0954, -0.2894, +0.1260, +0.2921, +0.6348, -0.8794, -0.3574, +0.1670, -0.2380, -0.7382, -0.1575, -0.0566, -0.2299, -0.0549, -0.1437, +0.2151, +0.1275, +0.0698, +0.1757, -0.2951, -0.4897, +0.0375, +0.5689, +0.0023, -0.0353, -0.0830, +0.0415, -0.1865, +0.5987, +0.3522, -0.3112, -0.5514, -0.3481, -0.1245, +0.6629, -1.5164, -1.5245, -0.1184, +0.2531, +0.2720, -0.2686, -0.9922, -0.4516, -0.0557, +0.0438, -0.1536, -0.1301, -0.0277, -0.2421, -0.9948, +0.5539, -0.6173, +0.3850, +0.2736, -0.0939, +0.1821, +0.6746, -0.3509, -0.0593, -0.0309, +0.1863, -0.4364, +0.8391, +0.0684, -0.6878, +0.0378, +0.0772, +0.2807, -0.2284, -0.0043, -0.1348, -0.0927, +0.4267, -0.3053, +0.4963, +0.5246, +0.7464, +0.0170, +0.0081, +0.1008, +0.3554, -0.1083, +0.0900, -0.0259, +0.2350, +0.2738, -0.0943, +0.1602, -0.8808, -0.3479, +0.1440, -0.2565, -0.8828, -0.4877, +0.1551, -0.4075, +0.1506, -0.1975, +0.2705, +0.4446, +0.1308, -0.4963, +0.5065, +0.4221, -0.3242, +0.3413, -0.4956, +0.1187, +0.1829, -0.3531, +0.1247, +0.1899, +0.3358, -0.3549, -0.4318, -0.2254, +0.1786, +0.0941, -0.6469, -0.2490, +0.3554, -0.5808, -0.0775, -0.6145, -1.3435, +0.1474, +0.0131, -0.6835, +0.6978, +0.1364, -0.6990, -0.0145, -1.0213, -1.1805, +0.7311, +0.1982, -0.4777, -0.1177, -0.2967, -0.1379, -0.9473, -0.2823, -0.1279, -0.2873, -0.5012, -0.1892, -1.1920, -0.6524, -0.3917, +0.2036, +0.4123, -1.2438, -0.5606, -0.2587, +0.1305, +0.2363, +0.1463, -0.0899, -0.5979, +0.4246, -0.1457, -0.1571, +0.2682, -0.3809, -0.3298, +0.5987, +0.2087, +0.0190, -0.5439, -0.1221, +0.0441, +0.4264, +0.1032, -0.3863, +0.0826, -0.5298, +0.1179, +0.4471, -0.0058, +0.1359, -0.5553, -0.2015, +0.0624, +0.5981, -0.0567, +0.3412, -0.2411, +0.1909, -0.4750, +0.3180, -0.3431, -0.4751, +0.2987, +0.6077, +0.4846, +0.0018, -0.0260, -0.5347, -0.2805, -0.1223, -0.2192, +0.1721, +0.2594, -0.4876, -0.5535, +0.0242, +0.6930, -0.7116, +0.1902, -0.1624, -0.0507, -0.7388, -0.0348, -0.1045, -0.5571, -0.1837, +0.2429, +0.2504, -0.4475, -0.1865, +0.0849, +0.3409, +0.8343, +0.2234, -0.5084, -0.1988, -0.7860, -0.5043, -0.0522, +0.2207, -0.1742, +0.0785, +0.3266],
-[ -0.1545, -0.2636, +0.7711, +0.5888, +0.8420, -0.3952, +0.4993, +0.0223, +0.1174, -0.1090, -0.1476, +0.3352, +0.5241, -0.6029, -0.3128, -0.1732, -0.4034, +0.0029, -0.0042, +0.2734, +0.4653, +0.4844, +0.7529, -0.0139, -0.0961, +0.1176, +0.3521, +0.0775, +0.0548, -0.1762, +0.3629, -0.1580, -0.1869, -0.0555, +0.6377, +0.0195, +0.0749, +0.2786, +0.0565, +0.7454, +0.4380, -0.2898, -0.6027, +0.3066, +0.3890, -0.2317, +0.1276, -0.3984, -0.0154, -0.1493, -0.1296, -0.2045, -0.2730, -0.1757, +0.2943, +0.2368, +0.2421, +0.4279, -0.0585, -0.5660, -0.0633, +0.5286, +0.4202, -0.0919, -0.2269, +0.1888, +0.2327, -0.0919, -0.2479, +0.3121, +0.0653, -0.6794, +0.7241, -0.1175, -0.2181, -0.0647, +0.1438, -0.1630, -0.1400, +0.4939, +0.2837, -0.1447, -0.0997, -0.5197, -0.1330, -0.0634, -0.6257, +0.0281, -0.3211, +0.2312, -0.1216, -0.3033, -0.1893, +0.7291, -0.0157, -0.3289, -0.4493, -0.5517, -0.1759, +0.6222, -0.4931, +0.2985, -0.4296, -0.2574, -0.2905, +0.0091, -0.5682, +0.0978, +0.1111, -0.0548, +0.2864, -0.4165, +0.8250, -0.1752, -0.0190, -0.1323, +0.2348, -0.6032, -0.2997, +0.5765, -0.1065, -0.1482, +0.5952, +0.1394, +0.1673, -0.2770, +0.4918, -0.2861, +0.6747, +0.0634, -0.6803, +0.1890, +0.1198, -0.3153, +0.2313, +0.0112, +0.0932, -0.1102, -0.2010, -0.3737, -0.5680, -0.4689, +0.5138, +0.2031, -0.6002, -0.1868, +0.3376, -0.2676, -0.9375, -0.2736, -0.2545, -0.0246, +0.0679, -0.0150, -0.0617, -0.2441, +0.4709, +0.0774, +0.5169, -0.3557, +0.0490, +0.7436, +0.6572, +0.0357, -0.0924, -0.4672, -0.1624, -0.7978, -0.3220, +0.0738, +0.7238, -0.2530, +0.5674, +0.4540, -0.7096, -0.0164, -0.1263, +0.9431, -0.5657, +0.2935, -0.2642, -0.2049, -0.0366, +0.8266, -0.1993, +0.2611, -0.1295, -0.6901, -0.2303, -0.0508, +0.0599, +0.2460, -0.5177, -0.4144, -0.2723, +0.3891, -0.3817, -0.0499, -0.2704, +0.2270, +0.3747, -0.1594, -0.2215, +0.7694, -0.0915, +0.0059, -0.6710, -0.3997, -0.0833, +0.2102, +0.4514, -0.3927, +0.2041, -0.8319, -0.4655, -0.2734, -0.1729, -0.2223, -0.2689, +0.6059, -0.5239, -0.2485, -0.3970, +0.3389, -0.3576, +0.2457, +0.1344, -0.0006, +0.2879, +0.0049, +0.2234, -0.2334, -0.1920, -0.1798, -0.2480, -0.2451, +0.1456, -0.1634, -0.0665, +0.5494, +0.2914, +0.2998, -0.0831, -0.1296, +0.3089, +0.1795, -0.1477, -0.0371, -0.8516, -0.1523, -0.1577, -0.0086, +0.0418, -0.7372, +0.2951, +0.0362],
-[ -0.4565, +0.1782, +0.1290, -0.5322, -0.2860, -0.2451, -0.3503, -0.1212, -0.6014, +0.2923, -0.2355, -0.4092, -0.3082, +0.6207, -0.6511, -0.1271, -0.3121, -0.6387, -0.1085, -0.3078, +0.0726, -0.1056, -0.7585, +0.0335, -0.1210, +0.2206, +0.5102, -0.4960, -0.3887, +0.0633, -0.2038, -0.0613, -0.1608, -0.4403, +0.1844, +0.2427, -0.0712, +0.1452, -0.3168, +0.2375, +0.5895, -0.3812, +0.4553, -0.3796, +0.0759, +0.0808, -0.0043, -0.1435, -0.1343, +0.4849, -0.4057, +0.0537, -0.3170, -0.5482, -0.0744, -0.2475, +0.2786, +0.0103, +0.1002, +0.2105, +0.0228, +0.2931, -0.1969, -0.5573, -0.5076, +0.3885, +0.2231, -0.7409, -0.3342, +0.1119, +0.1228, +0.3823, -0.4331, +0.0602, +0.0816, -0.3968, -0.1841, +0.2059, +0.3797, +0.0335, -0.0525, -0.1171, -0.4932, +0.0667, -0.3642, +0.2155, -0.2907, -0.0247, -0.8014, +0.1727, +0.2656, -0.3467, -0.1870, -0.0004, +0.2753, +0.0611, -0.0361, +0.0040, +0.3672, -0.6810, +0.3802, +0.1425, -0.1164, +0.0589, -0.3594, +0.1147, -0.0726, +0.1166, +0.1405, -0.8273, -0.1676, -0.0557, -0.2434, +0.1277, +0.5011, -0.1945, -0.3558, -0.3259, +0.0800, -0.1651, +0.5381, +0.0205, +0.0540, +0.3779, -0.3028, -0.0529, -0.6128, +0.1707, -0.3605, -0.0364, -0.3162, -0.0557, -0.1434, -0.3231, -0.3164, -0.7789, +0.0809, +0.0999, -0.0837, -0.1528, +0.2895, -0.0212, -0.0732, +0.2575, -0.1690, -0.2843, +0.0976, -0.0577, +0.0625, +0.5292, -0.2402, -0.4092, -0.0631, -0.0600, +0.1563, -0.0879, -0.1808, +0.0164, -0.1146, -0.5358, -0.1802, +0.0685, +0.2012, +0.2354, -0.1941, -0.2628, +0.2707, +0.0396, -0.2286, +0.1113, -0.3468, +0.2619, +0.0130, -0.2485, -0.1131, +0.1862, +0.0415, -0.6855, -0.1715, -0.3101, +0.2030, -0.4367, +0.3013, +0.0863, -0.5386, +0.0915, +0.2793, -0.1328, -0.0632, -0.1778, +0.0966, -0.0656, +0.1870, -0.4183, +0.2612, -0.3949, -0.2119, -0.7062, -0.1619, +0.1240, +0.5384, +0.0755, +0.2566, +0.0666, +0.1773, -0.0047, +0.2708, -0.0026, +0.0031, +0.2468, -0.0893, +0.3492, -0.1193, -0.7335, +0.3597, -0.9848, -0.3577, -0.0779, -0.3795, -0.3974, +0.0866, +0.3102, -0.5583, -0.7425, +0.1512, +0.1052, -0.1454, +0.2425, -0.1251, +0.1301, -0.5012, -0.6570, +0.7020, -0.1142, -0.0283, +0.1393, +0.1112, +0.1435, -0.3354, -0.2273, +0.4505, -0.0457, -0.2140, -0.4433, -0.4714, -0.0525, -0.0225, +0.1967, -0.0158, +0.1003, +0.0867, -0.9314, -0.2636, +0.3661, -0.5848, +0.0565],
-[ -0.1112, -0.4525, +0.1614, +0.0399, +0.5304, -0.3198, -0.4914, -0.2721, -0.0057, +0.1912, +0.3123, +0.1551, +0.3333, -0.0465, -0.1155, +0.1781, +0.0136, -0.4149, +0.1566, -0.5089, -0.0009, -0.0626, -0.1944, -0.1314, -0.1063, -0.2397, +0.2927, -0.6858, +0.3245, +0.2261, -0.2639, -0.0988, -0.2489, +0.0032, +0.2910, +0.1492, -0.3025, +0.0991, +0.2780, +0.3589, -0.2876, -0.0963, +0.1392, -0.5810, -0.7109, +0.6384, +0.0976, -0.5051, +0.0422, +0.6395, +0.2289, -0.6906, +0.6869, -0.2494, +0.0840, +0.5636, +0.4438, +0.0787, +0.3340, +0.0412, +0.3545, -0.4366, -0.4846, +0.0560, -0.0517, +0.2010, +0.1060, -0.5708, +0.4587, +0.0208, +0.0620, -0.2796, +0.5296, -0.2107, +0.3797, -0.3168, +0.6043, +0.1749, +0.4162, +0.4593, -0.7969, +0.6965, +0.4833, +0.1571, -0.1353, -0.0926, -0.0610, +0.0594, -0.8100, -0.3465, -0.8444, +0.1071, -0.1125, -0.1348, +0.1900, -0.3160, -0.0849, -0.5535, +0.2228, -0.0280, -0.2032, -0.5068, -0.1945, -0.4944, -0.3757, +0.2530, +0.2590, +0.0177, -0.3995, +0.1453, +0.4474, -0.2493, -0.1195, +0.1928, +0.9237, +0.0135, -0.6365, +0.1230, -0.3276, -0.0830, +0.2579, -0.3146, -0.1939, +0.4047, -0.0049, -0.3189, -0.0661, +0.1790, -0.2341, +0.1557, +0.2112, +0.1689, +0.1799, +0.0173, -0.3950, -0.5424, +0.0521, -0.3810, +0.1368, +0.1286, -0.4210, +0.4710, +0.0680, +0.2577, -0.2847, +0.2011, -0.0889, -0.3098, +0.3893, +0.1595, -0.2627, -0.1097, +0.1000, +0.1536, +0.3436, -0.1249, -0.4113, +0.2356, -0.0156, +0.1952, -0.0951, -0.3113, -0.3086, +0.4344, +0.0703, -0.2342, -0.3115, -0.1909, +0.4157, -0.3784, -0.1582, +0.1850, -0.2052, +0.1344, -0.0284, -0.4493, +0.0625, -0.1307, +0.3509, -0.0012, +0.8178, -0.2761, +0.7609, +0.1238, +0.0534, -0.2405, -0.2435, -0.1970, +0.0690, +0.4685, +1.0030, +0.6136, +0.6953, +0.0036, +0.5347, -0.4444, -0.1588, -0.4121, -0.3876, +0.3125, +0.2208, -0.0865, -0.2455, +0.0981, +0.4245, -0.5058, +0.2232, +0.1998, +0.1941, -0.2040, -0.0108, +0.2213, +0.0371, -0.3715, -0.4102, -0.1646, -0.1220, +0.6978, -0.2699, +0.1139, +0.0043, -0.2600, +0.4152, -0.2855, -0.2182, +0.7740, +0.1168, +0.1696, +0.1662, -0.4700, -0.0897, -0.5900, +0.0786, +0.2272, -0.1016, +0.3904, -0.3343, -0.1979, -0.2305, -0.0750, -0.1703, -0.4604, +0.2909, -0.3099, +0.1186, -0.3282, +0.2542, +0.0348, -0.2425, +0.4281, +0.1888, -0.6300, -0.0389, -0.2371, -0.1128, +0.1885],
-[ +0.6639, +0.0702, -0.1304, -0.4967, +0.3758, -0.1061, -0.0523, -0.2161, +0.0816, -0.3597, +0.0542, +0.0536, -0.3311, -0.1367, -0.5922, -0.3262, -0.3618, -0.8526, -0.5574, -0.1029, +0.1654, -0.3574, -0.5698, -0.0729, -0.4110, +0.1946, -0.5148, -0.2157, +0.0880, -0.4988, +0.1084, -0.2813, +0.4106, -0.0524, -0.1673, -0.7740, +0.1078, +0.1820, -0.5635, -0.0145, -0.1669, +0.0116, -0.1952, +0.1940, +0.2119, -0.0359, +0.3704, +0.2859, +0.1880, -0.0113, +0.0125, +0.4600, -0.2778, +0.0657, +0.7902, -0.1208, +0.1688, -0.1355, +0.3225, +0.4388, -0.2043, -0.5396, +0.0596, -0.6605, -0.4528, -0.4741, -0.3760, +0.4426, -1.1438, -0.0723, +0.2735, -0.1089, -0.3427, -0.0726, +0.0420, -0.2223, -0.7000, -0.2843, -0.4384, +0.2913, -0.1338, -0.5119, +0.5250, -0.0908, +0.5554, +0.1226, -0.0437, +0.2352, -0.2992, -0.2623, +0.3665, -0.0842, +0.0260, +0.0963, -0.6214, -0.3901, +0.0785, -0.0952, -0.0248, -0.3269, -0.1007, +0.0385, -0.1838, -0.4408, +0.0586, +0.3316, +0.2261, +0.1234, -0.1497, -0.8627, -0.2077, -0.0247, -0.3589, -0.2200, -0.0796, -0.3080, +0.0493, +0.1684, -0.0319, -0.4871, -1.0854, +0.0254, -0.3065, -0.1966, -0.3679, +0.1414, -0.0580, -0.2385, +0.2040, +0.0429, +0.1307, -0.8378, -0.1806, -0.4079, +0.4829, -0.5028, -0.1583, -0.4943, -0.0458, -0.1000, -0.5349, +0.2198, -0.1819, +0.4630, -0.0457, +0.0766, +0.3230, +0.6088, -0.0285, -0.3704, -0.3567, -0.3936, -0.1021, +0.4362, -0.1535, -0.1291, +0.0761, -0.3656, -0.3966, -0.4077, +0.6730, -0.0519, -0.6391, +0.2173, -0.2885, +0.2854, -0.2147, +0.1787, +0.2168, -0.4785, +0.1279, -0.0088, -0.4949, -0.8904, -0.6216, -0.1224, -0.2990, -0.4242, +0.3770, -0.3137, +0.0934, -0.5931, -0.2990, +0.3737, -0.6431, -0.1939, -0.2330, -0.1893, -0.2435, -0.1946, -0.0799, -0.1570, -0.5438, +0.0471, +0.2994, +0.2884, +0.2453, -0.6113, +0.4730, +0.2125, -0.6701, +0.0616, -0.2903, -0.2056, +0.2428, -0.1759, -0.8047, -0.2883, -0.6022, -0.4987, -0.2738, +0.1943, +0.2759, -0.3151, -0.3028, -0.0858, -0.6176, -0.4943, -0.2982, +0.3932, -0.3796, -0.1953, -0.3258, +0.0818, +0.1012, +0.0787, +0.3576, -0.5450, -0.2397, +0.1890, +0.4258, +0.1003, -0.4817, +0.3342, -0.1117, -0.1249, -0.0892, -0.1996, +0.0142, -0.0099, +0.0581, -0.7400, -1.2277, +0.0064, +0.0318, -0.4549, -0.0940, -0.0705, -0.0682, -0.2008, +0.1345, +0.5597, -0.2645, -0.0604, -0.3416, -0.2864],
-[ -0.0028, -0.0898, -0.4007, +0.4676, -0.1535, +0.2170, +0.0180, -0.0810, +0.5363, +0.0032, +0.3269, -0.1136, -0.1009, -0.2048, -0.3535, +0.4315, +0.1272, -0.1089, -0.5999, +0.0208, +0.0936, -0.1613, +0.4883, +0.1000, -0.2159, +0.4113, -0.0223, +0.6549, -0.3449, +0.0485, +0.2421, -0.4096, +0.0556, -0.4409, -0.4039, +0.0445, +0.3850, +0.0889, +0.0026, -0.1220, +0.3864, +0.3739, +0.1646, +0.5352, -0.0789, -0.0276, +0.2423, -0.3945, +0.1482, -0.0888, -0.1047, +0.6800, -1.1911, -0.7345, +0.5066, +0.0200, -0.0569, -0.0783, +0.1944, +0.4563, +0.1254, +0.3341, +0.8698, +0.3332, +0.4348, -0.3389, -0.4066, +0.2644, -0.2798, -0.0424, +0.1193, +0.0831, -0.7383, -0.0038, +0.2701, -0.0101, -0.6089, +0.1930, -0.1343, +0.5417, -0.3725, +0.0902, -0.1180, +0.3325, +0.3892, +0.1325, +0.9921, -0.0492, +0.2405, +0.2264, +0.2860, +0.0994, +0.0847, +0.9777, +0.0296, +0.4773, -0.1188, +0.6873, +0.5104, +0.0378, -0.2487, +0.3510, -0.3927, -0.0066, -0.3028, +0.1421, +0.0103, -0.0162, -0.2787, -0.3621, +0.7588, -0.1543, -0.1931, -0.2935, +0.1967, +0.2697, +0.4855, +0.5111, +0.1222, -0.3406, -0.2549, +0.1323, -0.0580, -0.1195, -0.1470, +0.6529, +0.2743, -0.0332, +0.1778, +0.2766, +1.1343, -0.3576, -0.6760, -0.2872, -0.8008, -0.0279, -0.0802, -0.0202, -0.1213, -0.5831, -0.2366, -0.4305, +0.3012, -0.1903, +0.2265, -1.0208, -0.1138, -0.1229, -0.7328, +0.1313, -0.1682, -0.7280, -0.4280, +0.6649, -0.3497, +0.2514, -0.2782, -0.0772, -0.4907, -0.0475, +0.0505, +0.6654, -0.5389, -0.2224, +0.0454, +0.0665, -0.2657, -0.1661, +0.3128, +0.5484, +0.2041, -0.0153, -0.5880, +0.1951, -0.1350, +0.2217, +0.2999, -0.1773, -0.1246, +0.2815, +0.3207, -0.3308, -0.0356, -0.2777, -0.1428, -0.4047, -0.1064, -0.0044, +0.4314, +0.0760, -0.0951, -0.1282, -0.0204, -0.0225, -0.4182, +0.3567, -0.0197, -0.3210, +0.7637, +0.2886, -0.3230, +0.0109, +0.3165, +0.0088, -0.3390, +0.6050, +0.0018, +0.0298, -0.2559, -0.2123, +0.1931, +0.0521, +0.1330, +0.2284, -0.4433, -0.2233, +0.6624, -0.0413, -0.5773, +0.0100, +0.0626, -0.5787, +0.5139, -0.7480, -0.1786, +0.2617, -0.1276, -0.0327, +0.3131, +0.2643, -0.0968, +0.1409, -0.3147, +0.6659, -0.4285, -0.2072, -0.0548, +0.1973, +0.0799, +0.4575, +0.3171, -0.2175, -0.2405, -0.0591, -0.2228, +0.1632, -0.0162, -0.1352, -0.2736, -0.6039, -0.5106, +0.1240, +0.3908, +0.0334, -0.1636, -0.2803],
-[ +0.0894, -0.1313, -0.5267, -0.3037, +0.0560, -0.0589, -0.0811, +0.2186, -0.0574, -0.2032, +0.4292, +0.1375, -0.1661, +0.1344, +0.1416, -0.2339, -0.1400, -0.1990, -0.2908, +0.0187, -0.1002, -0.5780, +0.0609, -0.2537, -0.2208, -0.0817, -0.0625, +0.3360, +0.3056, -0.0835, +0.0158, +0.1561, -0.5691, -0.0537, -0.0060, +0.0156, -0.0768, +0.1259, +0.0801, -0.3652, -0.2935, -0.0957, -0.3882, -0.0806, -0.1767, -0.1223, -0.2980, -0.0602, +0.0748, +0.1073, -0.2273, -0.0432, +0.0205, -0.1205, +0.0701, +0.2412, -0.0545, +0.4093, +0.1213, -0.1339, +0.2695, -0.1651, -0.3032, +0.2259, +0.2772, -0.4091, -0.2053, +0.1683, +0.3017, +0.0795, -0.0465, -0.1519, +0.1913, -0.0878, -0.3027, -0.1999, -0.1650, +0.0766, +0.3527, +0.0193, -0.0428, -0.3020, +0.1492, +0.0307, -0.0845, -0.3916, +0.2446, -0.2790, -0.1062, +0.0129, -0.0355, -0.0179, +0.0488, -0.1491, -0.1360, -0.5012, -0.1146, -0.6466, -0.0591, -0.2473, -0.0138, -0.0251, -0.3729, -0.4206, +0.0316, +0.4263, +0.1346, +0.0591, -0.0302, -0.3306, +0.2092, +0.1464, -0.2104, -0.0266, -0.5471, +0.3618, -0.0120, -0.0801, -0.6509, -0.1565, +0.2461, -0.2794, +0.1373, -0.3501, -0.0141, -0.3659, -0.0823, +0.0433, -0.4913, +0.1867, -0.1787, -0.2530, -0.0858, +0.0631, +0.4656, -0.0758, +0.1346, +0.3409, -0.0766, +0.1549, -0.1865, +0.0163, +0.1177, -0.1294, -0.0539, -0.1648, -0.3973, -0.0093, +0.0441, +0.2224, +0.2009, -0.1244, +0.2471, -0.1195, +0.2794, -0.1653, -0.0777, +0.2899, -0.0727, -0.0180, -0.1459, +0.1405, +0.2990, -0.3099, -0.0493, -0.0159, -0.3430, +0.2833, -0.0530, -0.1604, -0.0790, -0.0641, +0.4894, +0.1193, +0.0302, +0.0596, -0.3592, -0.0790, -0.3708, +0.1281, -0.1684, -0.1438, +0.1309, -0.1472, +0.0636, +0.0655, -0.2718, -0.3099, -0.2452, -0.3439, -0.2408, -0.2503, +0.0348, +0.1378, -0.1481, +0.0495, -0.0593, -0.2129, -0.1782, -0.1991, -0.0801, -0.0231, -0.2544, +0.3121, -0.6851, +0.1245, +0.1280, +0.0607, +0.1181, +0.2037, -0.0248, -0.0015, +0.2572, +0.1095, -0.4549, +0.0161, -0.0200, -0.3575, -0.3766, -0.1733, -0.1862, -0.2414, -0.4685, -0.1836, -0.3641, -0.1041, +0.0687, -0.1580, +0.1813, -0.0349, +0.2789, +0.1194, -0.2338, +0.3210, +0.0017, -0.4004, +0.2656, +0.2545, -0.2993, +0.1564, -0.3086, +0.0336, +0.0466, -0.0968, -0.2550, +0.2261, -0.0329, -0.1153, -0.1083, -0.2512, +0.0684, -0.1142, +0.1333, -0.0650, +0.2348, +0.3584],
-[ +0.4732, -0.1606, +0.6582, -0.2787, -0.4086, +0.4893, -0.4595, +0.1070, -0.2998, -0.3381, +0.4717, +0.0695, +0.0694, -0.1232, -0.3385, +0.5312, -0.7533, -0.6750, +0.5398, -0.0136, -1.7436, -0.4604, +0.1915, -0.0144, -0.8186, +0.6056, -1.0079, -0.6666, -0.5122, +0.1853, +0.3952, +0.3490, -0.4289, -0.8478, -0.7121, -0.3623, -1.4662, +0.2201, +0.5418, -0.3230, -0.6259, +0.1299, -0.6091, -0.0094, +1.4666, -0.0719, -0.9252, +0.3602, +0.1149, +0.3030, -0.2658, -0.4848, -0.1590, -0.5769, +0.0430, +0.2988, +0.0350, +0.5103, +0.7586, +0.2644, -0.0157, -0.6312, -0.2371, +0.1164, -0.9660, -0.9717, -0.1487, -0.1394, -0.5667, +0.3729, -0.3456, +0.3801, +0.4136, +0.3297, +0.6520, +0.3534, +0.5755, +0.4200, +0.3596, -0.0550, +0.0103, -0.2814, +0.1925, -0.1471, +0.2325, -0.1932, +0.2907, +0.9803, +0.4304, -0.2703, +0.4069, +0.0140, +0.3637, -0.1827, +0.2379, -0.0605, +0.1779, -1.0385, -0.3431, +0.3169, +0.8508, -0.5855, +0.4819, -0.2676, -0.2594, +2.1076, -1.0596, +0.4236, -0.3660, +0.6359, +0.4310, -1.0984, -0.9941, +0.8232, +0.0712, +0.3779, -0.7529, +0.0185, +0.2977, -0.6670, +1.1753, +0.0192, -0.2653, -0.9421, -0.1875, -0.4444, +0.2785, +0.6543, -0.0886, +0.1154, -0.7106, -0.5924, -1.0759, -0.0793, -0.5093, +0.2754, +0.4661, +0.6569, -0.0456, +0.8637, -1.5313, -0.3027, +0.2600, -0.4001, -0.0731, -0.9646, -1.3496, -0.5664, +0.6005, +0.7289, +1.0823, +1.0336, -1.1099, -1.7396, -0.0138, -0.7396, -0.4744, +0.5657, -0.4586, +0.7394, +0.3641, +0.1860, -0.2638, -0.0889, -0.1331, -0.8559, -0.1339, +1.0111, -0.7366, -0.8960, +0.9621, -0.2681, +0.3126, +0.2824, +0.1901, +0.1823, +0.1325, -0.3736, -0.2325, +0.3365, +0.2287, -0.0605, +0.2358, +0.0979, +0.5472, -0.2089, -0.0947, -0.2847, -0.4178, -0.4625, +0.9301, -0.4498, -0.1724, +0.1641, -0.2897, +0.7335, +0.1285, +0.5672, +0.0944, -1.2222, -0.4112, +0.0133, -0.3927, +0.7011, +0.1873, -0.9979, -0.6419, +0.0528, +0.2162, -0.9908, -0.0299, -0.0079, -0.1600, +0.4196, -0.5376, -0.5944, +0.5843, -1.4553, -0.3420, -0.0111, -0.3172, -0.7095, +0.3238, -1.5251, -0.6495, +0.1290, +0.5290, +0.8379, -0.0186, +0.3914, +0.6254, -0.9157, +0.5162, -0.7548, +0.2652, -0.1713, +0.6144, +0.3886, -1.0187, +0.4616, -0.1282, +0.1885, +0.4676, -0.5539, -1.3952, +0.1609, -1.3798, -0.9262, -0.0862, +0.4384, +0.1909, +0.6169, -0.2354, +0.0560, -0.4729, +0.5102],
-[ -0.2623, -0.5500, -0.8934, -0.5827, -0.3098, +0.0409, -0.5424, +0.1890, +0.2709, -0.4536, -0.2234, -0.0921, -0.0883, -0.1581, -0.2704, +0.1434, +0.5878, -0.1153, +0.3998, -0.5189, -0.0398, -0.8323, -0.2917, -0.3440, +0.1746, +0.1797, -0.0405, +0.1575, -0.4795, -0.0746, -0.0424, -0.3207, +0.5470, +0.0724, +0.6805, -0.1680, +0.8424, -0.1252, -0.9788, +0.5110, -0.3236, -0.0378, -0.3926, +0.3545, +0.6891, +0.0941, -0.4593, +0.3817, -0.4011, -0.1867, +0.1241, -0.0399, +0.0399, +0.4695, +0.0817, +0.2802, -0.2934, +0.1742, +0.2839, -0.6293, -0.0622, -0.3654, +0.3869, +0.0138, +0.3932, +0.3312, +0.0329, -0.5800, -0.2554, -0.0443, -0.1353, +0.3262, -0.1477, +0.3355, +0.4989, +1.0883, -0.1484, -0.0356, -0.1507, +0.0998, +1.0423, +0.8652, +0.0962, -0.7090, +0.0557, +0.4462, -0.5165, +0.3132, -0.1200, -0.7751, -0.2078, +0.0040, +0.1418, +0.0903, +0.1258, -0.7325, -0.0397, +0.2254, -0.0790, +0.6261, -0.1110, +0.0273, -0.3680, -0.6284, -0.5848, -0.0510, -0.3352, -0.4350, +0.7128, -0.0535, -0.3427, +0.1700, -0.1675, +0.5452, -0.0314, +0.0352, +0.0463, -0.2302, +0.2769, -0.1505, -0.0960, -0.1267, +0.0688, -0.3363, -0.3650, +0.1264, -0.6723, -0.1585, -0.3805, -0.5702, +0.3047, +0.0726, -0.1396, +0.5884, -0.5775, -0.3510, +0.4869, -0.2920, +0.2757, -0.7034, -0.5380, +0.2403, +0.4119, +0.0880, +0.4356, -0.1930, +0.0740, -0.1306, -0.5824, -0.1174, +0.3561, +0.0697, +0.1986, -0.1393, +0.6282, -0.6205, -0.1164, +0.2631, +0.2449, +1.0627, -0.6674, +0.7347, -0.0015, -0.2780, +0.0399, +0.2840, -0.5423, -0.3100, -0.2520, -0.5139, +0.2372, +0.0145, -0.3361, +0.2923, +0.0887, +0.0496, +0.1057, +0.5594, -0.0216, +0.0017, -0.0902, -1.1624, +0.2974, -0.0896, +0.0014, -0.1058, -0.2326, -0.4239, -0.6721, -0.1929, -0.0481, +0.2104, +0.4768, +0.2210, -0.2804, -0.0495, -0.2478, +0.0522, -0.0218, -0.0644, +0.2885, -0.2548, +0.0693, -0.4215, -0.0662, -0.4346, +0.2659, +0.0776, -0.1521, -0.4458, -0.0882, -0.0582, +0.8444, -0.5577, -0.3347, -0.0834, -0.6310, +0.3409, -0.3974, -0.6091, +0.3574, +0.2273, -0.4237, +0.1367, -0.1327, +0.0987, -0.9152, +0.5622, -0.0676, -0.6499, +0.3606, +0.4399, -0.3099, -0.6367, +0.3527, +0.0088, -0.2020, -0.1820, +0.0846, -0.6191, +0.1769, +0.3711, -0.1939, -0.3972, +0.0426, +0.0640, +0.5209, +0.2030, +0.3277, -0.5862, +0.1393, -0.2087, +0.5449, +0.1910, +0.0607, -0.1638],
-[ +0.3326, -0.2192, -0.1261, -0.7672, -0.0726, +0.0749, +0.1123, +0.2187, +0.0284, +0.2690, -1.0084, +0.3601, -1.6456, +0.1946, +0.3244, -0.8317, +0.0052, +0.3999, -0.0599, -0.2789, +0.4927, -0.0105, +0.6244, +0.6483, +0.2249, +0.2885, -0.0790, +0.6272, +0.2172, +0.7959, -0.3381, -0.4279, +0.1254, +0.8320, -0.3991, -0.4147, +0.0855, -0.0195, -1.0794, -0.2158, +0.6702, +1.1494, +0.5560, +0.2204, +0.5365, -0.4700, +0.1475, +1.1094, -0.3511, +0.0416, -0.2719, +0.1314, +0.6246, +0.5698, -0.1744, +0.2456, -0.5748, +0.2735, +0.2794, -0.3873, -0.3518, -0.4836, -0.9445, -0.7092, -0.1050, -0.5319, -0.0415, -0.4103, -0.8021, -0.4810, -0.3130, +0.2015, -0.2658, +0.7122, -0.9539, -0.1401, +0.3261, -0.1090, +0.1664, +0.8160, +0.8901, -0.4834, -0.9219, +0.2213, +0.7483, -0.0979, +0.4085, +0.6627, -0.0915, -0.1968, -0.3771, +0.0993, +0.7787, +0.2916, -0.1056, -0.9319, -0.6357, -0.2824, -0.2307, -0.0626, +0.4354, +0.1002, -0.4637, -0.6664, -0.5818, +0.3427, -0.1501, -0.4927, +0.1051, +0.9686, +0.4639, +1.0309, +0.4054, +0.5349, -0.5620, +0.0207, -0.0858, -0.6535, +0.4465, -0.0544, +0.4589, -0.3666, +0.5363, -0.2222, -0.2747, +0.3050, -1.1584, +0.1305, +0.3800, +0.8084, +0.6366, +0.2893, +0.1092, -0.0087, +0.9411, -0.5530, -0.4102, +0.2868, +0.3403, +0.1751, -0.2593, -0.2496, +0.0389, +0.9976, -0.4269, +0.1595, +0.6351, +0.2016, -0.0273, +0.3620, +0.8245, +0.5060, -0.2563, +0.2884, -0.3763, -0.3475, -0.6837, +0.1288, -0.4847, +0.2518, -0.6590, +0.4302, +0.0284, -0.3004, +0.1761, +0.0353, -0.3861, +0.6957, +0.1880, -0.5363, +0.7874, -0.0366, -0.1364, +0.5343, +0.6380, +1.6283, +0.0523, +0.5491, +0.3073, +0.7776, -0.5433, -1.0954, -0.4400, +0.3572, +0.4507, +0.2235, +0.4191, -0.0030, +0.2167, +0.0241, -0.2959, -0.1926, -0.0548, +0.6186, +0.1567, +0.0447, -0.1605, -1.2927, -0.0799, -0.8015, +1.0467, +0.1503, -0.1165, -0.3578, +0.0835, +0.3518, +0.6534, -1.6320, -0.4974, -1.2648, +0.0539, -0.7212, -0.4364, -0.5707, -0.3332, +0.8711, -0.2449, +0.2042, +0.1523, +0.2714, -0.1228, -0.3889, -0.8836, -0.0737, -0.1996, +0.3627, +0.1584, +1.3699, +0.5986, +0.4335, +0.7518, +0.4746, -0.6336, -0.6632, -0.1306, -0.2863, -1.0185, -0.5354, +0.0729, -0.2683, +0.2188, +0.0261, -0.3163, -0.0834, +0.0905, +0.2801, +0.6009, -0.2417, -0.5704, -0.4598, -0.5413, -0.0954, -0.1351, +0.9718, +0.4152, -0.8522],
-[ -0.1711, -0.1063, +0.0715, -0.3206, +0.1503, +0.3791, -0.1802, -0.0566, +0.2265, -0.1800, -0.0480, -0.3589, +0.0047, +0.2423, +0.3973, -0.1336, -0.1008, -0.2685, -0.0073, -0.0393, -0.1822, -0.3134, +0.3055, +0.2837, +0.2647, +0.0811, -0.0392, +0.1127, -0.1816, +0.1328, +0.0866, -0.1994, +0.0885, +0.0459, +0.6323, -0.0745, -0.1675, -0.1628, -0.2264, +0.2328, +0.2803, +0.3329, -0.0857, -0.0834, +0.0058, +0.2387, -0.0153, +0.1075, -0.1300, -0.0398, +0.0271, -0.0736, +0.0525, -0.3868, +0.1940, -0.4156, -0.0022, +0.0494, -0.0423, -0.2591, -0.0749, +0.0908, -0.0273, +0.1700, -0.1291, +0.1797, -0.2058, -0.1395, -0.4264, -0.2898, -0.1726, -0.0213, +0.1089, +0.0923, -0.0280, +0.2194, +0.0694, +0.4390, -0.0365, +0.2571, +0.0334, -0.0207, -0.0985, +0.0378, +0.0380, -0.0329, +0.3669, -0.1063, -0.1286, -0.0433, +0.1327, -0.0711, +0.4962, -0.2371, -0.1473, -0.0841, -0.1811, +0.0358, +0.1089, -0.1886, -0.1936, -0.2577, -0.0633, +0.4586, -0.1914, +0.2095, -0.1539, +0.0479, +0.2096, -0.0109, +0.4658, +0.1918, -0.1946, -0.4688, +0.0825, -0.0409, -0.0128, +0.0776, +0.0104, -0.1060, +0.0913, +0.1380, -0.3030, +0.2420, -0.1261, +0.0273, +0.2801, +0.1011, -0.2845, -0.0056, +0.0449, -0.2219, -0.3166, -0.0995, +0.3312, +0.0378, +0.3752, +0.1273, -0.0218, +0.1467, +0.7130, -0.1773, -0.0020, +0.0221, -0.2904, -0.3301, -0.0714, -0.3943, -0.2730, -0.3627, +0.0126, +0.1011, +0.0552, -0.0592, +0.1397, +0.4257, -0.5063, -0.1791, +0.3605, -0.0214, +0.0775, +0.3434, -0.4018, -0.1175, +0.0876, -0.2879, +0.1134, +0.4348, -0.0254, +0.0863, +0.1131, +0.1835, +0.2308, +0.3229, +0.3254, +0.4667, -0.3888, -0.1415, +0.0981, +0.0166, -0.1201, +0.2934, +0.3937, +0.2242, -0.5198, -0.3040, -0.0367, +0.1663, -0.3662, +0.1434, -0.2027, +0.0861, +0.0767, +0.2295, -0.0056, +0.0315, +0.0541, +0.2837, -0.1139, +0.0808, -0.0422, +0.0673, +0.1571, -0.3419, -0.1489, -0.1222, -0.0932, -0.1747, -0.2475, +0.2277, -0.2570, -0.1233, +0.2159, +0.0146, +0.0969, +0.0559, +0.2020, -0.1456, +0.4296, -0.3832, +0.5871, +0.3385, +0.1100, -0.1362, -0.0197, -0.1770, -0.1053, -0.1967, +0.1094, -0.1991, +0.4991, -0.0012, -0.1015, -0.0932, -0.3859, +0.1861, -0.2871, +0.4395, -0.2905, +0.3829, -0.1480, -0.0701, +0.1316, +0.0267, +0.1225, +0.2529, -0.2509, -0.2783, +0.1156, +0.1564, -0.0783, -0.0978, +0.2723, +0.2160, -0.1469, +0.3120],
-[ +0.0315, -0.2696, -0.0547, +0.1758, -0.2117, +0.4463, +0.8609, -0.1051, -0.0676, -0.3982, +0.9245, -0.1324, -0.1016, +0.6617, -0.2366, -0.4399, +0.3019, +0.1689, -0.0158, -0.1818, -0.4215, +0.0936, +0.5601, -0.0098, -0.1283, -0.0398, -0.0200, +0.2282, +0.1735, +0.0721, -0.2770, -0.0388, +0.0866, -0.0641, -0.3395, -0.0183, -0.2307, +0.2022, -0.0453, +0.1410, +0.1753, -0.2238, -0.0288, +0.3948, +0.1377, -0.2461, -0.2781, +0.1382, +0.0858, +0.0087, -0.2323, +0.0826, +0.3201, +0.0201, +0.1398, +0.4103, +0.1346, +0.1654, -0.2246, +0.4345, -0.0825, +0.0604, -0.4920, -0.1070, -0.2675, +0.0284, -0.6419, -0.0281, -0.1501, -0.1668, -0.0765, +0.0647, -0.0766, +0.1001, -0.1794, +0.2516, +0.4290, -0.7728, +0.2099, +0.0732, -0.2205, -0.5481, +0.1747, +0.2618, -0.1887, +0.2324, +0.3140, -0.0721, +0.0421, -0.0456, +0.0669, -0.3454, -0.0662, +0.4177, -0.1038, +0.2780, +0.0996, -0.5959, -0.5961, -0.4114, +0.2390, -0.3022, -0.1677, -0.3278, -0.3484, -0.1997, -0.0566, -0.0892, +0.7018, +0.6478, +0.1005, -0.5961, +0.1566, +0.0825, +0.2346, -0.3356, -0.3185, +0.0755, +0.0411, -0.0793, +0.3258, -0.1396, +0.1283, +0.1896, -0.5171, +0.1120, -0.1224, +0.0367, +0.0743, +0.1430, +0.0132, +0.0149, +0.1147, -0.4125, -0.2080, +0.1968, +0.8142, -0.0721, +0.3152, -0.2247, +0.3908, +0.0971, -0.1424, +0.1374, +0.2706, -0.3770, +0.1096, -0.0568, +0.3264, +0.4506, -0.4569, +0.1727, -0.2381, +0.4214, +0.1191, -0.3278, +0.1992, -0.2243, -0.4143, +0.8708, -0.2386, +0.7603, -0.1501, +0.0901, +0.4924, -0.2237, -0.3817, +0.1332, +0.1977, +0.2710, +0.2726, -0.0557, +0.0365, -0.2051, +0.4295, -0.0173, -0.0251, -0.2283, -0.5470, +0.2785, +0.4134, +0.1839, -0.2030, -0.0077, -0.3212, +0.1286, -0.2258, -0.2953, -0.3600, +0.0362, -0.2548, +0.1616, -0.2418, +0.2031, +0.1168, +0.1147, -0.0406, -0.0521, -0.8852, -0.2120, -0.0571, +0.0538, +0.2702, -0.2204, -0.2196, +0.0400, +0.1007, -0.4083, -0.1119, +0.3729, +0.3893, -0.2311, +0.3263, +0.3975, +0.2199, +0.1641, +0.7579, -0.3420, +0.3819, +0.0741, +0.7023, -0.1790, +0.3570, +0.1058, -0.1609, -0.0125, +0.1419, -0.2185, +0.1101, +0.2555, -0.5080, -0.2319, -0.0974, -0.4406, +0.3373, +0.7219, -0.2865, +0.0826, -0.1259, +0.1188, -0.0105, -0.1039, -0.0604, +0.3308, +0.0726, +0.0293, +0.4745, -0.6289, -0.2740, -0.5608, +0.1218, -0.0781, +0.0437, +0.1166, -0.0665, +0.7765],
-[ +0.1900, +0.1304, +0.1306, +0.1685, +0.0547, -0.1907, -0.0987, +0.3965, +0.0377, +0.3136, +0.3067, +0.0101, -0.0786, -0.2354, +0.2159, +0.2700, +0.1332, +0.0464, +0.0145, -0.3109, -0.1940, +0.3194, -0.0398, -0.0600, -0.1790, +0.0580, +0.3900, +0.3714, -0.3819, +0.1061, +0.0045, -0.2275, +0.0156, +0.1695, +0.1446, +0.0291, +0.2628, -0.0779, +0.2689, +0.1189, +0.4291, +0.3251, -0.2835, -0.1831, +0.5168, +0.2814, -0.2532, +0.1688, -0.0255, +0.0595, -0.0628, -0.0292, +0.4426, +0.0847, -0.0432, +0.1771, -0.1106, +0.0703, -0.0249, +0.0689, -0.0916, -0.0069, -0.0343, -0.1095, -0.0536, +0.0074, -0.0784, -0.1075, -0.2998, -0.0088, +0.1853, +0.0493, -0.1932, +0.0370, +0.2847, -0.0820, -0.1846, -0.0661, -0.3196, +0.3797, -0.0899, +0.5101, +0.0220, +0.4859, +0.3703, -0.0893, +0.0720, +0.0627, +0.0008, +0.2151, +0.2527, -0.0721, +0.2133, +0.1272, +0.2210, -0.2012, +0.1135, +0.8663, +0.3867, +0.5365, +0.1263, +0.2323, -0.0163, -0.1178, +0.4859, +0.1277, -0.5319, +0.0241, +0.1482, -0.2447, +0.1440, -0.1298, -0.0774, +0.1329, +0.2049, -0.1232, +0.0122, +0.2751, -0.1623, -0.0355, +0.2232, +0.1650, +0.0788, +0.3453, +0.3085, -0.0324, +0.2696, -0.1154, -0.0087, +0.0087, -0.0158, -0.0721, -0.2802, +0.6397, +0.1834, +0.1206, +0.1670, -0.0771, +0.3098, +0.0817, -0.2540, -0.1481, +0.3749, -0.1109, -0.1901, +0.0763, +0.0562, -0.0834, +0.4640, +0.2060, -0.0520, +0.2273, -0.5758, +0.0613, -0.3936, +0.4325, +0.3668, +0.6940, +0.0661, +0.1322, +0.0727, -0.1327, -0.2523, -0.0368, +0.3519, +0.0042, -0.1765, -0.0588, +0.0173, +0.3305, -0.0382, -0.0072, +0.1676, +0.4529, +0.1004, +0.0037, +0.4982, -0.1013, -0.1774, -0.1828, +0.0592, -0.0361, +0.1937, -0.3102, -0.0329, +0.7132, +0.1081, +0.1713, -0.1541, -0.1572, +0.0455, +0.0631, -0.3422, -0.0472, +0.0655, -0.1291, +0.1069, +0.3075, +0.2226, -0.1803, -0.1247, -0.0509, -0.1519, -0.1252, +0.2028, +0.1468, -0.0986, +0.0458, +0.0799, +0.2962, -0.2362, +0.1770, -0.0585, +0.1376, -0.1471, -0.0011, +0.3521, +0.1243, -0.4805, -0.2684, +0.2582, +0.5082, +0.1511, +0.5160, -0.3806, +0.1276, +0.1041, -0.3635, +0.0573, +0.0853, -0.1572, +0.2395, -0.0647, +0.1263, +0.2338, +0.2568, +0.0774, +0.3536, +0.4368, +0.1272, +0.1465, +0.0028, +0.2233, -0.0329, -0.0857, +0.0750, +0.1408, +0.3485, -0.0137, +0.1533, -0.1600, -0.1337, -0.0974, -0.0299, -0.0323, +0.0912],
-[ -0.3504, +0.3179, -1.0918, -0.3050, +0.9112, +0.5211, +0.6364, -0.0960, -0.5305, +2.3346, -0.7544, +0.0837, -1.0392, +0.7178, -0.1126, +0.7165, +0.7288, +0.6258, +0.0957, -1.2260, -0.3948, +0.3753, -0.4606, -1.5339, -0.2479, +0.2242, +0.6865, +0.0099, -0.0191, +0.2671, -1.2197, +0.0032, +0.1167, +0.3508, +0.8007, -0.7487, -0.4238, -0.6390, +0.5996, +1.5764, +1.4712, -0.0523, +0.3140, -0.9890, +0.3494, +0.4810, +0.6032, +0.9013, +0.8956, +0.0639, -0.6232, -0.0639, +1.3263, -0.6084, -0.2796, -0.4429, -0.1116, +1.2581, -0.3688, +0.4144, +0.1753, -0.8812, +0.1593, +1.7526, +0.2204, +0.7330, +0.7426, -0.1957, -0.5876, +0.3344, -0.8807, -0.3715, -0.2438, +0.2862, +0.1338, -0.8705, +1.3052, -0.7570, -0.9733, +0.0851, -0.1355, +0.7726, +0.9775, +1.8582, +0.4909, +0.2100, +0.6480, -0.9390, -0.0109, +0.8414, -0.0162, +0.1212, -0.3045, +1.2366, +0.6475, +0.0346, -0.5155, -0.4277, -0.3017, -1.3542, +0.5016, +0.3839, +1.0181, -0.2053, +1.2256, +0.6403, +0.2995, +0.1694, +1.1001, -1.2428, -0.6839, -0.0096, +0.2364, +0.6608, -0.0468, +1.1051, -0.4258, +0.2412, -0.0888, +0.4045, -0.8473, -0.3771, +0.0673, -0.7719, +2.2755, +0.1519, +0.2434, -0.3192, +1.2985, +0.1204, -1.2696, +0.5239, +0.3562, +1.0429, +0.1553, -1.0302, -0.3452, +0.4931, -0.8529, -0.2207, -1.4133, -0.7739, -0.9373, -0.0316, -0.0720, -0.3610, -0.9920, -0.2442, +0.1684, +0.8980, -0.3976, +0.5449, -1.5636, -0.8419, -0.1692, +1.3491, +0.0253, +1.9946, +0.3635, +0.5639, +0.1305, -1.3483, +0.7867, -0.0294, +1.3528, -0.4485, +0.0917, -0.0045, -0.8327, +0.2827, +0.4188, -0.2105, +0.3741, +0.7789, +0.7423, +0.3054, +0.5409, -0.3485, +0.2274, +0.8441, +0.2397, +0.5060, +0.4379, +0.3308, -0.3921, +0.2715, -1.0825, -0.5958, +1.3096, +0.7103, +0.1227, +0.1876, +0.7009, +0.2243, +0.6355, -0.1630, +0.2463, +0.1666, -0.3954, -0.5123, -0.7415, -0.0754, +0.2274, -0.2862, +0.2964, +0.0954, +1.1562, -0.3559, +0.4572, +0.9555, -0.5453, +0.1497, +0.0105, -1.4956, +1.3926, +0.0228, -0.3674, -0.1625, -0.9157, +0.7016, -0.6211, +0.5463, +0.3265, +0.9720, -0.3992, -0.4322, -0.4880, -1.3482, +0.7272, -0.0962, +0.1547, +0.6783, +0.1496, -0.0992, +0.4034, +0.1924, -0.1571, -0.0865, +2.5906, +1.2446, -0.5539, -0.0809, +0.5130, -0.0844, +0.9177, -1.3037, -0.0150, -0.6602, -0.0371, +0.3352, -0.4679, -0.8509, -0.6062, +1.6027, -0.5644, -1.3218],
-[ +0.2795, +0.0642, -0.4321, +0.1457, +0.0121, -0.6645, +0.5804, +0.1799, +0.0117, +0.5672, -0.3526, +1.0581, +0.0324, +0.3915, +0.1572, +0.0034, +0.2864, +0.1973, -0.4619, +0.3294, -0.0396, -0.3446, -0.0199, -0.4083, -0.5971, +0.0460, +0.5415, +0.6182, +0.2403, -0.1356, -0.1049, +0.4659, -0.2931, -0.2250, -0.6128, +0.4385, -0.0995, +0.3239, +0.6134, +0.3091, +0.2143, +0.1731, +0.0841, +0.1188, -0.3338, +0.3281, +0.2010, +0.5196, -0.1062, +0.2815, +0.2324, -0.1379, +0.0957, -0.2191, +0.1873, +0.2349, -0.1210, -0.0056, +0.0639, +0.0467, +0.4666, -0.0640, +0.1107, -0.0418, -0.2104, +0.1299, +0.4768, -0.1160, -0.0516, -0.1398, +0.3253, -0.0154, -0.2684, -0.1671, +0.4381, +0.1137, +0.2647, -0.2082, -0.5011, +0.0124, +0.2318, -0.0503, +0.0276, +0.8962, +0.2799, +0.3159, -0.6777, -0.0680, +0.1874, +0.1644, +0.1518, +0.1808, +0.0803, -0.2494, +0.5158, -0.2165, +0.3377, +0.8342, +0.0527, -0.6154, +0.1771, -0.1781, -0.0620, -0.7147, -0.3531, +0.2948, +0.0663, +0.3923, +0.6540, +0.0174, +0.6028, -0.1087, +0.4604, -0.0161, +0.2117, +0.3383, -0.2849, +0.9566, -0.4082, +0.2355, +0.0818, -0.0087, -0.1493, +0.1262, +0.5054, -0.1072, -0.1005, +0.2100, +0.2903, +0.3424, -0.1168, +0.1297, -0.4548, -0.4380, +0.6081, -0.8408, +0.4011, -0.0471, +0.3515, -0.2566, +0.8423, +0.1594, +0.1761, -0.0926, -0.3069, +0.2977, +0.0840, +0.2581, -0.1953, +0.2386, +0.2111, +0.4178, -0.1321, -0.0219, +0.5732, -0.0419, -0.2215, -0.5132, +0.3878, +0.0862, -0.3056, +0.3618, +0.7162, -0.0857, +0.1711, -0.1898, +0.2286, +0.6806, +0.3809, +0.2188, +0.2804, -0.2275, +0.6766, +0.1952, +0.0073, -0.3949, -0.1420, +0.3417, -0.3001, +0.1640, -0.1118, -0.5296, -0.0676, -0.1672, +0.2324, -0.0308, +0.0786, +0.9096, +0.7681, -0.2398, +0.0431, -0.1578, +0.3719, -0.3167, +0.8528, -0.0046, -0.0758, +0.2415, -0.2559, -0.1975, +0.2967, -0.1169, +0.0701, +0.1372, -0.0018, +0.2277, -0.2830, -0.1139, +0.4305, -0.3147, -0.3947, -0.2646, -0.1233, +0.6040, +0.2712, +0.5285, -0.3873, +0.1587, -0.0579, -0.4679, -0.2148, -0.1199, -0.3221, +0.0139, +0.2610, -0.2710, -0.0914, -0.3749, +0.8469, -0.0296, +0.0442, +0.4900, +0.0576, +0.9743, +0.1762, -0.1878, -0.2236, +0.2311, -0.1199, -1.0481, -0.3038, -0.3667, +0.0169, -0.1208, +0.0286, +0.1759, +0.1569, +0.1607, +0.8348, +0.0245, +0.1323, -0.3582, +0.6256, -0.2299, +0.2870, +0.0372],
-[ +0.4222, -0.0573, +0.5081, -0.3760, +0.7451, -0.3354, +0.9356, +0.3947, +0.3637, -0.1050, -0.9781, +0.0794, -0.0114, -0.2344, +0.9890, +0.2250, +0.6542, +1.0132, +0.4594, +0.1899, -0.5553, -1.0695, -0.0464, -1.0895, -1.4412, -0.4980, +0.1758, +0.2815, +0.6579, -0.0964, -0.0780, +0.3784, -0.4967, -0.2489, -0.4366, +0.4137, +0.5941, +0.9789, +0.0680, -0.1903, +0.4329, -1.2772, -0.2180, +0.1931, -0.5630, -0.7352, +1.4870, -0.7178, -0.2086, +0.0265, -0.1702, +0.1937, -0.0929, -0.7027, +0.1547, +0.8569, -0.3356, +0.3963, +0.7436, +0.5573, -0.0482, +0.1243, +0.5669, +1.2589, -0.1877, -0.2490, +0.0755, +0.6648, -0.4557, -0.9240, +0.0784, +0.3344, -0.4727, -0.2906, +0.2908, -0.0087, -0.8507, +0.9188, -1.0174, -0.3030, -0.1066, -0.1418, +0.6422, -0.4228, +0.8031, -0.0486, +0.0789, +0.0159, +0.4195, +0.7959, -0.4948, +1.0052, -0.4370, -0.3082, +0.4453, -0.8982, +0.1833, -0.0529, -0.2152, -0.6723, -0.5515, -0.5945, +0.1152, +0.2134, -0.1846, -0.0981, +0.0175, +0.3448, -0.5466, -0.3407, +0.8680, -0.2085, +0.9641, -0.1393, -0.2101, -0.2797, +0.4820, -0.4386, -0.8097, +0.0695, +0.3653, +0.4081, -0.0723, +0.6429, -1.1749, +0.0525, -0.3654, -0.7180, +0.1074, -0.2005, +0.3934, -0.5641, -0.3977, -0.7490, -0.7064, -0.2359, +0.3631, -0.7209, +0.4213, +0.5278, +0.1775, -0.0226, +0.2676, -0.8443, +0.6325, -0.6958, -0.0446, +0.0145, +0.6466, +0.4083, +0.2505, -0.3254, -1.3595, -0.2900, +0.3684, +0.2849, -0.0168, -0.9716, +0.0890, +0.1455, +0.1932, -0.2316, -0.2257, +0.1177, +0.1743, -0.0457, -0.7849, +0.7017, -0.4356, +0.1590, +0.2895, -0.5398, +0.2746, -0.1955, -0.9924, +0.4579, +0.0071, -0.0746, +0.2151, -0.1827, +0.5044, -0.5401, -0.4354, +0.1411, -0.2633, +0.7402, +0.0019, -0.0907, +0.3447, -0.6141, -0.2552, +0.5652, +0.2047, -0.5309, +0.2966, +0.0315, +0.2328, -0.1916, -0.2069, -0.1830, +0.6357, +0.4643, -0.5741, +0.4861, +0.7827, -0.0479, -0.3617, -0.1293, -0.0768, -0.3499, +0.2789, -0.1915, +0.0334, +0.0698, -0.1463, +0.4034, -0.1668, +0.9289, -0.9585, -0.4268, -0.3682, +0.1801, -0.8269, -0.3515, +0.3098, +0.1076, +0.6027, -0.1172, +0.0588, +0.7357, -0.0441, -0.1213, +0.2665, -0.4022, -0.2895, -0.3017, -0.3352, -0.3031, -0.1225, -0.1627, -0.6134, -0.3426, +0.4558, -0.3361, +0.5679, +0.5502, -0.0751, -0.7189, +0.6709, +0.5030, +0.3367, -0.7531, +0.9245, -0.8705, +0.2312, +0.0640],
-[ -0.0035, -0.0034, -0.2528, -0.3608, +0.3682, -0.2742, -0.0113, -0.3332, +0.0137, -0.0303, -0.0216, +0.0627, +0.1116, +0.0642, -0.3810, +0.0072, -0.0297, -0.1337, +0.2035, -0.1883, +0.0202, -0.0721, +0.1509, -0.2001, +0.5420, -0.1128, -0.1005, +0.1079, +0.1587, +0.0785, -0.0149, -0.0047, +0.3506, +0.3381, -0.1188, +0.1962, -0.0130, -0.0012, -0.2426, +0.1351, +0.1945, +0.1089, +0.2607, +0.0582, -0.2137, +0.6271, +0.1350, +0.0122, -0.1709, -0.2135, -0.1653, +0.0632, +0.4087, -0.0052, +0.6810, +0.0148, -0.0323, +0.3402, +0.0679, +0.1630, -0.0387, -0.0974, -0.0687, -0.0846, +0.1532, +0.1129, -0.0719, +0.0268, -0.1528, +0.0340, -0.0595, +0.3099, +0.0794, -0.0118, +0.0639, -0.3403, +0.0216, +0.0587, +0.1669, +0.1529, -0.0114, -0.5345, -0.0442, -0.2288, +0.4265, -0.3686, +0.1109, +0.0872, +0.1012, +0.1267, -0.0799, +0.0821, +0.1215, -0.1414, +0.1897, +0.3936, +0.1082, +0.0621, +0.4993, +0.1550, +0.0853, -0.1830, -0.0109, +0.2747, +0.0066, -0.0596, -0.0209, -0.1222, +0.6425, +0.0010, -0.1389, +0.2046, -0.0143, -0.1457, +0.2317, -0.3896, +0.1399, +0.0099, -0.0574, +0.3197, -0.2081, +0.1138, +0.0407, -0.0042, +0.0752, +0.0459, -0.2480, +0.0822, -0.3238, +0.0392, +0.3801, +0.1197, +0.2401, -0.4082, +0.0690, +0.1263, +0.1912, +0.2382, +0.0859, -0.4645, +0.1211, +0.0598, -0.1411, +0.2445, -0.0240, +0.1098, +0.1856, +0.2397, -0.0041, +0.1188, -0.0047, +0.0424, +0.5290, +0.3475, +0.1254, +0.0685, +0.0748, -0.0148, +0.1090, -0.0598, -0.0045, -0.2743, +0.1616, +0.1719, -0.1873, -0.0924, -0.0310, -0.1332, -0.1907, +0.1881, -0.4096, +0.1428, +0.2975, -0.0189, +0.2020, +0.2217, -0.0367, +0.3606, +0.4407, -0.2666, +0.0850, -0.0286, -0.1606, +0.1058, +0.0790, +0.1514, -0.0547, +0.1220, -0.2964, +0.1235, +0.4847, +0.0590, +0.0304, +0.2212, +0.2509, -0.1166, +0.0666, -0.1935, +0.0430, -0.1518, +0.3587, +0.0948, +0.2795, +0.4758, +0.0747, -0.1021, +0.3524, +0.0737, +0.1654, +0.6264, -0.0327, -0.1234, +0.0612, -0.0495, -0.2775, -0.2223, -0.0795, -0.0540, +0.4101, +0.0887, +0.6357, -0.0557, +1.0091, +0.3728, -0.2812, +0.0505, -0.2041, -0.0258, -0.0876, +0.0441, +0.0864, -0.0484, +0.3001, +0.3026, +0.0090, -0.2822, -0.1953, -0.2267, -0.2283, -0.0550, +0.4666, -0.2008, -0.1510, -0.0588, +0.0770, +0.3002, +0.0200, +0.1235, -0.0181, +0.1489, +0.1830, -0.0221, +0.2327, -0.2378, -0.1699, +0.4160],
-[ -0.1059, +0.1515, +0.0140, +0.1541, +0.3425, -0.3510, +0.1152, -0.0096, +0.0941, +0.2030, -0.5814, +0.1163, -0.1798, +0.2130, -0.0308, -0.2670, -0.0307, +1.1302, -0.5876, -0.1339, +0.0085, -0.4369, -0.0089, +0.2912, -0.0841, -0.0179, +0.0648, -0.2874, -0.3967, +0.1606, +0.4970, +0.0788, +0.1305, +0.6643, +0.8430, +0.0646, +0.0448, -0.3034, -0.1129, -0.3283, +0.0435, +0.5129, -0.1075, -0.1883, +0.4669, -0.3403, -0.1316, +0.3523, -0.0285, -0.1050, -0.0914, -0.0981, +1.3083, -0.3445, -0.5618, +0.0772, +0.1022, -0.0018, -0.1475, -0.3236, +0.1725, -0.3069, +0.1140, -0.1664, +0.1786, -0.4218, +0.2003, +0.1524, +0.2598, +0.0738, +0.0487, +0.4012, -0.3416, +0.1218, -0.1210, +0.9181, +0.6536, +0.4306, +0.0462, +0.6724, +0.0628, -0.5143, +0.2787, +0.1601, +0.2327, -0.0700, -0.0750, -0.2287, +0.2918, -0.3260, +0.0710, +0.0433, -0.6924, +1.1640, +0.4052, +0.4894, -0.0450, +0.6232, +0.1674, -0.1411, -0.1690, -0.3918, -0.5933, +0.4397, +0.5854, +0.6074, -0.2093, -0.2082, -0.2854, -0.2730, +0.4739, -0.1440, -0.0470, +0.3595, +0.0505, +0.0261, +0.2556, +0.1997, +0.1467, -0.6146, -0.1772, +0.3620, +0.2029, -0.1267, -0.5105, +0.2807, -0.7753, +0.0937, -0.0990, -0.0566, +0.1463, +0.4945, -0.4445, +0.2097, -0.4238, +0.3291, +0.4771, -0.0934, +0.3328, +0.0125, +0.2216, +0.1743, -0.1884, -0.1027, +0.1037, +0.9080, +0.7220, +0.3006, -0.4461, +0.2261, +0.3679, -0.0083, +0.1107, -0.2835, -0.2122, +0.9465, +0.2494, +0.2009, +0.3854, +0.3620, -0.0232, +0.7130, +0.5914, +0.2367, -0.1907, +0.0126, -0.4836, -0.7799, +0.1886, +0.7844, +0.0632, -0.1651, +0.5767, -0.3709, +0.2219, -0.4823, -0.4274, +0.1896, -0.2534, +0.2759, -0.0053, +0.3047, +0.0830, -0.0579, -0.5030, -0.3829, +0.2817, -0.4349, -0.1430, +0.1322, +0.3572, +0.0090, -0.5643, +0.1411, -0.4972, -0.3413, -0.1593, +0.0419, -0.3883, +0.0232, -0.1065, -0.0463, +0.3074, +0.6826, +0.1211, +0.1497, -0.0864, +0.0145, +0.6440, -0.1601, +0.2847, +0.4424, +0.1406, +0.3737, -0.0508, -0.0550, +0.2662, -0.1365, -0.2198, -0.1154, +0.1846, +0.3939, -0.1867, +0.2783, +0.0214, -0.2052, +0.2852, +0.4517, -0.0070, +0.9497, -0.0211, -0.5972, +0.0932, -0.0961, +0.0633, +0.5786, -0.2438, -0.1156, +0.1324, -0.0539, +0.1527, +0.5762, -0.0996, +0.2633, -0.0446, +0.2198, -0.1069, -0.1196, -0.3112, +0.2806, -0.0446, -0.3673, -0.3333, -0.5466, -0.6300, -0.0539],
-[ +0.0886, -0.1736, +0.2303, +0.7947, +0.0393, -0.2798, -0.5487, -0.2241, -0.5310, +0.5406, -0.0532, -0.0064, +0.2742, -0.3217, -0.2300, +0.1303, -0.2625, -0.4393, +0.0598, -0.2584, +0.0027, +0.2343, +0.3005, -0.3532, -0.7355, -0.1263, -0.0904, +0.0143, +0.0917, +0.3467, -0.1259, +0.0210, -0.0186, -0.0360, -0.4055, +0.0844, +0.3825, +0.1753, +0.3408, +0.2307, +0.4749, +0.1994, +0.1054, +0.3573, -0.2327, +0.0036, -0.2009, -0.1823, +0.0889, -0.0884, -0.2532, +0.3909, -0.2113, -0.2426, +0.1061, +0.2335, +0.3052, +0.1240, -0.2379, -0.0317, +0.0107, -0.3895, -0.0050, -0.0169, +0.1984, -0.1232, -0.2768, +0.4420, +0.0246, +0.3070, -0.1335, +0.2652, -1.1367, +0.2838, +0.3087, -0.5247, +0.1373, -0.5731, +0.0517, -0.8331, +0.0370, +0.0661, -0.1572, +0.1051, -0.4990, -0.9321, +0.2448, +0.2690, +0.2054, -0.4378, +0.0132, -0.3105, -0.1545, -0.3607, +0.4425, -0.1347, +0.2146, +0.2794, -0.1716, -0.0498, +0.0685, +0.4673, -0.5200, +0.4520, -0.0439, +0.0930, -0.0961, -0.2375, +0.2483, -0.1084, +0.0855, +0.3815, +0.1763, -0.2518, -0.0570, -0.2764, -0.9503, +0.4452, -0.2262, +0.2897, +0.2107, -0.2425, -0.2231, +0.1219, -0.2070, -0.3488, -0.2947, +0.0958, +0.0930, +0.1411, +0.3361, -0.2040, +0.2504, -0.7070, +0.2827, -0.1822, -0.1630, -0.0348, +0.0428, +0.0818, -0.1700, +0.0074, +0.1539, +0.0177, +0.3407, -0.0548, +0.5441, -0.1306, -0.4407, +0.0646, -0.3218, -0.0806, +0.1349, -0.2540, -0.0872, +0.4692, -0.4425, -0.5095, -1.0056, +0.4027, -0.0200, -0.1376, +0.0475, -0.7649, -0.3253, -0.6835, -0.0361, +0.1053, -0.0829, +0.3581, +0.3582, +0.2497, +0.0393, +0.5963, +0.3694, -0.2755, -0.4194, +0.3549, +0.2054, +0.2459, -0.3597, -0.1185, +0.0509, +0.6428, -0.3443, +0.2562, +0.0889, +0.3400, -0.6770, -0.0713, -0.2477, +0.2696, -0.1843, +0.4073, -0.2708, -0.0514, +0.2385, +0.0235, -0.1136, +0.4380, -0.0392, +0.0524, -0.4062, +0.1885, -0.7391, +0.2537, +0.0709, -0.3841, -0.6341, +0.1817, -0.4291, -0.5313, -0.9104, +0.3972, +0.0307, +0.2267, -0.0018, +0.2399, -0.1271, -0.1045, +0.1824, -0.9698, +0.0084, -0.2353, -0.0986, -0.3136, -0.0781, -0.0959, -0.3397, -0.8343, -0.6744, +0.2505, +0.0941, +0.0670, +0.2594, -0.5116, -0.1491, +0.4280, +0.3119, +0.6404, +0.1156, +0.2095, -0.0151, -0.0291, +0.0717, -0.2272, -0.3254, +0.0794, +0.0487, +0.1850, -0.2387, -0.0572, -0.2224, -0.4618, -0.5881, -0.0762],
-[ +0.1613, -0.0121, -0.6823, +0.4505, +0.0159, -0.6711, -0.4259, -0.0010, -0.1023, -0.0402, +0.1031, -0.1431, -0.0213, +0.4424, -0.1080, -0.2636, -0.0149, -0.1129, -0.4833, +0.1006, -0.8493, -0.2696, +0.3725, +0.1174, +0.3757, +0.0964, -0.1318, +0.1640, +0.0253, +0.2252, -0.1748, -0.0377, -0.0120, +0.1607, +0.0376, +0.0201, +0.0198, -0.3454, -0.2380, +0.4885, -0.2846, -0.3210, -0.3668, +0.1292, +0.0733, -0.1518, -0.1435, +0.7051, +0.0440, -0.3134, +0.1986, -0.0950, -0.2036, -0.5937, -0.5377, +0.0555, +0.1399, -0.1929, -0.1455, -0.0545, -0.5609, +0.4115, -0.3768, -0.6463, +0.4130, -0.0706, +0.1245, +0.2189, -0.1688, -0.4369, -0.0189, -0.1132, +0.0900, -0.0476, -0.3192, -0.0721, +0.3550, +0.0791, -0.1973, +0.2124, -0.3421, -0.2505, -0.4525, -0.3532, -0.4306, +0.0726, -0.1936, +0.3790, +0.0773, +0.1141, +0.3051, -0.1605, -0.1697, -0.3239, -0.0387, +0.0490, +0.4097, -0.1983, -0.3103, -0.1348, +0.0983, -0.1906, -1.0984, -0.3224, +0.1721, +0.0596, -0.0802, +0.1193, +0.5012, +0.4600, +0.1982, -1.2366, -0.3397, +0.0045, +0.0963, +0.0420, +0.0534, -0.6935, -0.1704, +0.2974, -0.5040, -0.4112, +0.1151, -0.3827, -0.6324, +0.1939, -0.0368, +0.1991, -0.2959, +0.1311, +0.0653, -0.1839, -0.3214, +0.2320, +0.2095, +0.0678, +0.0375, -0.1832, +0.4512, +0.2901, -0.4755, +0.2493, +0.2288, +0.0834, -0.3465, +0.4282, +0.0664, -0.2354, +0.3027, +0.2787, +0.2102, +0.1778, -0.2229, +0.2759, -0.2128, +0.5151, -0.0355, -0.2695, +0.0498, -0.6670, -0.2849, -0.1452, +0.4245, +0.4908, +0.4679, +0.0071, +0.3998, +0.0380, -0.1295, -0.2110, -0.0502, +0.0330, +0.5156, +0.2586, -0.1972, +0.1425, -0.5514, -0.1277, +0.3379, -0.1527, -0.0876, -0.1846, +0.3335, -0.2494, -0.1005, +0.0055, +0.1809, +0.2810, -0.2826, +0.1018, -0.1270, +0.2189, +0.2438, +0.0231, -0.0637, -0.4122, -0.1142, +0.0933, -0.0771, +0.0415, -0.0525, +0.1933, +0.5861, +0.1639, -0.0109, -0.1786, -0.3391, -0.0341, +0.4664, +0.3602, -0.2455, -0.1581, +0.0035, -0.6658, -0.4299, +0.0850, -1.0917, -0.1338, +0.4143, +0.0696, -0.3031, +0.3610, +0.2661, +0.1521, +0.6565, +0.1507, -0.1110, +0.1716, +0.2436, -0.5497, -0.6088, -0.4964, +0.0426, -0.4534, -0.0126, -0.2565, -0.2301, +0.0974, +0.1669, +0.5493, +0.0544, +0.2104, +0.0747, +0.2049, +0.2100, +0.1637, -0.5843, +0.3274, -0.4244, +0.4082, +0.2544, +0.0823, +0.2458, +0.1169, +0.1472, +0.0367]
-])
-weights_dense1_b = np.array([ +0.1494, +0.0039, -0.0527, -0.0962, +0.0315, -0.1903, -0.0055, -0.0615, -0.0553, -0.1921, -0.1072, -0.0451, -0.1178, -0.0108, -0.0561, -0.1273, -0.1139, -0.0796, -0.0175, -0.0684, -0.0933, -0.1067, -0.1255, +0.0234, -0.0703, -0.2935, -0.1144, -0.1077, -0.1229, -0.1456, -0.1558, +0.0667, +0.0781, -0.0370, -0.1065, -0.0846, -0.0311, +0.0140, -0.1026, -0.1604, -0.1456, -0.2161, -0.0539, -0.1573, -0.0612, -0.0970, -0.2703, -0.1411, -0.2202, +0.1398, -0.0699, -0.1028, -0.0294, -0.1635, +0.1305, -0.1769, +0.1233, -0.3288, +0.0167, +0.0028, -0.0550, -0.1999, +0.0864, +0.0176, -0.0370, +0.0562, -0.0984, +0.0783, +0.0478, -0.1250, -0.2548, -0.1360, -0.0914, -0.0499, -0.0393, +0.0658, -0.1763, -0.1398, -0.0844, -0.1208, -0.0743, -0.1800, +0.0300, -0.0678, -0.0124, -0.0126, -0.0269, -0.1089, -0.0306, -0.0458, -0.0984, -0.0951, -0.0395, +0.0311, -0.1592, -0.1021, -0.3524, -0.1006, -0.1488, -0.2021, -0.0736, -0.1389, -0.0688, +0.0139, +0.0820, -0.1823, -0.0241, -0.0035, -0.0373, +0.0326, -0.0615, +0.0254, -0.0134, +0.0239, -0.1209, -0.0289, -0.1025, -0.1184, -0.1214, -0.0290, -0.0975, +0.0992, -0.0952, -0.1083, -0.1422, -0.0548, -0.0305, -0.2508, -0.0206, -0.2072, -0.0452, +0.0112, -0.0011, +0.0417, +0.0035, +0.0200, -0.1942, -0.0485, -0.1137, +0.0025, +0.0786, +0.0299, -0.1345, +0.1579, -0.0281, -0.0762, -0.0884, +0.0861, -0.0782, -0.1839, -0.0320, -0.2262, +0.0617, -0.1688, -0.2112, -0.1037, -0.1056, -0.0510, -0.0038, +0.0895, -0.2475, -0.0174, -0.1610, +0.0683, -0.2035, -0.0045, -0.1483, +0.0695, -0.1126, -0.1221, +0.0023, -0.0862, -0.1456, -0.1136, -0.0341, +0.0209, -0.0928, -0.0567, +0.0725, -0.0127, -0.0353, -0.1072, -0.0613, -0.1992, +0.0168, -0.1877, -0.1331, -0.1073, -0.1444, +0.0069, +0.0563, -0.1909, -0.1581, -0.0970, -0.0138, -0.0487, -0.1580, -0.1599, -0.0073, -0.2733, -0.1690, -0.2064, +0.0071, -0.2040, -0.1194, -0.0529, -0.1376, -0.1651, -0.0822, -0.1775, -0.1370, -0.2621, -0.1093, -0.0536, -0.0812, +0.0422, +0.0078, -0.0437, -0.2098, -0.1435, +0.0691, -0.1066, -0.1223, +0.0092, -0.0332, -0.0460, +0.0013, -0.0559, -0.1134, -0.1300, -0.0909, +0.0010, -0.2052, -0.1058, -0.0746, +0.0049, +0.0770, -0.0889, +0.0130, -0.1252, -0.2867, -0.0034, +0.0268, -0.0217, -0.0712, -0.0839, +0.0532, -0.1541, +0.0243, -0.2173, +0.0914, -0.1751, -0.1907, -0.0940, -0.0697, -0.1361])
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ +0.2289, +0.2584, +0.2595, +0.0173, +0.1293, -0.2980, +0.1410, +0.0982,
+ +0.0216, +0.3724, +0.2204, -0.0734, -0.2420, -0.3443, -0.2738, -0.3825,
+ +0.1504, -0.0930, -0.2680, +0.0685, +0.1592, +0.2534, -0.0787, -0.0426,
+ +0.2591, +0.2134, -0.1631, +0.5168, +0.1444, +0.2736, +0.3623, -0.3472,
+ +0.0393, -0.3056, +0.3850, -0.5231, +0.4511, +0.4223, -0.0905, +0.2265,
+ +0.1662, +0.1092, +0.0426, -0.0209, +0.3260, -0.1788, +0.5045, -0.0254,
+ +0.6684, +0.4659, +0.2193, +0.6121, -0.1771, +0.3024, +0.3233, -0.3380,
+ +0.1834, +0.1947, +0.2840, -0.0212, +0.0610, +0.0254, -0.0687, +0.3342,
+ -0.2010, +0.4851, -0.5739, -0.3228, -0.2242, +0.6149, +0.2704, -0.1006,
+ +0.3950, -0.2684, +0.0090, -0.2419, +0.1112, -0.0795, +0.0021, -0.0317,
+ +0.1345, -0.2847, +0.2323, +0.5374, -0.0119, -0.2098, +0.2074, +0.1693,
+ +0.4537, -0.1453, +0.2661, -0.2997, +0.1043, -0.2340, +0.4472, -0.0415,
+ +0.6437, +0.0279, +0.1609, +0.3353, -0.2240, -0.5433, -0.0053, +0.1863,
+ +0.1038, +0.3337, +0.3889, +0.4159, -0.0836, -0.0826, +0.0872, -0.1362,
+ +0.0061, -0.2982, -0.0074, -0.1452, -0.0655, -0.1369, -0.0493, -0.1082,
+ -0.4080, +0.4732, +0.1229, +0.3087, -0.1222, +0.3846, +0.0719, -0.4536,
+ +0.1202, -0.3903, -0.0445, +0.4052, +0.2922, +0.1095, +0.0317, +0.0974,
+ +0.1149, -0.3794, +0.4364, -0.1597, +0.2889, +0.2431, +0.6867, +0.5117,
+ -0.2517, +0.2835, -0.0365, +0.3303, +0.2569, +0.3636, -0.0945, +0.1853,
+ -0.1341, +0.2595, -0.0174, -0.3227, +0.1999, +0.2348, +0.5826, -0.0480,
+ +0.1449, +0.3866, +0.4740, +0.2486, +0.5011, -0.0334, +0.0953, +0.1072,
+ -0.0901, -0.3235, +0.3258, +0.3003, +0.1229, -0.2257, -0.1920, -0.2025,
+ -0.2022, +0.0843, +0.4563, -0.2654, +0.3158, -0.3102, +0.1105, -0.1171,
+ +0.0465, -0.0692, +0.2824, +0.2598, -0.0289, -0.7774, +0.3501, -0.0635,
+ +0.2257, -0.1644, +0.4091, -0.1967, +0.1614, +0.5468, +0.1365, +0.5054,
+ +0.1986, +0.1368, +0.0886, -0.1305, +0.4297, +0.2482, -0.1914, -0.2909,
+ +0.1784, +0.0690, +0.0224, +0.0378, +0.4991, -0.3410, +0.4281, -0.4574,
+ +0.1952, -0.0444, -0.1939, +0.1637, +0.2385, +0.1354, +0.1817, -0.3849,
+ +0.1909, +0.6585, +0.0997, +0.1376, +0.3598, +0.0611, +0.0124, -0.1492,
+ -0.0659, -0.2671, -0.3925, +0.2333, +0.4184, -0.1364, -0.0361, -0.5937,
+ -0.0327, -0.1142, -0.3334, +0.2963, +0.2350, -0.2600, +0.2784, -0.0720,
+ -0.1594, -0.2652, +0.3922, +0.7291, -0.1830, +0.2253, +0.1965, +0.1972
+ ],
+ [
+ +0.2244, +0.6008, -0.2907, -0.1769, -0.1935, +0.0902, +0.3499,
+ +0.0213, +0.1343, -0.4925, -0.0996, -0.2332, -0.0739, -0.3686,
+ -0.8946, +0.0956, +0.0229, -0.1700, -0.1541, -0.1738, -0.2712,
+ +0.2399, -0.9785, +0.0332, -0.1472, +0.2317, -0.2498, -0.5549,
+ +0.2247, +0.1835, +0.3699, +0.4326, +1.0277, +0.5037, +0.1917,
+ -0.0519, +0.6952, +0.0699, +0.5892, -0.2437, +0.4122, +0.8816,
+ +0.1263, -0.2072, +0.7932, +0.1292, -0.0770, +0.0025, +0.5216,
+ -0.0476, +0.1862, +0.5225, -0.1914, +0.2424, +0.9420, +0.3432,
+ +0.0285, +0.1507, +0.1983, -0.3111, -0.2958, -0.3750, -0.3894,
+ +0.4764, -0.0933, -0.1671, -0.3327, -0.1734, +0.3197, -0.2884,
+ +0.0234, -0.3527, -0.4019, +0.4847, +0.8950, +0.1055, +0.1383,
+ +0.2209, -0.0691, +0.6060, +0.3265, -0.0979, -0.2110, +0.6802,
+ -0.4336, -0.6381, -0.1507, +0.4082, -0.1635, -0.0835, -0.0082,
+ +0.5745, -0.2450, +0.7778, -0.2730, -0.6112, -0.0839, -0.0785,
+ -0.6745, -0.1420, +0.4217, +0.3215, -0.2859, +0.3225, +0.0936,
+ +0.0283, -0.1876, +0.4980, -0.4691, -0.0344, +0.1162, +0.1886,
+ -0.1320, +0.4492, +0.0019, -0.0631, +0.2038, -0.3549, +0.2250,
+ -0.2285, -0.0618, -0.0311, +0.7220, +0.0530, -0.3637, +0.2023,
+ -0.3015, +0.1247, +0.2858, -0.2926, +0.2305, +0.2896, +0.1855,
+ -0.3343, -0.1031, -0.3579, -0.6165, -0.3269, +0.0746, +0.2497,
+ -0.3880, -0.5785, -0.7582, -0.1729, -0.3449, -0.1357, -0.5979,
+ -0.7973, +0.1202, +0.6009, -0.0103, -0.0233, -0.0987, +0.4404,
+ +0.4355, -0.0934, -0.0910, -0.0382, -0.0268, +0.0425, +0.0329,
+ +0.7613, +0.1151, +0.1962, +0.3848, +0.6449, +0.0600, +0.8192,
+ +0.2580, +0.4444, -0.5772, -0.1268, -0.0429, +0.0785, +0.1237,
+ +0.5161, -0.3665, +0.0825, +0.1226, +0.4157, +0.4844, -0.5870,
+ -0.6568, +0.1661, +0.0846, +0.9718, +0.8856, +0.4171, -0.4568,
+ -0.0714, +0.0394, -0.1495, +0.1462, -0.1572, +1.3937, +0.1682,
+ +0.4968, -0.3699, +0.0710, +0.2328, +0.4747, -0.4286, +0.4434,
+ -0.0531, +0.8446, +0.0101, -0.4317, -0.2297, +0.4299, -0.1323,
+ +0.4804, -0.2152, +0.0161, +0.0560, -0.3013, +0.2911, +0.3542,
+ +0.3124, +0.3897, +0.1082, +0.2437, +0.0183, +0.2230, +0.0093,
+ +0.1507, -0.3895, -0.2750, +0.0991, +0.1170, -0.5877, +0.4045,
+ +1.0306, -0.1141, -0.0084, +0.3079, +0.4545, +0.0084, +0.1517,
+ -0.0344, +0.4704, -0.2666, -0.0728, -0.0447, +0.4098, -0.4524,
+ -0.4638, -0.4063, -0.2521, -0.2830, +0.1845, -0.3146, +0.4381,
+ -0.0215, +0.2613, -0.1182, +0.4527
+ ],
+ [
+ +0.1845, -0.1290, +0.0236, -0.1312, +0.0155, -0.6011, -0.0454,
+ +0.0183, -0.0613, -0.1651, +0.0204, -0.2374, +0.1045, -0.2035,
+ -0.2268, +0.2069, +0.0483, -0.3226, -0.2196, +0.0847, +0.1314,
+ +0.0426, -0.4253, -0.0748, -0.1497, -0.1902, +0.3815, +0.1306,
+ +0.0276, -0.2593, -0.0081, +0.1098, -0.0062, -0.1922, -0.0409,
+ -0.2615, +0.1296, +0.0267, -0.1602, -0.4755, +0.0039, +0.2688,
+ -0.0225, -0.1433, -0.0383, -0.0131, +0.0675, +0.1684, +0.1298,
+ +0.3818, -0.0260, +0.1636, -0.2338, +0.0062, +0.1756, -0.1825,
+ +0.1473, -0.2689, -0.1376, -0.0224, +0.2016, -0.2086, +0.0723,
+ +0.2100, -0.3345, +0.1170, -0.4292, -0.1302, -0.1132, +0.0030,
+ -0.3599, -0.1974, -0.4807, +0.0184, -0.0768, -0.0310, -0.2677,
+ -0.0838, -0.0072, -0.1049, -0.2841, -0.2426, +0.2338, +0.0917,
+ -0.1451, -0.3906, -0.0315, +0.1058, -0.0429, +0.1218, +0.0590,
+ +0.0446, -0.0043, -0.0168, -0.0899, -0.3793, -0.3134, +0.0907,
+ -0.5332, -0.0995, -0.0256, -0.2710, -0.0487, -0.0059, +0.0274,
+ -0.1885, +0.3208, +0.0437, -0.0411, -0.3716, -0.5700, +0.0576,
+ +0.0903, -0.1064, -0.1600, +0.1009, -0.1957, -0.0539, -0.2426,
+ -0.5847, -0.2240, +0.0023, -0.2533, -0.2903, -0.0328, +0.1289,
+ +0.0927, -0.2596, +0.2300, -0.4833, -0.1772, +0.3817, -0.1000,
+ -0.2391, -0.2917, -0.3748, +0.0640, +0.0005, +0.1664, +0.0173,
+ +0.2214, -0.2440, +0.0039, +0.2924, +0.3009, +0.0540, -0.3460,
+ +0.1538, +0.3727, -0.0801, +0.0130, -0.0963, -0.0172, +0.0524,
+ -0.1681, +0.1478, -0.1827, +0.2902, +0.2376, +0.0703, -0.3115,
+ -0.0634, +0.0512, +0.1366, +0.0646, -0.0811, -0.1668, +0.1052,
+ -0.1976, -0.1411, -0.1401, +0.0263, -0.0454, -0.0315, -0.1376,
+ +0.0403, +0.1526, -0.0385, +0.0782, -0.1382, +0.0399, -0.1812,
+ -0.3915, -0.1615, -0.0648, -0.3724, +0.1436, -0.1380, -0.4987,
+ -0.1783, +0.2295, -0.4115, -0.2025, -0.3245, -0.3584, -0.1729,
+ -0.0822, -0.0460, -0.1321, -0.3484, -0.4094, -0.1418, +0.0986,
+ -0.2276, -0.0267, -0.1027, -0.1794, -0.1338, -0.2575, -0.2837,
+ -0.0241, -0.2849, -0.2569, -0.0871, -0.0534, +0.1427, +0.1857,
+ -0.1384, -0.3600, -0.1343, -0.0075, +0.1601, +0.1113, -0.1131,
+ -0.1716, -0.2434, +0.1357, -0.1294, -0.2366, -0.0562, -0.1674,
+ -0.0974, -0.1556, -0.5273, -0.1928, -0.0431, +0.1909, +0.0233,
+ +0.2048, -0.2176, -0.1908, +0.0150, +0.1610, +0.0468, -0.1319,
+ +0.0579, +0.4051, -0.2020, +0.0208, -0.5383, +0.1756, +0.0117,
+ -0.2675, -0.1795, -0.1730, -0.1394
+ ],
+ [
+ -0.5736, -0.8805, -0.0769, -0.0851, -0.5427, +0.1977, +0.0607,
+ -0.3635, +0.5918, +0.1243, -0.0683, -0.5963, +0.2201, -0.1754,
+ -0.1193, +0.2689, +0.2383, -0.1014, +0.2498, +0.0947, -0.3494,
+ -0.0848, -0.3292, +0.0194, -0.1043, +0.4501, +0.5483, -0.0839,
+ +0.2682, +0.5032, -0.0208, -0.0950, +0.2171, +0.2045, -0.3694,
+ +0.3404, -0.0883, +0.2092, -0.2164, -0.1036, +0.2583, -0.0949,
+ +0.0715, -0.3988, +0.0751, -0.1982, +0.5441, +0.0172, +0.3297,
+ -0.6622, -0.1357, -0.5829, -0.2161, -0.6473, -0.0565, +0.6117,
+ -0.0156, +0.6255, -0.1497, -0.1722, +0.1335, +0.6251, +0.3700,
+ -0.5719, -0.2368, -0.0315, +0.0146, -0.8732, -0.2498, -0.1137,
+ +0.2604, -0.1385, -0.8775, -0.5170, -0.2435, -0.3753, +0.2906,
+ +0.0193, -0.5174, -0.3639, -0.2548, -0.5402, -0.8794, -0.5529,
+ -0.0559, -0.1246, -0.0725, -0.0145, -0.7285, -0.0017, -0.1507,
+ +0.3688, -0.1245, -0.3651, +0.3866, -0.1138, -0.0853, +0.0368,
+ -0.4360, -0.1958, -0.1419, +0.1774, +0.0723, -0.3591, -0.4659,
+ +0.3450, +0.3742, -0.1436, +0.0044, +0.2917, -0.5689, -0.5904,
+ +0.1288, -0.4701, -0.2539, -0.6716, +0.2295, -0.4429, -0.0556,
+ -0.0518, +0.2292, -1.7909, +0.1799, -0.1646, +0.3310, +0.0519,
+ -0.1858, +0.0612, +0.0647, +0.1269, +0.1987, -0.0585, -0.2811,
+ -0.8582, -0.6569, -0.3871, +0.1939, +0.1120, -0.0105, -0.3577,
+ -0.0086, -0.2489, +0.4663, -0.1103, +0.0332, -0.6252, -0.2411,
+ -0.0892, -0.4744, +0.1257, +0.1445, +0.1788, +0.0429, -0.2699,
+ +0.4812, +0.4112, +0.2460, -0.0158, -0.6195, -0.7866, +0.7380,
+ -0.1607, -0.9005, -0.3402, +0.1250, +0.0292, -0.5294, +0.2517,
+ -0.1519, +0.6130, -0.3528, -0.4301, -0.2510, +0.5858, +0.0060,
+ +0.0751, +0.0733, +0.2363, -0.6337, -0.0453, -0.3818, -0.0374,
+ -0.0048, -0.4378, -0.0780, -0.1101, +0.1504, +0.4377, -0.3238,
+ +0.2260, -0.4677, +0.1361, -0.0218, +0.2108, -0.0987, +0.3155,
+ +0.6500, +0.2126, -0.2016, +0.3768, +0.6421, +0.2673, +0.1952,
+ +0.0513, -0.0657, +0.2197, +0.2465, +0.2605, +0.3151, +0.0719,
+ -0.6572, +0.4819, +0.2985, -0.1793, -0.1759, -0.3330, -0.5562,
+ +0.1846, -0.1096, -0.5457, -0.6485, -0.4409, -0.4658, -0.0819,
+ +0.1681, -0.3892, +0.4901, -0.3008, -0.7256, +0.1596, +0.0896,
+ -0.3508, +0.4520, -0.5112, -0.3458, -0.6592, -0.9615, +0.1979,
+ +0.2483, +0.1385, -0.0924, -0.2448, +0.4041, +0.5250, +0.1655,
+ -0.5895, -0.4537, +0.3295, -0.4612, -0.1340, -0.5730, -0.2680,
+ +0.4814, +0.0250, -1.0258, +0.1863
+ ],
+ [
+ -1.0573, +0.3035, -1.0110, +0.1281, -0.5940, -0.0072, +0.4667,
+ +0.7137, +0.0810, -0.8921, -0.1219, -1.0541, -0.7295, +0.7648,
+ +0.1772, -0.1785, -1.0871, -0.1349, +0.3227, +0.6328, -0.8310,
+ +0.8725, -0.4619, -0.3077, +0.8552, -0.3231, -0.1156, -0.5372,
+ -0.4023, +0.8194, -0.8025, -0.5804, +0.5964, -0.0932, +0.5116,
+ -0.2766, +0.1760, -0.1303, +0.6465, -0.0711, -0.1220, -0.5499,
+ +0.1202, +0.1071, +0.2686, -0.1856, -0.2504, +0.0925, -0.4784,
+ +0.9105, -1.1430, -0.5899, -0.1242, +0.5508, +0.7145, +0.2748,
+ -0.3478, -0.7003, +0.4850, +0.1385, +0.3943, +0.2670, -0.4550,
+ +0.0036, -0.5703, -0.8350, -1.1953, -0.0970, +0.3308, +0.7714,
+ +0.1061, +2.0960, +0.0376, -0.7406, +0.0789, +1.5258, +0.9057,
+ +0.4235, -0.5466, +0.1064, +0.2408, +0.7252, -0.2936, +0.4144,
+ -0.3486, -0.7981, +0.0240, -0.1555, +0.9355, -0.4706, -0.7375,
+ +0.9309, +0.7671, -0.0113, -0.2764, -0.0366, +0.2126, +0.6469,
+ -0.4462, -0.2112, +0.6839, +0.4796, -0.1490, +0.8926, -0.2453,
+ +0.0598, -0.0021, +0.3849, +0.4954, -0.1375, -0.1142, +0.8535,
+ +0.8888, -0.3101, +0.7679, -0.5564, -0.2071, -0.3134, -0.0526,
+ -0.1788, +0.3544, +0.6677, +0.3217, -0.6103, -0.0902, +0.3894,
+ +0.8153, -0.5409, -0.0261, +0.7648, +0.3098, +0.5138, -0.1609,
+ +0.3192, +0.4370, -0.1330, -0.0368, +0.8144, -0.1377, +0.9899,
+ +0.2202, +0.5290, +0.4051, +0.0875, +0.4018, -0.0897, +0.4689,
+ +0.1784, +1.2015, -0.2091, +0.3738, +0.7411, -0.1037, -0.2531,
+ +0.3753, +0.1518, -0.1351, +0.3109, +0.2514, +0.2564, -0.2295,
+ +0.5837, +0.1827, -0.1766, +0.1354, -0.0895, +0.8237, +0.4432,
+ -0.3878, -0.0831, +0.7593, -0.9360, -0.4304, +0.0854, -0.9559,
+ +0.1652, +0.2593, +0.3457, -0.5038, -0.1274, +0.4108, -0.0822,
+ -0.1254, +0.4618, -0.0763, -0.4831, -0.4356, +0.5051, -0.4981,
+ +0.2556, -0.1951, +0.5189, +0.0342, +0.2521, +0.1616, -0.0889,
+ -0.0898, +0.3080, +0.2350, -0.2451, +0.2174, +0.3621, +0.7812,
+ +0.8774, +0.7318, +0.1353, +0.0450, -0.8271, +0.5002, -0.7626,
+ +1.3003, +0.4312, -0.6138, -0.1886, -0.2482, -0.5597, -0.0913,
+ +0.0901, -0.3340, +0.4610, -0.7099, +0.3496, +0.3531, +0.2044,
+ -0.1057, +0.8731, -0.6409, +0.5075, +1.0426, -0.7513, -0.3445,
+ +0.1368, -0.0996, +0.4420, +0.2574, +0.2526, +0.2479, +1.3376,
+ -0.0922, +0.2117, -0.1829, -0.0796, +1.4092, -0.2412, +0.0230,
+ +0.3997, -0.3151, +0.0822, -0.7801, -0.5236, +0.0178, -0.9243,
+ -0.5063, +0.5279, -0.2153, +0.6347
+ ],
+ [
+ +1.4703, +1.2982, -0.0402, -0.2425, +0.2475, -0.0634, +0.4494,
+ -0.7865, -1.3634, -0.1417, -0.2296, -0.4785, -0.1649, -0.8603,
+ +0.2584, +0.1614, -0.3570, -0.9330, +0.6203, -0.0622, +0.7080,
+ +0.0465, +0.0007, -0.3840, -0.0692, +0.8238, -0.9584, +0.8456,
+ -0.8160, +0.4813, +0.3511, -0.0667, +0.7182, -0.5514, +0.3622,
+ -2.3828, +0.6020, +0.0268, +0.3220, -0.4798, -0.1588, -0.6060,
+ +0.0455, -0.1433, -0.5643, -0.4139, +1.0605, -0.3742, +2.4072,
+ +1.2664, +0.1790, +0.8069, -0.1647, +0.2396, +0.6662, -1.2914,
+ -0.2594, +0.4644, +0.3116, -0.1614, -0.7359, -0.9930, -0.4012,
+ +0.1121, -1.4436, -0.0692, -0.3936, -0.4506, -0.8123, +1.3841,
+ +1.2088, +0.9410, +0.1766, -0.7999, +0.2004, +0.2158, -0.4015,
+ -0.0484, -0.3474, +0.0076, -0.7156, -0.5177, +0.8020, -0.1543,
+ +0.0434, -0.2892, +0.1293, +0.5121, +1.2537, -0.1804, +0.2232,
+ -0.3681, -0.4471, -0.5221, +0.0472, -0.4809, +0.5478, -0.3337,
+ +0.0365, -0.6143, +0.7588, -0.4842, +0.1022, +0.4930, +0.5103,
+ +0.7343, +1.5783, +0.8545, -0.9636, -0.3476, +0.5063, +0.0514,
+ +0.3894, -0.8884, +0.0449, +0.5949, -0.2352, +0.4529, +0.2948,
+ +0.0390, -0.7291, +0.1560, +0.0583, -0.0293, +0.0597, +0.1500,
+ +0.7947, -1.3192, -0.1611, -1.8176, +0.9184, -0.4718, +0.7685,
+ -0.1878, -0.3281, -0.4007, -1.2232, -1.0534, +0.7252, -0.6923,
+ +0.3817, +0.7918, +0.4028, +0.9145, -0.0126, +0.1591, -0.2679,
+ +1.3580, +0.0393, +0.1672, -0.4754, +1.0527, -1.0403, +0.6002,
+ +0.1479, +0.5369, -0.1762, +0.2856, +0.3766, +0.0768, -0.3013,
+ +1.0575, +0.6036, +0.1491, +0.6333, -0.2535, +0.1049, +1.1164,
+ -0.3730, -1.5166, +0.5125, +0.1594, +1.6473, -0.6655, +0.4091,
+ +0.3638, -0.5117, -0.2984, +0.3496, -0.3595, -0.3811, -0.7337,
+ -0.0616, +0.0449, -0.2416, -0.0535, -1.3687, +0.3001, +0.0840,
+ -1.5971, +0.7260, -0.0056, +0.3636, -0.3623, +0.2754, -0.6047,
+ -1.2724, +0.5213, -0.0817, +1.6422, -0.2038, +0.5006, +0.7695,
+ +0.9680, +0.4044, +0.9807, -0.1294, -0.6531, -0.7634, +0.1569,
+ +1.2350, +1.2254, +0.7556, -0.2483, +0.0008, +0.2024, +1.1261,
+ +0.0476, -0.1030, +0.8195, -0.2271, +0.2323, +0.3329, -0.5824,
+ -0.1342, +1.5237, +1.2337, -0.8420, -0.3239, -0.1192, -0.3712,
+ -0.4645, -1.4312, -0.8121, -1.2723, -0.3935, -0.0198, -0.0735,
+ +0.7791, -1.3631, -0.8079, +0.0497, -1.1443, +0.1149, -1.0024,
+ -0.7783, +0.5146, -0.0900, +0.2533, -0.3197, +0.8769, +0.6185,
+ -0.4478, -0.2109, +0.9331, +0.1720
+ ],
+ [
+ +0.1914, +0.2367, -0.1629, -0.2121, -0.4821, +0.2042, -0.6208,
+ -0.6690, -0.5308, +0.2751, +0.0058, +0.7246, +0.5435, -0.0560,
+ -0.5556, -0.0165, +0.6507, +0.2775, +0.0431, -0.1270, +0.5966,
+ +0.0977, +0.2673, -0.3136, -0.6983, +0.5473, -0.4528, -0.0306,
+ +0.1088, -0.0717, +0.8475, +1.1961, +0.2308, -0.5281, -0.0913,
+ +0.1937, +0.9934, -0.0981, -0.0031, +0.0337, +0.2783, -0.9124,
+ +0.4286, -0.3317, +0.1689, +0.1181, +0.3386, +0.0006, -0.3645,
+ -0.7711, -0.0095, +0.3991, -0.1333, -0.6688, +0.4254, +0.0559,
+ +0.2671, +0.5579, -0.9046, -0.2728, -0.4878, -0.5582, +0.2866,
+ -0.2315, +0.2442, +0.7093, +0.4266, +0.2287, +0.1558, -0.3636,
+ +0.5561, -1.4425, -0.1192, +0.6250, -0.3334, -0.3746, -0.1556,
+ -0.0636, +0.1641, +0.2846, +0.2501, -0.3944, -0.4040, -0.1150,
+ -0.6399, +0.1609, +0.5772, +0.5262, -0.0361, +0.7536, +0.2497,
+ -0.7278, +0.1851, -0.0259, -0.7170, -0.3231, -0.2127, -0.1993,
+ -0.2452, +0.3888, +0.2922, -0.4279, -0.3269, +0.0756, +0.1988,
+ -0.1777, -0.0172, -0.0312, -0.1341, +0.0269, +0.1057, -0.1237,
+ -0.6615, +0.2952, +0.0767, -0.0778, -0.5447, +0.0285, +0.6785,
+ -0.1794, +0.0174, -0.1047, -0.1765, +0.5859, -0.0837, -0.5167,
+ -0.4280, +0.1787, +0.1762, -0.3390, +0.6731, +0.3160, +1.4737,
+ -0.6632, +0.2942, -0.0664, -0.2121, -0.3356, -0.5989, +0.4079,
+ -0.2348, +0.1857, -0.9283, +0.1377, -0.0273, +0.2580, +0.9982,
+ -0.2876, -0.4685, +0.2032, +0.2644, -0.0163, -0.6819, -0.9446,
+ -1.0937, +0.3750, -0.1436, -0.7771, +0.1031, -0.7357, -0.2943,
+ +0.1850, -0.7978, -0.0747, +0.1661, +1.1391, -0.7675, -0.0677,
+ +0.3038, +0.0354, -0.4304, +0.3333, +0.1617, +0.3656, +1.2621,
+ -0.3526, +0.0040, +0.2239, +0.4336, -0.3180, +0.1273, +0.0488,
+ -0.3459, -0.8226, +0.1833, +0.2386, -0.0214, +0.4261, -0.1491,
+ +0.0678, -0.3771, -0.3311, +0.1703, +0.2722, +0.1684, +0.0372,
+ -0.3637, -0.0246, -0.1785, +0.1548, -0.7042, -0.2042, -0.3849,
+ +0.1776, -0.0536, -0.1493, -0.6161, +0.1739, -0.1201, +0.2798,
+ +0.4395, -0.3635, +0.2738, +0.3116, -0.3052, +0.5248, +0.4516,
+ -0.4132, -0.0536, -0.2435, +0.3823, +0.0218, +0.8631, -0.2524,
+ +0.4060, -0.9034, +0.8162, -0.0182, -0.6250, +1.1502, +0.3362,
+ +0.2115, -0.3169, -0.6787, -0.3379, +0.1962, -0.0973, -0.4042,
+ -0.7209, +0.4764, -0.3201, -0.6573, -0.3488, -0.4370, -0.4269,
+ +0.1515, +0.6850, -0.0542, +0.4701, +0.4224, -0.1287, +0.2937,
+ +0.3044, +0.0041, +0.2738, -0.7350
+ ],
+ [
+ -0.5305, -1.0649, -0.0954, -0.2799, -0.3787, +0.9727, -0.0627,
+ -0.2684, +0.5308, -0.2507, -0.2276, -0.2753, +0.7152, -0.1676,
+ -0.6453, +0.2848, -0.5792, -0.4101, +0.4678, +0.5229, -0.5333,
+ +0.2654, -0.1755, -0.2015, -0.1202, +0.7424, -0.0436, -0.7146,
+ -0.3689, +0.3063, -0.0962, -0.5648, +0.3302, +0.8726, +0.4133,
+ +0.3269, -0.3124, -0.3711, +0.0620, +0.1089, +0.7904, -0.6871,
+ +0.1509, -0.6424, +0.6935, +0.1535, -0.2352, +0.2431, +0.2551,
+ -0.9536, -0.6756, -0.5438, +0.5175, +0.0297, +0.3081, +0.7367,
+ -0.5743, +0.5190, -0.6644, -0.2655, -0.8614, +0.5008, +0.1180,
+ -0.6145, +0.0548, -0.0824, +0.1499, -0.4286, -0.2922, +0.1617,
+ +0.4914, -0.1181, -0.0810, -0.5932, -0.1382, +0.2021, -0.2492,
+ +0.4315, -0.3313, -0.7047, -0.1362, -0.6261, -0.8227, -0.2876,
+ -0.3360, -0.0240, +0.4826, -0.3108, -1.4351, -0.0640, -0.0199,
+ +0.5721, +0.2496, -0.3540, -0.6179, -0.1694, +0.3353, -0.1535,
+ -0.2695, +0.0006, -0.0797, +0.6059, -0.0136, -0.1401, -0.1369,
+ +0.5776, -0.3561, -0.7428, +0.1167, -0.2765, +0.2429, -0.5045,
+ +0.2792, -0.3781, +0.1033, -0.2574, -0.1043, -0.2264, +0.4170,
+ +0.4963, +0.1617, -1.0455, +0.0243, +0.7325, +0.1549, +0.2681,
+ -0.0576, +0.7945, -0.1418, +0.9368, -0.4814, -0.5513, -0.3667,
+ -0.9507, -0.5204, +0.1824, -0.0299, -0.3973, -0.1318, +0.1508,
+ +0.6482, -0.3319, +0.3144, -0.0892, -0.4015, -0.1038, -0.0171,
+ -0.1544, +0.0384, +0.0638, +0.1878, +0.4846, +0.3388, -0.2064,
+ +0.0282, +0.0187, -0.2866, +0.2655, +0.1010, -0.3126, +0.2875,
+ -0.2012, -0.5520, -0.7519, -0.0311, -0.4679, -0.2289, -0.1862,
+ -0.6687, -0.0894, -0.4530, -0.4726, +0.2286, +0.4884, +0.2238,
+ -0.4041, +0.4382, +0.0763, +0.2040, +0.1290, -0.1270, -0.3557,
+ -0.3726, +0.2727, +0.1078, -0.3465, -0.1650, +0.1213, +0.1463,
+ +0.4907, -0.6272, +0.2849, -0.1256, -0.0692, -0.1280, +0.6426,
+ +0.8455, -0.2999, +0.2388, +0.3314, +0.0211, +0.1282, +0.7080,
+ +0.2266, -0.4417, -0.5596, +0.0456, +0.0472, -0.0761, +0.3607,
+ +0.0925, +0.5921, +0.5351, -0.1387, -0.0664, +0.0244, +0.0458,
+ -0.1461, +0.4734, -0.3399, +0.1727, -0.3891, -0.2727, +0.1968,
+ +0.3090, -0.2189, +0.0718, -0.4483, -0.5429, -0.1845, -0.6284,
+ +0.1738, +0.0977, +0.1842, +0.1739, -0.5167, -1.2017, +0.1491,
+ +0.6558, +0.4300, +0.8097, +0.0739, -0.3018, -0.1147, +0.2953,
+ +0.2045, -0.2690, -0.2379, -0.3909, -0.1637, -1.1258, -0.3999,
+ +0.3399, +0.0625, -1.1293, +0.3265
+ ],
+ [
+ +0.2985, -0.6516, +0.4775, -0.0140, -0.4299, -0.1279, -0.3789,
+ -0.8213, -0.0525, +0.0010, +0.0503, -0.2211, +0.0995, +0.1976,
+ -0.4291, +0.0379, +0.2930, +0.3705, -0.2469, -0.0770, +0.4237,
+ +0.4334, +0.2506, -0.2329, -0.4291, +0.1146, +0.0874, +0.3548,
+ +0.0268, +0.0869, +0.3078, +0.0402, -0.4679, +0.8574, -0.3867,
+ +0.0835, +0.6660, -0.4280, -0.6492, -0.1042, -0.6310, -0.0259,
+ -0.0944, +0.1484, +0.0317, -0.0098, -0.0450, +0.5161, +0.0257,
+ +0.0005, -0.0494, +0.0465, -0.2364, +0.1916, +0.5391, +0.0028,
+ +0.9037, -0.0930, +0.2142, +0.1406, -0.1165, -0.0293, +0.3984,
+ -0.4787, -0.0384, +0.1164, +0.1826, -0.3080, +0.0997, +0.6248,
+ -0.1437, -0.1716, -0.3102, -0.0448, -0.3595, +0.9930, -0.2071,
+ +0.9864, +0.3101, +0.1298, -0.1277, -0.2569, -0.3749, -0.5782,
+ -0.2509, +0.3860, +0.4451, +0.1810, -0.1763, +0.1142, -0.1178,
+ +0.6319, +0.5940, +0.3328, -0.0479, -0.4712, -0.1765, -0.1778,
+ -0.2369, +0.2725, -0.2929, -0.2874, -0.1177, +1.2907, +0.3847,
+ -0.2287, +0.2036, +0.0735, +0.3001, -0.2437, +0.2036, -0.3419,
+ +0.4514, +0.2280, -0.2737, +0.3508, -0.1208, -0.4684, +0.0684,
+ +0.0490, +0.3631, -0.3185, +0.0020, -0.1861, -0.0268, -0.1274,
+ -0.0160, -0.1210, +0.1408, +0.4183, -0.3518, -0.4569, +0.1282,
+ -0.2319, +0.2512, -0.3592, +0.0540, -0.6120, -0.1856, -0.0308,
+ +0.1304, -0.3050, +0.4704, +0.3629, +0.4371, -0.0915, -0.2140,
+ -0.1166, +0.2194, +0.2926, -0.3646, -0.5791, +0.3207, -0.0810,
+ +0.1578, -0.3067, -0.3441, +0.4426, +0.1421, -0.4309, +0.1017,
+ -0.1754, +0.3775, +0.0048, -0.1489, +0.2823, +0.4104, +0.5312,
+ -0.4843, -0.3423, -0.7578, -0.0118, +0.0645, +0.2197, +0.3624,
+ -0.0137, +0.5216, -0.4339, +0.1736, +0.3054, +0.5684, +0.4813,
+ +0.2408, +0.0112, -0.0637, -0.1112, +0.4575, -0.4203, -0.2375,
+ -0.1869, -0.1914, +0.5073, -0.2876, +0.2371, +0.3740, +0.8589,
+ +0.1326, +0.0220, -0.0639, +0.1505, -0.3579, -0.1986, +0.6998,
+ +0.1042, -0.2976, -0.0343, -0.2863, -0.0873, -0.3928, -0.3351,
+ +0.0212, +0.3023, -0.1197, +0.1894, +0.1328, -0.0621, +0.5685,
+ +0.1133, +0.0837, -0.2829, -0.4764, +0.0455, +0.7453, +0.1416,
+ +0.3608, +0.1513, +0.8440, +0.1792, +0.6390, +0.0493, +0.4155,
+ -0.2832, -0.0157, +0.0372, +0.0957, +0.8445, -0.2723, +0.3604,
+ -0.4921, +0.8836, +0.2896, -0.0577, -0.4621, +0.1412, +0.1202,
+ -0.1868, -0.0938, +0.0032, +0.4614, -0.0066, +0.1586, +0.0146,
+ +0.0698, +0.1539, -0.3187, +0.2030
+ ],
+ [
+ +0.1593, +0.0673, -0.2547, -0.4164, -0.7417, -0.0947, -0.0055,
+ -0.3648, +0.1302, +0.0556, +0.3797, -0.0956, -0.3993, +0.4257,
+ +0.0176, +0.1360, +0.1971, +0.2499, -0.1564, -0.1776, -0.3742,
+ +0.1572, +0.1570, -0.1127, -0.4366, -0.0255, -0.0662, -0.2298,
+ +0.5912, +0.0107, -0.5855, +0.8709, +0.0119, -0.4277, +0.4122,
+ -0.0525, +0.1397, -0.3018, +0.6338, -0.1003, -0.1246, +0.1427,
+ -0.1638, -0.2808, +0.1959, +0.7202, +0.1200, -0.2316, +0.1650,
+ +0.2782, +0.4346, +0.0802, -0.2768, +0.4015, +0.4213, -0.2252,
+ +0.2750, -0.4314, +0.0254, +0.3742, -0.3016, -0.2429, -0.6429,
+ +0.3386, -0.0971, +0.1080, -0.2511, +0.2752, +0.6792, +0.0080,
+ +0.2215, +0.0504, -0.7341, -0.1637, +0.0300, +0.3588, -0.3274,
+ +0.1918, +0.3612, +0.5223, +0.1182, +0.6870, -0.3318, -0.2261,
+ +0.2921, -0.4550, +0.1582, +0.2888, -0.2669, +0.1638, -0.6216,
+ +0.6262, -0.6351, +0.4334, +0.0973, -0.1839, +0.0321, -0.5037,
+ -0.2649, -0.0552, -0.1270, -0.2993, +0.6138, +0.4850, +0.3384,
+ -0.5962, -0.6860, +0.0256, -0.2307, -0.2724, -0.1256, +0.6033,
+ +0.2383, -0.0195, -0.0630, -0.4518, -0.3697, +0.8157, -0.5800,
+ +0.7963, -0.3184, +0.0568, -0.3475, -1.0642, +0.7602, +0.5601,
+ -0.0858, +0.3643, -0.4833, -0.2227, +0.5590, -0.0992, -0.6019,
+ -0.1924, -0.1267, -0.0245, -0.5970, -0.4330, +0.1239, -1.0436,
+ -0.3711, -0.3417, -0.1319, +0.4664, +0.2170, -0.1831, +0.2072,
+ -0.1819, -0.1112, +0.5897, +0.4138, -0.1745, +0.0069, +0.5481,
+ -0.2551, -0.1321, +0.3068, +0.1709, -0.3829, +0.3386, +0.0268,
+ -0.1402, +0.2465, +0.6522, -0.6667, +0.5380, +0.8128, +0.0613,
+ -0.6277, +0.2254, +0.0309, -0.1557, +0.0074, +0.0135, -0.5031,
+ +1.1359, +0.0562, -0.6937, +0.1323, +0.5053, +0.0667, -0.5712,
+ -0.3070, +0.7015, +0.2751, -0.2162, -0.2375, -0.5178, +0.6995,
+ -0.2979, +0.2039, -0.2180, +0.6633, +1.0514, +0.7916, +0.4500,
+ +0.3561, -0.2985, -0.7077, +0.0663, -0.6082, -0.4968, +0.0381,
+ -0.3695, -0.1673, -0.1879, +0.3407, -0.1239, -0.4802, -0.1217,
+ +0.5713, +0.3748, +0.0324, -0.2357, +0.1038, +0.2317, -0.2465,
+ -0.1541, +0.0306, -0.1631, -0.6562, -0.1803, -0.1607, -0.1324,
+ +0.2002, +0.0519, +0.1840, +0.2045, +0.1503, -0.2435, -0.1554,
+ -0.1546, +0.1199, -0.7402, +0.5261, -0.2881, -0.7153, +0.8782,
+ -0.2197, +0.3991, +0.1447, +0.2319, +0.2099, +0.3708, +0.1532,
+ +0.0936, -0.0373, +0.3127, -0.0938, -0.2230, +0.3024, -0.2431,
+ +0.1687, +0.5369, -0.6572, +0.0691
+ ],
+ [
+ -0.9205, -0.6407, -0.3495, -0.1292, -0.2954, -0.2824, -0.5187,
+ -0.1155, +0.1093, +0.0234, -0.0082, +0.0037, +0.4904, -0.0225,
+ +0.5050, +0.2188, +0.4062, +0.0352, -0.0210, -0.7050, +0.1355,
+ +0.6423, -0.6829, -0.3672, -0.2787, +1.0915, +0.0694, -0.4533,
+ +0.6736, +0.2396, +0.0699, -0.7669, -0.8898, -0.5430, -0.6663,
+ +0.1795, -0.8685, -1.0686, +0.1690, -0.0744, -0.2449, +0.3012,
+ -0.1798, -0.3383, +0.4449, -0.8733, +0.0579, -0.1487, +0.4444,
+ -0.7043, +0.0664, -0.0857, +0.0319, -0.1203, -0.7229, +0.1748,
+ -0.2829, +0.8293, +0.1026, -0.2243, +0.3540, -0.1479, -0.5573,
+ +0.2202, +0.1052, +0.1821, +0.2858, -0.2647, +0.0733, -0.5249,
+ +0.9333, +0.1392, -0.4069, +0.2683, -0.0897, -0.1305, -0.2437,
+ -0.2181, -0.2209, +0.0429, -0.1205, +0.1112, -0.1993, -0.0594,
+ -0.0557, -0.3577, -1.1923, +0.0014, -0.6420, +0.1696, -0.9703,
+ +0.7222, -0.0252, +0.1879, +0.3040, +0.2103, +0.0601, +0.0977,
+ -0.2715, +0.2625, -0.7554, -0.0208, +0.0804, +0.1709, -0.0788,
+ +0.2233, +0.1557, -0.4419, -0.1501, -0.1374, -0.0640, -0.0173,
+ +0.5292, -0.3886, +0.8104, +0.1731, +0.4099, +0.0172, +0.2222,
+ +0.4837, -0.1392, -0.2487, -0.3176, +0.9001, +0.5629, -0.0966,
+ -0.7590, +0.7981, -0.3387, +0.1281, -0.0880, -0.1736, -0.4041,
+ +0.2927, +0.2257, -0.2617, +0.0081, -0.0981, -0.3232, -0.8960,
+ -0.4555, -1.0944, +0.2450, -0.6488, -0.3626, +0.3229, -0.7959,
+ -0.9218, -0.1168, -0.0386, -0.0772, -0.3662, -0.2033, +0.5171,
+ -0.2605, +0.2099, +0.0587, -0.1684, +0.5608, -0.2795, +0.4050,
+ -0.2488, -0.0009, -0.3548, +0.2713, +0.2540, +0.4301, +0.1538,
+ +0.5952, +0.0035, -0.0855, +0.1828, +0.5056, -0.0285, -0.2480,
+ +0.3974, -0.1071, +0.7901, -0.1271, +0.0085, +0.0022, -0.0033,
+ -0.5544, -0.3821, -0.4543, +0.5065, -0.2156, +0.4301, -0.0898,
+ +0.0038, -0.3771, -0.1299, +0.3414, +0.2850, +0.2536, +0.2735,
+ -0.2499, +0.1810, -0.8185, +0.2789, +0.0172, +0.1249, +0.5116,
+ -0.3276, +0.0151, -0.1496, -0.3928, +0.0160, +0.1973, +0.6946,
+ -1.0572, +0.2596, +0.5213, +0.1074, +0.0397, +0.0158, -0.1003,
+ +0.0849, -0.6143, +0.0286, +0.1211, -0.3642, -0.2030, -1.3791,
+ -0.2391, -0.0444, -0.2008, -0.4846, +0.4913, -0.1766, -0.7605,
+ -0.6237, +0.0567, -0.2466, +0.8322, +0.1745, -0.5219, -0.2627,
+ -0.0347, +0.0840, +0.8085, -0.8310, -0.2293, -0.5016, +0.3874,
+ -0.3295, -1.6434, -0.0489, -0.2061, +0.2168, -0.8213, -0.3119,
+ +0.3437, -0.3040, +0.2633, -0.6758
+ ],
+ [
+ -0.1224, +0.1807, +0.0476, -0.1733, -0.2275, -0.6607, +0.5602,
+ +0.2290, +0.4946, -0.3229, +0.2211, +0.5021, +0.2795, -0.4379,
+ -0.4183, +0.0239, -0.0520, -0.3631, +0.5901, -0.8528, -0.3056,
+ -0.0029, -0.2342, -0.2650, -0.0214, +0.1637, +0.3739, -0.1126,
+ -0.0839, -0.1313, +0.0461, -0.5930, +0.2383, +0.3599, -0.3978,
+ -0.2775, +0.1222, -0.6615, +0.1524, -0.2367, -0.3254, -0.1699,
+ -0.2446, +0.0040, -0.2987, -0.0853, +0.0497, -0.1563, -0.0894,
+ -0.0426, +0.3357, -0.5865, -0.3145, -0.2334, +0.4475, +0.6045,
+ -0.1532, -0.5043, -0.3072, -0.2198, +0.1998, -0.1104, +0.1984,
+ -0.0500, -0.1988, -0.0554, +0.6667, +0.2950, +0.4560, +0.0905,
+ +0.8948, +0.4141, +0.0889, +0.2876, +0.8547, +0.0443, +0.4713,
+ +0.0125, +0.4692, +0.0556, +0.3437, -0.2034, +0.0493, +0.0987,
+ -0.5343, -0.5624, +0.5240, +0.6423, +0.0898, -0.3092, -0.3829,
+ +0.4628, -0.3896, -0.2335, +0.4425, +0.1577, -0.3808, +0.7042,
+ -0.1099, +0.2177, -0.4898, -0.2984, +0.2604, -0.0835, -0.5402,
+ +0.0921, -0.1487, +0.1235, -0.0274, +0.1865, -0.3032, +0.1477,
+ -0.8785, +0.2594, +0.2667, +0.1290, +0.4497, -0.5279, +0.2041,
+ -0.2774, -0.2247, +0.1755, +0.2179, +0.2883, -0.2374, -0.2710,
+ -0.6661, +0.2488, -0.2718, +0.3415, -0.0217, +0.1544, +0.2134,
+ +0.0385, -0.3567, +0.1695, +0.3289, +0.5405, -0.1381, -0.5697,
+ -0.1969, -0.0151, -0.4153, -0.3042, -0.4061, -0.9120, -0.3237,
+ -0.4619, -0.2990, -0.3770, -0.1387, +0.0114, -0.7310, +0.1120,
+ +0.1241, -0.2797, +0.0220, -0.0135, +0.3210, -0.6078, -0.4427,
+ -0.1668, +0.0040, -0.6242, +0.8404, -0.5844, +0.6519, +0.2185,
+ -0.0381, -0.3671, +0.4789, +0.0554, +0.1012, +0.0864, -0.0963,
+ -0.3227, -0.1091, +0.5487, -0.5835, +0.2718, +0.6050, -0.0901,
+ -0.1951, -0.1213, -0.1814, -0.2178, -0.2861, -0.3037, -0.0871,
+ -0.4600, +0.2746, -0.5300, -0.5216, +0.7110, +0.1588, +0.0332,
+ -0.7698, +0.7929, +0.4748, -0.0828, -0.1833, +0.0244, -0.4698,
+ -0.2932, +0.7227, +0.3943, +0.6195, -0.4069, +0.5510, +0.4044,
+ -0.0376, +0.1132, +0.2594, +0.2696, -0.0090, -0.5220, +0.3694,
+ +0.2535, +0.2949, -0.3292, +0.1338, -0.1614, -0.4826, -0.6461,
+ -0.0891, +0.6627, -0.4489, +0.1577, +0.7618, +0.4944, -0.3768,
+ -0.0778, +0.0620, -0.2107, +0.0132, -0.1325, -0.0489, +0.2153,
+ -0.2410, +0.1829, +0.1007, -0.1304, -0.2355, -0.7770, +0.3267,
+ -0.3735, -0.2366, +0.1976, -0.1219, +0.3927, +0.2558, -0.0528,
+ +0.6828, +0.6081, -0.0640, -0.1716
+ ],
+ [
+ +0.5773, +0.4005, +0.2367, -0.2554, -0.0570, -0.3491, -0.1217,
+ +0.1797, +0.2174, +0.2224, +0.1831, +0.3781, -0.1077, -0.4088,
+ -0.3937, +0.1849, +0.6256, +0.1961, -0.3727, -0.1188, -0.2571,
+ -1.0813, +0.1191, -0.0072, +0.3410, -0.1113, +0.0178, +0.0221,
+ -0.2449, +0.1956, +0.4295, +0.0470, -1.0544, +0.3908, -0.2403,
+ +0.0338, +0.1049, -0.1989, -0.6795, +0.1352, +0.3580, -0.0550,
+ +0.1559, +0.1566, -0.2989, +0.3722, +0.3373, +0.1194, -0.0818,
+ +0.0315, +0.2551, +0.0579, +0.0571, +0.2316, -0.0330, -0.4553,
+ -0.3433, -0.1070, -0.3248, +0.3737, -1.0162, -0.2596, -0.5808,
+ +0.0423, -0.0359, -0.5898, +0.0525, +0.4582, +0.0296, -0.4855,
+ +0.1305, -0.5326, +0.1646, +0.2046, -0.6652, -0.1011, +0.0367,
+ +0.0979, -0.1058, -0.8457, -0.1656, -0.5374, +0.7134, -0.6131,
+ +0.0588, -0.5346, -0.4256, +0.2006, +0.5099, -0.5682, -0.3149,
+ -0.1147, -0.9188, -0.0958, -0.2129, -0.6066, -0.0144, -0.2814,
+ +0.0966, -0.1576, +0.1431, -0.1485, +0.2355, -0.1664, -0.0622,
+ -0.0011, -0.0136, +0.1440, -0.6193, -0.1540, -0.1121, -0.2571,
+ +0.0337, +0.5311, -0.7750, +0.2000, +0.1121, -0.1559, -0.5731,
+ +0.3587, -0.0157, +0.0921, +0.2889, -0.0086, -0.1163, -0.1031,
+ +0.4536, +0.0260, +0.4147, -0.0971, -0.6322, -0.1779, +0.1588,
+ +0.1106, -0.6539, -0.1867, -0.0918, -0.4986, +0.1861, -0.8405,
+ +0.0673, +0.1445, -0.2178, +0.0211, -0.3776, -0.2325, -0.7193,
+ -0.2383, +0.1055, -0.3297, -0.6075, -0.0166, -0.0599, +0.3519,
+ +0.2016, -0.1683, -0.0618, +0.0966, +0.4444, +0.0336, -0.0360,
+ -0.0038, -0.0901, +0.0575, +0.1595, +0.0420, +0.3149, +0.1565,
+ -0.5973, +0.0455, -0.2269, +0.7422, -0.1403, +0.1556, -0.5552,
+ -0.1018, -0.1478, -0.1449, -0.3502, -0.3411, -0.6673, +0.1856,
+ -0.1387, -0.0826, +0.2279, +0.3411, +0.3251, -0.8518, +0.4285,
+ -0.3885, +0.0961, +0.2770, +0.5029, +0.0081, -0.0688, +0.2335,
+ -0.2451, +0.0313, -0.1630, +0.4845, -0.1214, -1.0611, -0.9483,
+ -0.0859, +0.7039, -0.0264, +0.1340, -0.3957, -0.1174, +0.1597,
+ -0.1261, +0.0289, +0.1340, +0.1144, -0.1680, +0.3226, -0.1484,
+ -0.3115, +0.0072, -0.3260, +0.4108, +0.1639, -0.9366, +0.4429,
+ -0.1095, -0.2999, -0.0186, -0.5972, -0.1980, -0.2521, +0.2721,
+ +0.2089, +0.1511, -0.1393, -0.4629, -0.8785, +0.0836, -0.2853,
+ -0.3804, -0.4894, +0.1630, -0.3580, -0.0938, +0.3543, -0.1880,
+ +0.4280, -0.0910, -0.1145, -0.4794, -0.0023, +0.0837, +0.2889,
+ -0.0548, -0.1878, -0.2514, +0.2941
+ ],
+ [
+ +0.1971, +0.1297, +0.3127, -0.1900, +0.2138, -0.5950, -0.0518,
+ +0.5522, +0.7271, -0.4612, +0.0603, -0.0771, +0.0421, +0.2994,
+ -0.7150, -0.6847, +0.4128, +0.2148, +0.7659, -0.1203, +0.0513,
+ -0.6664, -0.4696, -0.1599, -0.0016, -0.2961, +0.0878, +0.1158,
+ +0.3799, +0.1267, +0.2748, -0.7240, -0.1967, +0.8070, -0.4856,
+ +0.2131, +0.4358, -0.0098, -0.1944, +0.7715, +0.0676, +0.2041,
+ -1.1034, -0.3384, +0.6977, +0.1520, +0.3113, -0.3375, +0.1434,
+ +0.0769, +0.4804, -0.4066, -0.1047, +0.1328, -0.6792, +0.1742,
+ +0.1389, -0.0741, -0.2742, +0.1880, -0.7640, -0.3254, +0.0108,
+ -0.5652, -0.7209, -0.2656, +0.4557, +0.1764, -0.2182, -0.3519,
+ -0.1209, +0.1609, +0.2707, -0.0814, -0.2446, -0.1418, +0.0642,
+ -0.4075, -0.3181, +0.1488, -0.3156, -0.0194, -0.1112, -0.0664,
+ +0.8506, +0.0797, +0.0967, +0.0589, +0.2103, -0.1941, -0.0901,
+ -0.1765, +0.2050, -0.5338, +0.2230, +0.0117, +0.4295, -0.6978,
+ -0.2315, -0.1358, -0.1298, +0.1919, +0.7137, +0.4695, -0.2569,
+ +0.3268, -0.1098, -0.6414, -0.3317, -0.5824, +0.3109, +0.5197,
+ +0.0289, +0.2862, -0.1670, -1.1588, -0.5376, +0.7066, -0.4736,
+ -0.6062, +0.0383, +0.4817, +0.3675, -0.2474, -0.1373, +0.6097,
+ +0.1162, +0.0026, +0.5885, +0.5167, +0.1943, -0.2286, -0.0977,
+ -0.0914, -0.2177, -0.4933, -0.2152, +0.3393, +0.4035, +0.4174,
+ -0.0249, -0.1241, +0.2562, +0.2692, -0.4636, +0.2140, -0.2008,
+ -0.2862, -0.0860, -0.3197, -0.2499, +0.4412, -0.1225, -0.0678,
+ -0.5300, +0.0226, +0.5928, +0.4112, +0.3408, +0.3258, +0.3220,
+ +0.6597, -0.3444, +0.3276, -0.3681, -0.4247, -0.2516, +0.2093,
+ -0.5528, +0.0715, +0.3478, +0.5149, +0.7822, -0.1180, +0.3608,
+ -0.1642, +0.1633, -0.3586, +0.3944, -0.3117, +0.3464, +0.2220,
+ -0.1847, +0.2722, -0.1410, +0.6442, +0.2111, -0.5102, +0.0657,
+ -0.0787, +0.1314, +0.1596, +0.3922, +0.4387, +0.3768, +0.0938,
+ -0.2301, -0.4222, -0.2457, +0.1377, +0.0971, -1.0034, -0.6783,
+ -0.2950, +0.6848, +0.3718, -0.0991, +0.3351, +0.4113, -0.0339,
+ -0.0272, +0.1386, +0.1174, +0.5951, -1.3231, +0.1352, -0.0537,
+ -0.0648, -0.0348, -0.3936, +0.4308, -0.5901, +0.3274, +0.4185,
+ +0.2364, -0.0838, +0.1790, -0.2632, -0.5750, -0.3647, -0.7477,
+ -0.3476, +0.6007, +0.2378, -0.2952, -0.8994, +0.0876, +0.5734,
+ -0.1559, +0.1650, +0.4103, -0.0516, -0.4388, +0.6463, -0.4788,
+ +0.0584, +0.0616, +0.1933, -0.1242, -0.5378, -0.0676, +0.5118,
+ +0.2571, +0.5174, +0.5873, -0.0766
+ ],
+ [
+ +0.0258, +0.0557, +0.0314, -0.1428, +0.1264, +0.2882, +0.1731,
+ +0.0442, -0.6218, -0.1942, -0.3289, +0.2295, -0.1792, -0.3100,
+ -0.3131, -0.3692, -0.1941, +0.5551, +0.0759, +0.0739, -0.2385,
+ -0.4435, -0.1647, +0.3799, +0.1403, -0.2910, -0.1646, -0.1996,
+ -0.0809, -0.3370, +0.1309, -0.1390, +0.1873, -0.1753, -0.1671,
+ +0.0357, +0.0419, +0.1547, -0.2335, +0.3820, +0.0704, +0.1450,
+ +0.3619, -0.4785, +0.0094, +0.2105, -0.0015, -0.4892, +0.0153,
+ +0.1744, +0.6894, +0.0375, -0.2539, +0.3752, -0.0939, +0.0410,
+ -0.0005, +0.0414, -0.5551, +0.0786, +0.2726, -0.2081, +0.1608,
+ +0.0056, -0.3801, +0.2772, -0.0787, -0.3693, -0.1018, +0.1075,
+ +0.0577, +0.1752, +0.2847, +0.1793, -0.2131, +0.1969, +0.0438,
+ +0.0763, -0.2106, +0.1562, -0.0079, -0.0419, -0.6081, -0.3683,
+ -0.0284, +0.0196, +0.2458, +0.0486, +0.3165, -0.1404, +0.0881,
+ -0.2001, +0.0943, -0.2257, +0.1904, -0.2215, -0.0143, +0.1636,
+ -0.1493, +0.0209, -0.3232, -0.1058, +0.1450, +0.2953, -0.0649,
+ -0.1792, -0.4404, +0.0648, -0.0782, -0.0980, -0.1962, +0.0114,
+ -0.4174, +0.1230, +0.2255, -0.4465, +0.0099, -0.0002, -0.0327,
+ -0.2182, -0.0044, +0.1385, +0.2404, -0.1530, -0.2449, -0.1187,
+ -0.1197, -0.0196, +0.0636, +0.2732, -0.0020, -0.3308, -0.2261,
+ -0.2961, -0.0110, +0.1877, -0.1727, -0.0579, +0.3186, -0.1244,
+ +0.4831, -0.3772, +0.2442, -0.5991, -0.0244, -0.0651, +0.3005,
+ +0.2811, -0.1175, -0.1017, +0.0363, +0.1163, -0.1070, +0.2171,
+ -0.2766, -0.1591, -0.2473, +0.2177, -0.5437, +0.2643, +0.1680,
+ -0.2968, -0.1783, -0.3845, -0.2310, -0.1699, +0.1597, +0.0023,
+ +0.0930, +0.3626, +0.1183, +0.3463, +0.1107, +0.1850, +0.1242,
+ -0.0231, -0.2174, -0.2698, -0.5214, -0.3067, +0.0808, +0.6624,
+ -0.0719, +0.0046, +0.2116, -0.0666, +0.1001, -1.0531, +0.4140,
+ -0.6715, -0.0883, -0.2107, +0.1025, -0.2391, +0.0068, +0.5813,
+ +0.0922, -0.7574, +0.1401, +0.1576, -0.0085, -0.2051, +0.2217,
+ +0.0145, +0.0643, +0.2933, -0.1660, -0.0310, +0.3889, +0.2739,
+ +0.0619, -0.0057, -0.0851, -0.3741, -0.0350, +0.0032, -0.1186,
+ +0.3271, -0.7010, -0.0641, -0.2619, +0.2942, +0.0946, -0.2396,
+ -0.0092, +0.2894, +0.4296, -0.1338, +0.4397, -0.3429, +0.5862,
+ +0.2123, -0.0220, +0.0683, -0.0801, -0.2240, +0.1695, -0.0177,
+ +0.1851, -0.2303, +0.1154, -0.0554, -0.1827, +0.0404, +0.5515,
+ -0.3435, +0.1356, -0.6155, +0.0421, +0.4062, -0.1319, -0.1664,
+ +0.2044, -0.3144, +0.3057, +0.5167
+ ],
+ [
+ +0.2190, +0.5299, +0.0416, -0.0133, +0.2273, +0.1847, +0.2117,
+ -0.3650, +0.1088, +0.7693, +0.2472, -0.1210, -0.3569, -0.1793,
+ -0.3154, +0.2999, +0.6809, +1.1643, -0.4968, -0.0260, -0.3963,
+ +0.2722, -0.2396, +0.0662, -0.1695, -0.3343, -0.4404, +0.2240,
+ -0.2892, +0.3186, +0.0070, -0.3156, +0.5497, +0.1461, +0.4193,
+ +0.5595, -0.1487, +0.2295, -0.1106, +0.8187, +0.2716, -0.3308,
+ -0.2466, +0.7375, -0.5231, -0.8374, -0.1546, +0.8101, +0.0305,
+ +0.4414, +0.9101, -0.0790, -0.7719, -0.1223, +0.2108, -0.3328,
+ -0.1319, +0.0044, -0.7621, -0.2411, -0.3317, -0.3602, +0.3811,
+ -0.5627, -0.3574, +0.1514, -0.1217, +0.1223, -0.3627, -0.3312,
+ +0.0908, +0.3559, -0.2127, +0.4198, -0.1993, +0.5076, +0.6647,
+ +0.6660, -0.3889, +0.3641, +0.0583, +0.6410, +0.3024, +0.7780,
+ -0.0566, -0.0725, +0.0005, -0.6199, +0.1416, -0.1018, +0.1975,
+ +0.0407, -0.6696, +0.1270, +0.2403, -0.0984, +0.1143, -0.1629,
+ +0.5482, -0.5193, -0.0165, +0.5192, +0.7334, -0.1055, -0.0946,
+ -0.2747, -0.9139, +0.5439, -0.0660, -0.1288, +0.0253, -0.3988,
+ -0.4482, +0.7088, +0.5435, -0.5111, +0.0793, +0.0429, -0.4865,
+ +0.4337, +0.3207, -0.1065, +0.5435, +0.0121, +0.0708, +0.4475,
+ +0.0082, -0.0752, +0.5082, +0.5027, -0.4079, -0.1469, -0.0291,
+ -0.2024, +0.4415, +0.6201, +0.0561, +0.7860, -0.0309, -0.4140,
+ -0.4525, -0.0112, -0.2588, -0.1160, -0.1658, -0.3977, -0.1903,
+ +0.0040, +0.5195, -0.5027, +0.1395, +0.3001, -0.0364, -0.0070,
+ -0.1940, -0.0794, -0.7707, +0.0793, +0.2436, -0.2028, +0.7458,
+ -0.4411, +0.3906, -0.3629, -0.3652, -0.1732, +0.0129, -0.1646,
+ +0.1341, +0.3027, +0.3714, +0.8555, +0.0846, -0.1275, +0.1576,
+ -0.5475, +0.2914, -0.4467, -1.0526, +0.4156, +0.1801, +0.5511,
+ -0.2876, -0.3708, +0.4191, -0.5156, -0.5698, -0.2032, -0.3767,
+ +0.9636, +0.0591, -0.2111, -0.2921, +0.2434, +0.1629, +0.5713,
+ -0.0247, -0.3819, -0.0096, +0.1990, +0.1771, +0.1748, -0.6692,
+ +0.6622, +0.8074, +0.1628, -0.0205, +0.2880, -0.4322, +0.2115,
+ -0.7574, +0.6190, +0.0132, -0.2705, -0.5313, -0.2903, +0.6175,
+ -0.2226, -0.1388, -0.5078, -0.6529, +0.2888, +0.2174, +0.3050,
+ -0.2648, -0.1298, +0.0513, +0.0026, +0.2277, +0.6358, -0.3906,
+ -0.3793, +0.6255, -0.4248, -0.5383, +0.2805, +0.1700, +0.1024,
+ -0.2525, +0.0197, +0.0756, +0.2159, -0.4651, -0.3313, -0.4396,
+ +0.4773, -0.5920, -0.1574, -0.0513, -0.7548, +0.1198, +0.6633,
+ -0.0992, +0.4179, +0.5154, +0.1625
+ ],
+ [
+ +0.4234, +0.4392, -0.2747, -0.2705, -0.6422, -0.0934, +0.0052,
+ -0.0935, +0.0754, +0.1551, -0.0347, +0.1696, +0.2298, +0.1517,
+ -0.1544, -0.7179, +0.3967, -0.4788, +0.2861, -0.2384, +0.3171,
+ +0.3328, -0.2257, -0.2352, +0.3594, +0.1360, -0.1726, -0.0534,
+ -0.3732, +0.4586, +0.6655, +0.1862, -0.0504, -0.5245, -0.2335,
+ -0.1044, +0.1731, -0.4958, +0.3857, +0.1822, -0.2132, +0.2401,
+ -0.1770, -0.3829, -0.1447, +0.0365, +0.1743, -0.0582, +0.1387,
+ +0.1938, -0.4010, +0.2540, -0.1261, -0.1798, -0.1797, -0.3228,
+ -0.1266, -0.0110, +0.4102, +0.1474, -0.3089, -0.3147, -0.4659,
+ +0.7590, -0.0920, -0.0002, -0.4629, -0.1343, -0.1630, -0.1713,
+ +0.0623, +0.1539, -0.2611, +0.2111, +0.0032, +0.0254, -0.1147,
+ -0.5070, +0.2582, +0.4978, -0.2704, +0.2963, -0.2424, -0.2377,
+ +0.0542, -0.5813, -0.3314, +0.0234, +0.1353, +0.1885, -0.4818,
+ +0.4946, -0.3437, -0.0408, -0.3601, +0.1318, +0.2486, -0.3088,
+ -0.4411, +0.5277, -0.1257, -0.4646, -0.4539, -0.0095, +0.6496,
+ -0.1052, -0.6746, +0.3025, -0.0855, -0.1113, +0.1304, -0.2482,
+ +0.0107, -0.3439, -0.1315, -0.2316, +0.1768, -0.2268, -0.1223,
+ -0.5271, +0.3784, -0.5252, -0.2377, +0.1388, -0.3378, +0.2181,
+ -0.0689, +0.2941, +0.0044, +0.1891, -0.0509, +0.0914, +0.2977,
+ -0.1663, -0.3623, -0.0772, +0.0197, -0.2234, -0.3112, -0.0609,
+ -0.1381, +0.0890, +0.0460, +0.0142, -0.4865, -0.1751, +0.2371,
+ -0.1852, -0.6088, +0.0152, -0.0823, -0.1289, -0.2044, -0.7310,
+ -0.2056, +0.1072, +0.0079, -0.1789, +0.1253, -0.2312, -0.3431,
+ -0.1412, -0.0953, -0.3622, +0.3766, +0.3203, +0.1998, -0.1852,
+ -0.4630, +0.1017, +0.0380, -0.3577, +0.0552, -0.0491, +0.0620,
+ -0.2254, +0.5100, +0.3085, -0.9197, +0.0245, +0.1613, -0.2888,
+ -0.3367, -0.7743, +0.2930, +0.5275, +0.2395, +0.3260, -0.4876,
+ +0.1441, +0.1083, -0.2077, -0.0162, -0.0100, -0.0559, -0.0036,
+ +0.1453, +0.0042, +0.2518, -0.2407, +0.1021, +0.0405, -0.2128,
+ +0.0866, +0.2753, -0.2614, -0.0256, -0.6157, -0.2181, -0.3962,
+ +0.5585, -0.2790, -0.3463, -0.2301, -0.3256, +0.1199, +0.3906,
+ -0.2450, +0.2601, +0.2751, +0.2546, +0.3675, -0.1279, -0.3002,
+ -0.2151, -0.3924, -0.6061, +0.0396, -0.2452, -0.3420, +0.0579,
+ +0.4261, -0.2200, -0.0324, -0.2346, -0.5050, -0.0047, -0.1375,
+ -0.6326, -0.2100, +0.2774, +0.0850, +0.1070, -0.2795, +0.2149,
+ -0.4067, +0.2429, -0.1144, +0.4880, +0.0949, +0.3567, +0.0152,
+ +0.0013, -0.2505, -0.1949, +0.0630
+ ],
+ [
+ -0.1723, -0.1557, -0.4950, -0.3447, +0.3134, -0.3579, -0.0001,
+ +0.0962, -0.5796, -0.4150, -0.5110, +0.4075, +0.0227, +0.0725,
+ -0.9421, +0.6107, +0.2790, +0.1984, +0.2337, +0.5453, -0.0340,
+ +0.3049, -0.1807, -0.1085, +0.4351, +0.4050, -0.1805, -0.2090,
+ +0.3533, -0.0195, -0.0786, +0.8944, -0.2721, +0.7169, -0.2861,
+ -0.1510, -0.2619, -0.3671, -0.2015, +0.2595, +0.0351, +0.2994,
+ -0.3666, +0.2408, +0.3073, -0.0179, +0.0976, -0.3664, +0.1841,
+ +0.0979, -0.1209, +0.2309, -0.2827, +0.3789, +0.4197, -0.0155,
+ +0.1979, +0.2720, -0.1160, +0.4626, -0.5456, +0.0007, -0.2535,
+ -0.1234, +0.1810, +0.1973, -0.3088, -0.1346, +0.3206, -0.1146,
+ +0.2446, -0.3067, -0.4639, +0.1647, -0.2162, +0.3796, +0.0619,
+ +0.6112, +0.1175, +0.5665, +0.1142, +0.3709, -0.1419, +0.1321,
+ +0.0650, +0.1952, -0.3417, +0.3802, -0.6273, -0.0162, +0.1213,
+ +0.0823, -0.5304, +0.9111, +0.5029, +0.8862, +0.2029, +0.2394,
+ +0.4913, -0.2721, -0.0655, -0.0001, +0.0483, -0.5096, -0.0732,
+ -0.4347, -0.4974, +0.0450, +0.2935, -0.1081, +0.7021, -1.1752,
+ +0.0609, -0.9516, -0.4281, +0.0092, +0.2223, -0.7367, +0.0107,
+ -0.5940, -0.1206, -0.0405, -0.2688, +0.0516, -0.1647, +1.0320,
+ -0.6207, -0.2238, +0.2180, -0.1574, -0.0412, +0.1640, -0.8342,
+ +0.5910, +0.5872, -0.1396, +0.0310, -0.4284, -0.1957, -0.5202,
+ -0.4918, +0.1178, +0.1810, +0.2900, +0.3115, +0.0185, +0.0360,
+ -0.0422, -0.0245, +0.0866, -0.1750, -0.2731, -0.2825, -0.5676,
+ -0.1056, +0.3177, +0.3432, +0.2608, +0.3884, +0.5627, -0.2243,
+ -0.0137, -0.1918, -1.0110, -0.2613, -0.0348, +0.3585, -0.6610,
+ +0.5136, -0.0330, +0.3686, -0.6808, +0.2505, +0.3316, +0.7917,
+ -0.1283, +0.9045, +0.1989, -0.5997, -0.9126, +0.2693, +0.3214,
+ -0.7779, -0.7518, -0.2985, +0.6057, +0.1136, +0.2035, +0.2291,
+ +0.2812, -0.0236, -0.9562, +0.1740, -0.0238, +0.7070, +0.0373,
+ -0.2822, +0.1867, +0.0245, -0.3107, -0.4408, -0.2246, -0.3152,
+ +0.5446, -0.2249, -0.4331, -0.3255, -0.4219, -0.5227, -0.0210,
+ +0.0635, -0.2103, -0.5634, +0.8767, +0.2529, -0.1215, -0.3635,
+ -0.1327, -0.3813, +0.4531, -0.6627, +0.1316, +0.2156, +0.1508,
+ -0.2161, -0.1154, -0.6417, +0.8709, -0.2289, +0.0605, -0.4046,
+ +0.3373, -0.1148, -0.6212, +0.0371, -0.1410, -0.2213, +0.8599,
+ -0.4573, +0.6222, +0.3107, -0.1569, +0.4160, -0.0845, +0.1652,
+ +0.0080, +0.1743, -0.0456, +0.3639, +0.2093, -0.1005, +0.0093,
+ -0.2168, -0.7153, -0.1972, +0.7276
+ ],
+ [
+ +0.1697, -0.3885, +0.1069, -0.0617, +0.5131, -0.1418, +0.1427,
+ -0.5709, +0.0191, -0.0495, -0.3026, -0.1129, +0.1109, -0.0662,
+ +0.3090, +0.3430, -0.2976, +0.1814, -0.4145, -0.1168, -0.1641,
+ -0.3613, +0.2260, -0.3825, -0.1149, +0.5480, +0.3160, +0.1604,
+ -0.1252, -0.1538, -0.2604, +0.2282, -0.2813, +0.1356, -0.5893,
+ -0.1053, -0.1946, -0.7235, +0.2499, -0.6875, +0.0987, +0.0351,
+ -0.1473, +0.0171, -0.3876, -0.1652, -0.0297, +0.1009, -0.1188,
+ -1.0803, +0.0354, -0.3797, -0.0477, +0.2496, +0.1565, +0.0354,
+ -1.0098, -0.0470, -0.0345, -0.2341, +0.0760, -0.0247, -0.4161,
+ -0.0920, +0.3157, +0.5730, -0.1212, +0.0573, +0.1007, +0.1926,
+ +0.4577, -0.2041, -0.1005, +0.1324, +0.2268, -0.3710, -0.0038,
+ -0.2247, +0.3495, -0.3643, -0.2977, -0.5127, -0.0201, +0.1074,
+ +0.4485, -0.2529, -0.1624, -0.2576, -0.0633, +0.5198, +0.4709,
+ +0.2370, -0.1645, +0.0109, -0.1159, -0.1174, +0.2032, -0.2863,
+ -0.1481, +0.0215, -0.3431, -0.7387, +0.0869, +0.2565, -0.7215,
+ -0.2867, -0.2441, -1.6201, -0.1918, -0.1217, +0.1225, -0.1834,
+ -0.4723, +0.2542, +0.0229, +0.2454, -0.2479, -0.0542, +0.2266,
+ +0.0513, -0.1715, +0.3481, -0.0674, +0.0048, +0.0435, -0.0930,
+ -0.0589, -0.1182, -0.2407, +0.1002, +0.1340, +0.5007, -0.1613,
+ -0.1241, -0.3080, +0.1454, +0.3897, -0.2256, -0.0927, +0.1028,
+ -0.4274, -0.2913, -0.3130, -0.9492, +0.2260, -0.4201, +0.1871,
+ -0.0975, -0.8489, +0.7287, -0.4117, +0.1555, -0.2486, -0.6040,
+ +0.4002, -0.2970, -0.1902, +0.1478, +0.3497, +0.0713, -0.0653,
+ -0.5390, -0.3187, +0.2181, +0.2413, +0.5533, -0.3434, -0.1390,
+ -0.2986, +0.1452, -0.7319, +0.0479, -0.4350, +0.2009, +0.0184,
+ -0.5783, -0.1971, -0.0501, +0.1205, -0.6514, -0.4555, -0.1106,
+ -0.0623, -0.1877, -0.2276, +0.0869, +0.5072, -0.1449, +0.1115,
+ -0.3480, -0.8555, +0.0199, -0.3390, +0.2017, -0.1187, -0.3836,
+ +0.2586, +0.0085, -0.1478, -0.1012, +0.0896, +0.4176, +0.5783,
+ -0.2789, -0.3044, +0.0019, -0.0417, -0.0133, -0.1092, +0.0913,
+ -0.0325, +0.2607, -0.0013, -0.0174, +0.1431, -0.1434, -0.1505,
+ -0.0888, +0.3194, +0.0493, -0.1195, +0.3872, +0.0543, +0.6214,
+ -1.1019, -0.3721, -0.3201, +0.3204, -0.1039, -0.0099, +0.0641,
+ -0.3761, +0.2542, -0.1680, +0.3555, -0.0990, -0.6406, +0.2056,
+ -0.5322, +0.1438, +0.1698, -0.4285, +0.2757, -0.2258, -0.0983,
+ +0.1210, -0.2695, -0.0074, -0.0644, -0.0990, -1.3496, +0.1073,
+ +0.3525, -0.0115, +0.0264, -0.2596
+ ],
+ [
+ +0.2747, +0.5628, +0.4431, -0.4808, +0.1649, +0.5614, +0.3499,
+ +0.3167, -0.4618, -0.0132, -0.3237, -0.2952, +0.4245, -0.1691,
+ +0.1089, +0.1352, -0.2851, +0.1287, -0.6465, -0.2492, +0.4377,
+ +0.2717, +0.4748, -0.5543, -0.4054, +0.1491, +0.2907, +0.6462,
+ +0.2216, -0.4695, -0.0424, +0.2164, -0.2030, -0.4614, -0.1250,
+ +0.0055, -0.0856, -0.1442, +0.4880, -0.2420, -0.4811, +0.1583,
+ -0.4418, +0.9357, +0.0392, -0.6858, -0.0939, +0.5365, -0.1688,
+ -0.7388, -0.0071, -0.3334, +0.1075, +0.2025, -0.3026, +0.3052,
+ -0.2410, -0.0626, +0.2712, -0.0920, -0.0153, +0.2765, -0.0545,
+ +0.2745, +0.0655, +0.3442, +0.3462, +0.3263, +0.2914, -0.5316,
+ +0.3494, +0.0859, -0.2454, +0.2092, -0.1163, +0.3634, +0.2525,
+ +0.5571, +0.2256, -0.5412, -0.0111, +0.0994, -0.0691, +0.3054,
+ +0.2804, -0.0680, -0.1856, -0.1495, +0.4269, +0.2529, +0.2101,
+ -0.0740, -0.8437, +0.3873, -0.1279, +0.0644, -0.4079, -0.5276,
+ -0.3977, -0.4074, -0.4552, -0.3181, +0.1966, +0.1559, +0.0435,
+ -0.1219, -0.1680, +0.0140, -0.4742, -0.2062, +0.2468, +0.0087,
+ -0.2799, -0.2163, +0.1322, +0.1842, -0.3525, +0.1758, +0.4053,
+ -0.0979, -0.2324, +0.4251, +0.0993, +0.1651, -0.2595, +0.1306,
+ -0.0781, +0.1477, -0.4104, -0.1264, +0.1643, +0.3303, -0.1632,
+ -0.5046, +0.0847, -0.0272, +0.3258, +0.0115, -0.2498, -0.0496,
+ -0.0365, +0.2946, -0.2972, -0.5459, +0.3055, -0.0819, -0.1421,
+ +0.1174, -0.3425, -0.0407, +0.1862, -0.0683, -0.3621, -0.1234,
+ +0.1474, +0.0456, +0.2276, -0.2268, +0.7288, +0.0816, +0.1983,
+ +0.1715, -0.1798, -0.5754, +0.1822, -0.1222, +0.3782, +0.1634,
+ -0.3839, -0.1345, -0.1396, -0.4157, +0.7586, +0.0151, +0.2993,
+ +0.6449, -0.2801, +0.0825, +0.0071, -0.2395, -0.2420, +0.3180,
+ -0.6414, +0.1926, -0.3371, -0.2227, -0.1492, -0.2123, -0.0785,
+ +0.4464, -0.6735, +0.7092, +0.2349, +0.2622, +0.2318, +0.2083,
+ +0.2080, -0.6163, +0.5206, -0.2141, -0.1516, +0.3485, +0.2487,
+ -0.3222, +0.2153, +0.4927, +0.0316, -0.0842, +0.2031, +0.4124,
+ +0.0955, +0.2378, +0.1805, -0.3313, -0.0765, -0.2072, +0.1117,
+ +0.4379, +0.4960, +0.1179, +0.5476, -0.4134, +0.1773, +0.3737,
+ -0.0206, -0.3819, +0.0122, -0.3059, -0.3299, +0.1291, -0.2483,
+ -0.0893, -0.0693, -0.1249, +0.3299, -0.4633, +0.3046, +0.1212,
+ -0.1704, +0.2537, -0.1089, +0.1156, -0.0764, -0.1748, +0.4580,
+ +0.2688, -0.0216, -0.3047, +0.0361, +0.0442, -0.4634, -0.0529,
+ +0.7424, +0.0897, -0.4915, -0.2530
+ ],
+ [
+ -0.2950, +0.4745, -0.2429, +0.2752, -0.4050, -0.0669, -0.1100,
+ -0.2696, +0.5789, -0.3232, -0.6611, +0.0717, -0.5163, +0.1445,
+ -0.0622, -0.0038, -0.2640, +0.3361, +0.1008, +0.4852, -0.5955,
+ -0.1323, +0.3321, +0.3346, -0.3011, -0.0732, -1.1028, +0.0692,
+ -1.0819, +1.2074, -1.0188, -0.2155, +0.2934, +0.0449, +0.0060,
+ -0.8519, -0.2445, +0.3793, -0.2954, -0.1761, +0.1100, -0.1667,
+ +0.1866, +0.0724, +0.1035, -0.1747, +0.1722, -0.3217, +0.8777,
+ +0.5600, -0.4940, +0.0429, +0.2103, -0.0161, +0.0652, -0.0538,
+ -0.6381, +0.0505, -0.2626, -0.8758, -0.8780, -0.3226, +0.3723,
+ -0.0063, +0.3529, -0.2120, -0.8369, -0.4227, +0.0098, +0.6233,
+ -0.0428, -0.0706, +0.0185, -1.4554, -0.2413, +0.1361, -0.0933,
+ -0.2917, -0.7164, -0.2296, +0.2872, -0.6325, -0.4693, +0.5704,
+ +0.2275, +0.1236, +0.0047, +0.2918, +0.3270, -0.3250, -0.6201,
+ -0.2348, +0.3860, -0.0198, +0.7052, -0.5551, +0.8388, -0.0369,
+ -0.5169, -0.3586, +0.3014, -0.1938, +0.2685, -0.0955, -0.1103,
+ +0.2058, -0.3227, +1.0233, -0.4240, +0.1558, +0.2731, +0.0126,
+ +0.5597, -0.0101, -0.1268, -0.3800, +0.1101, +0.2421, -0.2984,
+ -0.2336, +0.1988, +0.3700, -0.4579, -0.0235, -0.1603, -0.7767,
+ +0.2749, -0.5447, +0.0028, +0.0438, -0.4079, +0.1064, -0.2033,
+ -0.1493, -0.2249, +0.2252, -0.2091, -0.2542, -0.7724, +0.2091,
+ +0.0220, -0.2310, -0.1476, -0.3213, +0.1362, -0.2202, +0.3902,
+ -0.1610, -1.1772, -0.2014, +0.3702, +0.0760, -0.3432, +0.2867,
+ -0.4002, -0.5128, +0.6702, -0.3667, -0.0299, +0.1372, -0.4944,
+ +0.3034, +0.3064, -0.1679, +0.2280, -0.5870, -0.2718, -0.5096,
+ -0.2144, -0.9115, -0.4486, -0.0969, -0.1706, -0.2283, +0.0728,
+ -0.0999, +0.4275, -0.0496, +0.2265, +0.6409, +0.5212, -0.2511,
+ -0.0128, -0.5112, +0.7315, -0.6277, -0.8890, +0.1119, -0.0329,
+ -0.4842, +0.3657, -0.0832, -0.0453, -0.4431, -0.7345, -0.4028,
+ -0.6844, +0.2773, -0.0776, +0.5961, +0.2588, -0.1628, -0.2956,
+ +0.6240, -0.0442, -0.1976, -0.0601, +0.0487, +0.1059, -0.4802,
+ +0.2312, +0.1878, -0.1641, -0.3063, +0.0779, -0.5947, +0.3276,
+ -0.1574, +0.0518, -0.8603, -0.6282, +0.0159, +0.2217, -0.0711,
+ +0.4798, +0.0434, -0.2916, -0.1463, +0.0058, -0.0726, -0.1971,
+ -0.1869, -0.6205, -0.2644, -0.8322, +0.5034, -0.0311, +0.2060,
+ -0.2229, -0.0838, -0.4383, -1.3797, +0.0462, +0.3815, -0.6875,
+ -0.0992, -0.1150, +0.5152, -0.9405, -0.1500, -0.1374, +0.1917,
+ -0.5055, -0.9638, -0.3250, -0.2241
+ ],
+ [
+ -0.1536, -0.3932, -0.1488, +0.0040, -0.1288, -0.1545, -0.9172,
+ -0.2805, +0.3230, +0.1461, -0.1107, +0.2029, +0.1632, -0.2643,
+ +0.2472, +0.3046, +0.2814, -0.1184, -0.5096, +0.0984, -0.3366,
+ +0.2242, -0.0239, +0.4157, +0.2858, +0.1108, -0.0776, -0.1283,
+ -0.2030, +0.1134, -0.0902, -0.1824, +0.0418, +0.3266, +0.4316,
+ -0.2477, +0.2924, -0.0527, +0.1449, +0.2986, +0.2485, +0.1540,
+ +0.0001, -0.8476, -0.0689, -0.1016, +0.3742, -0.1236, +0.2377,
+ +0.3154, +0.1240, +0.2560, +0.5795, -0.3371, +0.3826, -0.2159,
+ -0.3485, +0.1224, -0.7865, -0.3446, -0.2398, -0.2691, -0.0612,
+ -0.2650, +0.4368, -0.7490, +0.1430, -0.6888, -0.1218, +0.1478,
+ -0.1616, -0.4055, -0.0134, -0.2593, -0.5647, +0.1908, -0.6317,
+ +0.7954, +0.0961, -0.5094, +0.5672, +0.1861, -0.0810, +0.6770,
+ +0.5015, +0.6221, -0.4789, +0.2531, +0.1142, -0.3287, -0.0953,
+ +0.1372, +0.4031, +0.0750, -0.0161, -0.2726, +0.5245, +0.3697,
+ -0.6535, -0.4510, +0.0919, +0.0658, -0.4687, -0.0160, -1.0360,
+ +0.3085, +0.1988, -0.0155, -0.0580, +0.6356, +0.4824, -0.0580,
+ -0.6040, +0.1401, -0.5050, -0.3169, -0.0570, +0.2261, -0.2034,
+ +0.2546, +0.1917, -0.2450, -0.5480, -0.0658, +0.4291, -0.0303,
+ -0.4937, -0.4524, -0.0388, +0.3961, +0.4950, +0.0312, -0.2034,
+ +0.5666, -0.1002, -0.5486, +0.0753, +0.0175, -0.7026, +0.3155,
+ -0.0880, +0.2177, +0.0881, +0.2664, +0.0051, -0.2471, +0.4793,
+ -0.2982, +0.1036, +0.1263, +0.0034, -0.4423, +0.0933, +0.3059,
+ +0.4064, -0.3276, +0.0026, +0.0185, -0.6529, -0.6750, -0.5380,
+ +0.1447, +0.1747, +0.3788, +0.1551, -0.0605, -0.6776, +0.2446,
+ +0.5547, -0.0101, +0.1820, +0.1259, -0.0514, +0.0479, -0.2650,
+ -0.1059, -0.1688, -0.1912, -0.3360, +0.2134, +0.0543, +0.5636,
+ +0.3412, -0.5392, +0.0621, +0.4772, -0.3313, -0.4376, +0.0272,
+ +0.1554, +0.3807, +0.4939, +0.3175, -0.4498, +0.5755, -0.0546,
+ +0.0159, +0.0351, +0.0451, +0.3587, +0.0944, -0.0031, -0.0826,
+ +0.2568, +0.5953, -0.6936, +0.1513, +0.0973, -0.0282, +0.1344,
+ +0.1280, +0.0350, +0.2338, -0.0971, +0.2113, +0.0762, -0.6498,
+ -0.7180, +0.6955, -0.6532, +0.2342, +0.3941, +0.3652, +0.0793,
+ -0.0786, -0.0365, -0.0705, +0.3362, +0.0218, +0.3218, +0.1325,
+ +0.0795, +0.0799, -0.3366, -0.0008, -0.7087, +0.1497, +0.1490,
+ +0.2054, -0.3338, +0.2178, -0.5476, +0.0694, -0.3220, -0.2363,
+ -0.6905, -0.0137, -0.0039, -0.3057, -0.0075, -0.2926, +0.3981,
+ +0.1954, -0.6497, -0.6387, -0.5863
+ ],
+ [
+ -0.0360, +0.2954, -0.0415, -0.1861, -0.1073, -0.0619, +0.0758,
+ +0.2595, -0.1324, +0.0786, -0.4354, -0.2461, -0.1916, -0.2344,
+ -0.1291, +0.2328, +0.3387, -0.0731, -0.6766, +0.1840, +0.0911,
+ -0.1266, -0.0519, +0.1181, +0.1365, -0.0523, -0.1781, +0.2005,
+ +0.1115, +0.1210, +0.0721, -0.1915, +0.0981, +0.0564, -0.4853,
+ +0.2200, +0.1986, +0.2435, -0.0983, +0.2328, +0.0097, +0.2252,
+ -0.3074, -0.2446, -0.1512, +0.0477, -0.1672, -0.1571, -0.3081,
+ -0.0384, +0.1514, -0.0964, -0.1442, -0.3555, -0.4037, -0.3527,
+ +0.2746, +0.0331, +0.3087, -0.4382, -0.1313, +0.1540, -0.2501,
+ -0.0540, -0.0858, -0.3254, +0.2537, +0.1154, +0.3133, +0.2732,
+ +0.0159, -0.0697, +0.3618, -0.2276, +0.0914, -0.6782, +0.1307,
+ -0.1598, +0.1400, -0.3742, -0.2462, -0.1944, -0.0343, +0.4345,
+ +0.1273, -0.2421, +0.1062, -0.0204, +0.0289, +0.3268, -0.1223,
+ +0.1921, -0.0763, +0.2320, -0.0406, +0.2471, -0.1578, -0.3309,
+ +0.3415, +0.1961, +0.2112, -0.1143, +0.1991, +0.0273, +0.0975,
+ +0.2010, -0.0719, +0.1204, +0.1723, +0.1155, -0.0569, -0.1840,
+ +0.2899, -0.0957, +0.2138, -0.0352, -0.7646, -0.4011, +0.5825,
+ -0.0675, -0.2865, +0.2258, -0.0888, +0.4040, +0.5791, -0.3169,
+ +0.1193, -0.2115, +0.1814, +0.2504, -0.1733, +0.0491, +0.0677,
+ +0.2845, +0.0169, +0.0868, -0.0024, -0.0365, -0.2270, -0.4361,
+ +0.3346, +0.2319, -0.0769, +0.2725, -0.2883, -0.1010, +0.0275,
+ -0.1357, +0.1794, -0.2117, +0.2064, +0.1074, -0.1082, +0.0635,
+ +0.0389, -0.7832, +0.1141, +0.1320, +0.0181, -0.1715, +0.1375,
+ +0.4326, +0.1225, -0.0650, -0.0209, -0.2055, -0.3685, -0.2018,
+ +0.0845, -0.1548, +0.0742, -0.0552, -0.5630, -0.0593, -0.6809,
+ -0.0612, -0.1252, +0.0674, +0.3169, +0.2488, -0.0968, -0.2377,
+ -0.0607, +0.3838, -0.2299, -0.5658, -0.3862, +0.3168, -0.3866,
+ +0.0213, +0.4963, -0.6488, -0.5193, +0.5468, +0.1999, -0.2567,
+ -0.1807, +0.1057, -0.1875, -0.1282, +0.0276, +0.4583, -0.4058,
+ -0.0258, -0.3120, -0.1087, -0.2016, +0.1688, -0.1348, +0.2886,
+ -0.7916, +0.0877, +0.1170, -0.3574, -0.6124, +0.2224, +0.4414,
+ +0.0925, -0.2001, -0.0743, -0.0906, +0.0475, -0.1264, +0.2501,
+ -0.1218, +0.1349, +0.1751, -0.2361, +0.5184, -0.1585, +0.1610,
+ +0.1194, -0.0824, -0.1333, +0.1845, -0.4864, -0.1342, -0.0673,
+ -0.1059, -0.1255, +0.1713, -0.2342, +0.1031, +0.0191, +0.0026,
+ -0.0553, -0.1135, +0.2985, +0.2850, +0.4020, -0.1087, +0.0884,
+ -0.3541, +0.3092, +0.0849, -0.2151
+ ],
+ [
+ +0.2371, -0.0086, -0.2611, +0.5156, +0.0931, +0.0796, +0.1728,
+ +0.0679, -0.5360, -0.0178, -0.4290, +0.0138, -0.1435, -0.2081,
+ -0.2986, +0.6750, +0.3418, +0.3486, -0.2263, +0.1717, -0.2510,
+ -0.3704, +0.1700, +0.7958, +0.2257, +0.0034, -0.4423, -0.0504,
+ -1.1018, -0.4064, -0.4251, +0.1119, -0.6379, +0.4920, +0.8266,
+ +0.0255, +0.3594, +0.4602, +0.3663, -0.0724, -0.1700, -0.3765,
+ +0.3345, -0.3255, -0.0887, +0.9938, -0.3264, -0.0687, -0.1137,
+ -0.0124, -0.0392, -0.0047, +0.5795, -0.4190, +0.4339, +0.0758,
+ -0.0027, -0.1153, +0.1485, +0.4894, +0.1099, -0.2054, +0.6032,
+ -0.0731, -0.2392, +0.1160, -0.1188, -0.0067, +0.2892, -0.4823,
+ -0.0291, +0.4673, -0.3526, -0.0929, +1.1909, +0.2589, -0.0504,
+ -0.3820, -0.1289, +0.3804, +0.1888, +0.2932, -0.2874, -0.2412,
+ -0.0845, +0.2648, -0.0194, +0.1119, +0.0614, +0.5552, -0.3978,
+ +0.3185, -0.9749, +0.1223, -0.1325, +0.0353, -0.3382, -0.4137,
+ -0.2405, -0.2323, +1.0141, -0.4834, +0.3897, -0.1186, -0.0549,
+ -0.2652, -0.0160, +0.8072, +0.3652, -0.5397, +1.1077, -0.4531,
+ +0.0320, +0.7525, +0.3837, -0.1597, -0.5915, -1.0873, +0.2604,
+ -0.1406, +0.0787, +0.4561, +0.0474, -0.1794, +0.3019, +0.3779,
+ +0.0220, +0.2327, -0.7537, +0.1829, -0.2856, +0.0857, -1.0650,
+ -0.3748, -0.2974, -0.7783, +0.8731, -0.1243, -0.1016, +0.1358,
+ -0.3743, +0.9547, -0.7992, -0.6159, -0.1482, -0.3578, +0.1896,
+ +0.5530, +0.4486, +0.4260, +0.5332, -0.0449, +0.2954, +0.1244,
+ +0.3628, -0.2508, -0.7484, -0.8054, -0.0311, -0.1260, +0.7015,
+ -0.0675, -0.0999, -0.0363, -0.0300, -0.4767, -0.1877, -0.4087,
+ -0.0022, -0.7186, -0.5304, +0.5916, +0.5709, +0.0832, -0.7458,
+ +0.5229, +0.4158, -0.0808, -0.0479, -0.1827, -0.0359, +0.1044,
+ -0.6888, +0.3843, +0.3503, -0.0043, -0.0708, +0.2169, -0.2123,
+ +0.0380, +0.1926, -0.5396, +0.0643, +0.1430, +0.2271, -0.5528,
+ +0.0703, +0.1330, +0.2271, -0.2817, -0.5850, +0.4538, -0.2435,
+ -0.1733, +0.7802, +0.4799, -0.4109, +0.5072, -0.3197, +0.6073,
+ +0.6545, +0.1636, +0.0254, +0.6118, -0.3745, +0.7355, -0.5632,
+ -0.6298, -0.0379, +0.4363, -0.5521, +0.6507, -0.0700, +0.1930,
+ -0.8462, -0.1050, -0.3672, +0.1103, +0.2060, -0.7312, -0.6317,
+ +0.1302, +0.0955, -0.5235, +0.3899, -0.0225, -0.0077, +0.4365,
+ +0.2099, +0.2631, -0.2255, -0.6623, +0.1293, -0.6884, -0.2619,
+ -0.1395, -0.1443, +0.6374, +0.8680, +0.8132, +0.7087, -0.2445,
+ +0.4986, -0.0446, -0.0006, -0.8373
+ ],
+ [
+ -0.4495, +0.0435, +0.4813, +0.1369, -0.3641, -0.2529, +0.4496,
+ -0.0242, -0.2999, -0.3478, -0.2722, -0.0916, +0.1491, -0.1968,
+ -0.2539, +0.1463, -0.2696, +0.2267, +0.2962, +0.5283, +0.0416,
+ +0.7199, -0.0238, +0.0954, -0.2894, +0.1260, +0.2921, +0.6348,
+ -0.8794, -0.3574, +0.1670, -0.2380, -0.7382, -0.1575, -0.0566,
+ -0.2299, -0.0549, -0.1437, +0.2151, +0.1275, +0.0698, +0.1757,
+ -0.2951, -0.4897, +0.0375, +0.5689, +0.0023, -0.0353, -0.0830,
+ +0.0415, -0.1865, +0.5987, +0.3522, -0.3112, -0.5514, -0.3481,
+ -0.1245, +0.6629, -1.5164, -1.5245, -0.1184, +0.2531, +0.2720,
+ -0.2686, -0.9922, -0.4516, -0.0557, +0.0438, -0.1536, -0.1301,
+ -0.0277, -0.2421, -0.9948, +0.5539, -0.6173, +0.3850, +0.2736,
+ -0.0939, +0.1821, +0.6746, -0.3509, -0.0593, -0.0309, +0.1863,
+ -0.4364, +0.8391, +0.0684, -0.6878, +0.0378, +0.0772, +0.2807,
+ -0.2284, -0.0043, -0.1348, -0.0927, +0.4267, -0.3053, +0.4963,
+ +0.5246, +0.7464, +0.0170, +0.0081, +0.1008, +0.3554, -0.1083,
+ +0.0900, -0.0259, +0.2350, +0.2738, -0.0943, +0.1602, -0.8808,
+ -0.3479, +0.1440, -0.2565, -0.8828, -0.4877, +0.1551, -0.4075,
+ +0.1506, -0.1975, +0.2705, +0.4446, +0.1308, -0.4963, +0.5065,
+ +0.4221, -0.3242, +0.3413, -0.4956, +0.1187, +0.1829, -0.3531,
+ +0.1247, +0.1899, +0.3358, -0.3549, -0.4318, -0.2254, +0.1786,
+ +0.0941, -0.6469, -0.2490, +0.3554, -0.5808, -0.0775, -0.6145,
+ -1.3435, +0.1474, +0.0131, -0.6835, +0.6978, +0.1364, -0.6990,
+ -0.0145, -1.0213, -1.1805, +0.7311, +0.1982, -0.4777, -0.1177,
+ -0.2967, -0.1379, -0.9473, -0.2823, -0.1279, -0.2873, -0.5012,
+ -0.1892, -1.1920, -0.6524, -0.3917, +0.2036, +0.4123, -1.2438,
+ -0.5606, -0.2587, +0.1305, +0.2363, +0.1463, -0.0899, -0.5979,
+ +0.4246, -0.1457, -0.1571, +0.2682, -0.3809, -0.3298, +0.5987,
+ +0.2087, +0.0190, -0.5439, -0.1221, +0.0441, +0.4264, +0.1032,
+ -0.3863, +0.0826, -0.5298, +0.1179, +0.4471, -0.0058, +0.1359,
+ -0.5553, -0.2015, +0.0624, +0.5981, -0.0567, +0.3412, -0.2411,
+ +0.1909, -0.4750, +0.3180, -0.3431, -0.4751, +0.2987, +0.6077,
+ +0.4846, +0.0018, -0.0260, -0.5347, -0.2805, -0.1223, -0.2192,
+ +0.1721, +0.2594, -0.4876, -0.5535, +0.0242, +0.6930, -0.7116,
+ +0.1902, -0.1624, -0.0507, -0.7388, -0.0348, -0.1045, -0.5571,
+ -0.1837, +0.2429, +0.2504, -0.4475, -0.1865, +0.0849, +0.3409,
+ +0.8343, +0.2234, -0.5084, -0.1988, -0.7860, -0.5043, -0.0522,
+ +0.2207, -0.1742, +0.0785, +0.3266
+ ],
+ [
+ -0.1545, -0.2636, +0.7711, +0.5888, +0.8420, -0.3952, +0.4993,
+ +0.0223, +0.1174, -0.1090, -0.1476, +0.3352, +0.5241, -0.6029,
+ -0.3128, -0.1732, -0.4034, +0.0029, -0.0042, +0.2734, +0.4653,
+ +0.4844, +0.7529, -0.0139, -0.0961, +0.1176, +0.3521, +0.0775,
+ +0.0548, -0.1762, +0.3629, -0.1580, -0.1869, -0.0555, +0.6377,
+ +0.0195, +0.0749, +0.2786, +0.0565, +0.7454, +0.4380, -0.2898,
+ -0.6027, +0.3066, +0.3890, -0.2317, +0.1276, -0.3984, -0.0154,
+ -0.1493, -0.1296, -0.2045, -0.2730, -0.1757, +0.2943, +0.2368,
+ +0.2421, +0.4279, -0.0585, -0.5660, -0.0633, +0.5286, +0.4202,
+ -0.0919, -0.2269, +0.1888, +0.2327, -0.0919, -0.2479, +0.3121,
+ +0.0653, -0.6794, +0.7241, -0.1175, -0.2181, -0.0647, +0.1438,
+ -0.1630, -0.1400, +0.4939, +0.2837, -0.1447, -0.0997, -0.5197,
+ -0.1330, -0.0634, -0.6257, +0.0281, -0.3211, +0.2312, -0.1216,
+ -0.3033, -0.1893, +0.7291, -0.0157, -0.3289, -0.4493, -0.5517,
+ -0.1759, +0.6222, -0.4931, +0.2985, -0.4296, -0.2574, -0.2905,
+ +0.0091, -0.5682, +0.0978, +0.1111, -0.0548, +0.2864, -0.4165,
+ +0.8250, -0.1752, -0.0190, -0.1323, +0.2348, -0.6032, -0.2997,
+ +0.5765, -0.1065, -0.1482, +0.5952, +0.1394, +0.1673, -0.2770,
+ +0.4918, -0.2861, +0.6747, +0.0634, -0.6803, +0.1890, +0.1198,
+ -0.3153, +0.2313, +0.0112, +0.0932, -0.1102, -0.2010, -0.3737,
+ -0.5680, -0.4689, +0.5138, +0.2031, -0.6002, -0.1868, +0.3376,
+ -0.2676, -0.9375, -0.2736, -0.2545, -0.0246, +0.0679, -0.0150,
+ -0.0617, -0.2441, +0.4709, +0.0774, +0.5169, -0.3557, +0.0490,
+ +0.7436, +0.6572, +0.0357, -0.0924, -0.4672, -0.1624, -0.7978,
+ -0.3220, +0.0738, +0.7238, -0.2530, +0.5674, +0.4540, -0.7096,
+ -0.0164, -0.1263, +0.9431, -0.5657, +0.2935, -0.2642, -0.2049,
+ -0.0366, +0.8266, -0.1993, +0.2611, -0.1295, -0.6901, -0.2303,
+ -0.0508, +0.0599, +0.2460, -0.5177, -0.4144, -0.2723, +0.3891,
+ -0.3817, -0.0499, -0.2704, +0.2270, +0.3747, -0.1594, -0.2215,
+ +0.7694, -0.0915, +0.0059, -0.6710, -0.3997, -0.0833, +0.2102,
+ +0.4514, -0.3927, +0.2041, -0.8319, -0.4655, -0.2734, -0.1729,
+ -0.2223, -0.2689, +0.6059, -0.5239, -0.2485, -0.3970, +0.3389,
+ -0.3576, +0.2457, +0.1344, -0.0006, +0.2879, +0.0049, +0.2234,
+ -0.2334, -0.1920, -0.1798, -0.2480, -0.2451, +0.1456, -0.1634,
+ -0.0665, +0.5494, +0.2914, +0.2998, -0.0831, -0.1296, +0.3089,
+ +0.1795, -0.1477, -0.0371, -0.8516, -0.1523, -0.1577, -0.0086,
+ +0.0418, -0.7372, +0.2951, +0.0362
+ ],
+ [
+ -0.4565, +0.1782, +0.1290, -0.5322, -0.2860, -0.2451, -0.3503,
+ -0.1212, -0.6014, +0.2923, -0.2355, -0.4092, -0.3082, +0.6207,
+ -0.6511, -0.1271, -0.3121, -0.6387, -0.1085, -0.3078, +0.0726,
+ -0.1056, -0.7585, +0.0335, -0.1210, +0.2206, +0.5102, -0.4960,
+ -0.3887, +0.0633, -0.2038, -0.0613, -0.1608, -0.4403, +0.1844,
+ +0.2427, -0.0712, +0.1452, -0.3168, +0.2375, +0.5895, -0.3812,
+ +0.4553, -0.3796, +0.0759, +0.0808, -0.0043, -0.1435, -0.1343,
+ +0.4849, -0.4057, +0.0537, -0.3170, -0.5482, -0.0744, -0.2475,
+ +0.2786, +0.0103, +0.1002, +0.2105, +0.0228, +0.2931, -0.1969,
+ -0.5573, -0.5076, +0.3885, +0.2231, -0.7409, -0.3342, +0.1119,
+ +0.1228, +0.3823, -0.4331, +0.0602, +0.0816, -0.3968, -0.1841,
+ +0.2059, +0.3797, +0.0335, -0.0525, -0.1171, -0.4932, +0.0667,
+ -0.3642, +0.2155, -0.2907, -0.0247, -0.8014, +0.1727, +0.2656,
+ -0.3467, -0.1870, -0.0004, +0.2753, +0.0611, -0.0361, +0.0040,
+ +0.3672, -0.6810, +0.3802, +0.1425, -0.1164, +0.0589, -0.3594,
+ +0.1147, -0.0726, +0.1166, +0.1405, -0.8273, -0.1676, -0.0557,
+ -0.2434, +0.1277, +0.5011, -0.1945, -0.3558, -0.3259, +0.0800,
+ -0.1651, +0.5381, +0.0205, +0.0540, +0.3779, -0.3028, -0.0529,
+ -0.6128, +0.1707, -0.3605, -0.0364, -0.3162, -0.0557, -0.1434,
+ -0.3231, -0.3164, -0.7789, +0.0809, +0.0999, -0.0837, -0.1528,
+ +0.2895, -0.0212, -0.0732, +0.2575, -0.1690, -0.2843, +0.0976,
+ -0.0577, +0.0625, +0.5292, -0.2402, -0.4092, -0.0631, -0.0600,
+ +0.1563, -0.0879, -0.1808, +0.0164, -0.1146, -0.5358, -0.1802,
+ +0.0685, +0.2012, +0.2354, -0.1941, -0.2628, +0.2707, +0.0396,
+ -0.2286, +0.1113, -0.3468, +0.2619, +0.0130, -0.2485, -0.1131,
+ +0.1862, +0.0415, -0.6855, -0.1715, -0.3101, +0.2030, -0.4367,
+ +0.3013, +0.0863, -0.5386, +0.0915, +0.2793, -0.1328, -0.0632,
+ -0.1778, +0.0966, -0.0656, +0.1870, -0.4183, +0.2612, -0.3949,
+ -0.2119, -0.7062, -0.1619, +0.1240, +0.5384, +0.0755, +0.2566,
+ +0.0666, +0.1773, -0.0047, +0.2708, -0.0026, +0.0031, +0.2468,
+ -0.0893, +0.3492, -0.1193, -0.7335, +0.3597, -0.9848, -0.3577,
+ -0.0779, -0.3795, -0.3974, +0.0866, +0.3102, -0.5583, -0.7425,
+ +0.1512, +0.1052, -0.1454, +0.2425, -0.1251, +0.1301, -0.5012,
+ -0.6570, +0.7020, -0.1142, -0.0283, +0.1393, +0.1112, +0.1435,
+ -0.3354, -0.2273, +0.4505, -0.0457, -0.2140, -0.4433, -0.4714,
+ -0.0525, -0.0225, +0.1967, -0.0158, +0.1003, +0.0867, -0.9314,
+ -0.2636, +0.3661, -0.5848, +0.0565
+ ],
+ [
+ -0.1112, -0.4525, +0.1614, +0.0399, +0.5304, -0.3198, -0.4914,
+ -0.2721, -0.0057, +0.1912, +0.3123, +0.1551, +0.3333, -0.0465,
+ -0.1155, +0.1781, +0.0136, -0.4149, +0.1566, -0.5089, -0.0009,
+ -0.0626, -0.1944, -0.1314, -0.1063, -0.2397, +0.2927, -0.6858,
+ +0.3245, +0.2261, -0.2639, -0.0988, -0.2489, +0.0032, +0.2910,
+ +0.1492, -0.3025, +0.0991, +0.2780, +0.3589, -0.2876, -0.0963,
+ +0.1392, -0.5810, -0.7109, +0.6384, +0.0976, -0.5051, +0.0422,
+ +0.6395, +0.2289, -0.6906, +0.6869, -0.2494, +0.0840, +0.5636,
+ +0.4438, +0.0787, +0.3340, +0.0412, +0.3545, -0.4366, -0.4846,
+ +0.0560, -0.0517, +0.2010, +0.1060, -0.5708, +0.4587, +0.0208,
+ +0.0620, -0.2796, +0.5296, -0.2107, +0.3797, -0.3168, +0.6043,
+ +0.1749, +0.4162, +0.4593, -0.7969, +0.6965, +0.4833, +0.1571,
+ -0.1353, -0.0926, -0.0610, +0.0594, -0.8100, -0.3465, -0.8444,
+ +0.1071, -0.1125, -0.1348, +0.1900, -0.3160, -0.0849, -0.5535,
+ +0.2228, -0.0280, -0.2032, -0.5068, -0.1945, -0.4944, -0.3757,
+ +0.2530, +0.2590, +0.0177, -0.3995, +0.1453, +0.4474, -0.2493,
+ -0.1195, +0.1928, +0.9237, +0.0135, -0.6365, +0.1230, -0.3276,
+ -0.0830, +0.2579, -0.3146, -0.1939, +0.4047, -0.0049, -0.3189,
+ -0.0661, +0.1790, -0.2341, +0.1557, +0.2112, +0.1689, +0.1799,
+ +0.0173, -0.3950, -0.5424, +0.0521, -0.3810, +0.1368, +0.1286,
+ -0.4210, +0.4710, +0.0680, +0.2577, -0.2847, +0.2011, -0.0889,
+ -0.3098, +0.3893, +0.1595, -0.2627, -0.1097, +0.1000, +0.1536,
+ +0.3436, -0.1249, -0.4113, +0.2356, -0.0156, +0.1952, -0.0951,
+ -0.3113, -0.3086, +0.4344, +0.0703, -0.2342, -0.3115, -0.1909,
+ +0.4157, -0.3784, -0.1582, +0.1850, -0.2052, +0.1344, -0.0284,
+ -0.4493, +0.0625, -0.1307, +0.3509, -0.0012, +0.8178, -0.2761,
+ +0.7609, +0.1238, +0.0534, -0.2405, -0.2435, -0.1970, +0.0690,
+ +0.4685, +1.0030, +0.6136, +0.6953, +0.0036, +0.5347, -0.4444,
+ -0.1588, -0.4121, -0.3876, +0.3125, +0.2208, -0.0865, -0.2455,
+ +0.0981, +0.4245, -0.5058, +0.2232, +0.1998, +0.1941, -0.2040,
+ -0.0108, +0.2213, +0.0371, -0.3715, -0.4102, -0.1646, -0.1220,
+ +0.6978, -0.2699, +0.1139, +0.0043, -0.2600, +0.4152, -0.2855,
+ -0.2182, +0.7740, +0.1168, +0.1696, +0.1662, -0.4700, -0.0897,
+ -0.5900, +0.0786, +0.2272, -0.1016, +0.3904, -0.3343, -0.1979,
+ -0.2305, -0.0750, -0.1703, -0.4604, +0.2909, -0.3099, +0.1186,
+ -0.3282, +0.2542, +0.0348, -0.2425, +0.4281, +0.1888, -0.6300,
+ -0.0389, -0.2371, -0.1128, +0.1885
+ ],
+ [
+ +0.6639, +0.0702, -0.1304, -0.4967, +0.3758, -0.1061, -0.0523,
+ -0.2161, +0.0816, -0.3597, +0.0542, +0.0536, -0.3311, -0.1367,
+ -0.5922, -0.3262, -0.3618, -0.8526, -0.5574, -0.1029, +0.1654,
+ -0.3574, -0.5698, -0.0729, -0.4110, +0.1946, -0.5148, -0.2157,
+ +0.0880, -0.4988, +0.1084, -0.2813, +0.4106, -0.0524, -0.1673,
+ -0.7740, +0.1078, +0.1820, -0.5635, -0.0145, -0.1669, +0.0116,
+ -0.1952, +0.1940, +0.2119, -0.0359, +0.3704, +0.2859, +0.1880,
+ -0.0113, +0.0125, +0.4600, -0.2778, +0.0657, +0.7902, -0.1208,
+ +0.1688, -0.1355, +0.3225, +0.4388, -0.2043, -0.5396, +0.0596,
+ -0.6605, -0.4528, -0.4741, -0.3760, +0.4426, -1.1438, -0.0723,
+ +0.2735, -0.1089, -0.3427, -0.0726, +0.0420, -0.2223, -0.7000,
+ -0.2843, -0.4384, +0.2913, -0.1338, -0.5119, +0.5250, -0.0908,
+ +0.5554, +0.1226, -0.0437, +0.2352, -0.2992, -0.2623, +0.3665,
+ -0.0842, +0.0260, +0.0963, -0.6214, -0.3901, +0.0785, -0.0952,
+ -0.0248, -0.3269, -0.1007, +0.0385, -0.1838, -0.4408, +0.0586,
+ +0.3316, +0.2261, +0.1234, -0.1497, -0.8627, -0.2077, -0.0247,
+ -0.3589, -0.2200, -0.0796, -0.3080, +0.0493, +0.1684, -0.0319,
+ -0.4871, -1.0854, +0.0254, -0.3065, -0.1966, -0.3679, +0.1414,
+ -0.0580, -0.2385, +0.2040, +0.0429, +0.1307, -0.8378, -0.1806,
+ -0.4079, +0.4829, -0.5028, -0.1583, -0.4943, -0.0458, -0.1000,
+ -0.5349, +0.2198, -0.1819, +0.4630, -0.0457, +0.0766, +0.3230,
+ +0.6088, -0.0285, -0.3704, -0.3567, -0.3936, -0.1021, +0.4362,
+ -0.1535, -0.1291, +0.0761, -0.3656, -0.3966, -0.4077, +0.6730,
+ -0.0519, -0.6391, +0.2173, -0.2885, +0.2854, -0.2147, +0.1787,
+ +0.2168, -0.4785, +0.1279, -0.0088, -0.4949, -0.8904, -0.6216,
+ -0.1224, -0.2990, -0.4242, +0.3770, -0.3137, +0.0934, -0.5931,
+ -0.2990, +0.3737, -0.6431, -0.1939, -0.2330, -0.1893, -0.2435,
+ -0.1946, -0.0799, -0.1570, -0.5438, +0.0471, +0.2994, +0.2884,
+ +0.2453, -0.6113, +0.4730, +0.2125, -0.6701, +0.0616, -0.2903,
+ -0.2056, +0.2428, -0.1759, -0.8047, -0.2883, -0.6022, -0.4987,
+ -0.2738, +0.1943, +0.2759, -0.3151, -0.3028, -0.0858, -0.6176,
+ -0.4943, -0.2982, +0.3932, -0.3796, -0.1953, -0.3258, +0.0818,
+ +0.1012, +0.0787, +0.3576, -0.5450, -0.2397, +0.1890, +0.4258,
+ +0.1003, -0.4817, +0.3342, -0.1117, -0.1249, -0.0892, -0.1996,
+ +0.0142, -0.0099, +0.0581, -0.7400, -1.2277, +0.0064, +0.0318,
+ -0.4549, -0.0940, -0.0705, -0.0682, -0.2008, +0.1345, +0.5597,
+ -0.2645, -0.0604, -0.3416, -0.2864
+ ],
+ [
+ -0.0028, -0.0898, -0.4007, +0.4676, -0.1535, +0.2170, +0.0180,
+ -0.0810, +0.5363, +0.0032, +0.3269, -0.1136, -0.1009, -0.2048,
+ -0.3535, +0.4315, +0.1272, -0.1089, -0.5999, +0.0208, +0.0936,
+ -0.1613, +0.4883, +0.1000, -0.2159, +0.4113, -0.0223, +0.6549,
+ -0.3449, +0.0485, +0.2421, -0.4096, +0.0556, -0.4409, -0.4039,
+ +0.0445, +0.3850, +0.0889, +0.0026, -0.1220, +0.3864, +0.3739,
+ +0.1646, +0.5352, -0.0789, -0.0276, +0.2423, -0.3945, +0.1482,
+ -0.0888, -0.1047, +0.6800, -1.1911, -0.7345, +0.5066, +0.0200,
+ -0.0569, -0.0783, +0.1944, +0.4563, +0.1254, +0.3341, +0.8698,
+ +0.3332, +0.4348, -0.3389, -0.4066, +0.2644, -0.2798, -0.0424,
+ +0.1193, +0.0831, -0.7383, -0.0038, +0.2701, -0.0101, -0.6089,
+ +0.1930, -0.1343, +0.5417, -0.3725, +0.0902, -0.1180, +0.3325,
+ +0.3892, +0.1325, +0.9921, -0.0492, +0.2405, +0.2264, +0.2860,
+ +0.0994, +0.0847, +0.9777, +0.0296, +0.4773, -0.1188, +0.6873,
+ +0.5104, +0.0378, -0.2487, +0.3510, -0.3927, -0.0066, -0.3028,
+ +0.1421, +0.0103, -0.0162, -0.2787, -0.3621, +0.7588, -0.1543,
+ -0.1931, -0.2935, +0.1967, +0.2697, +0.4855, +0.5111, +0.1222,
+ -0.3406, -0.2549, +0.1323, -0.0580, -0.1195, -0.1470, +0.6529,
+ +0.2743, -0.0332, +0.1778, +0.2766, +1.1343, -0.3576, -0.6760,
+ -0.2872, -0.8008, -0.0279, -0.0802, -0.0202, -0.1213, -0.5831,
+ -0.2366, -0.4305, +0.3012, -0.1903, +0.2265, -1.0208, -0.1138,
+ -0.1229, -0.7328, +0.1313, -0.1682, -0.7280, -0.4280, +0.6649,
+ -0.3497, +0.2514, -0.2782, -0.0772, -0.4907, -0.0475, +0.0505,
+ +0.6654, -0.5389, -0.2224, +0.0454, +0.0665, -0.2657, -0.1661,
+ +0.3128, +0.5484, +0.2041, -0.0153, -0.5880, +0.1951, -0.1350,
+ +0.2217, +0.2999, -0.1773, -0.1246, +0.2815, +0.3207, -0.3308,
+ -0.0356, -0.2777, -0.1428, -0.4047, -0.1064, -0.0044, +0.4314,
+ +0.0760, -0.0951, -0.1282, -0.0204, -0.0225, -0.4182, +0.3567,
+ -0.0197, -0.3210, +0.7637, +0.2886, -0.3230, +0.0109, +0.3165,
+ +0.0088, -0.3390, +0.6050, +0.0018, +0.0298, -0.2559, -0.2123,
+ +0.1931, +0.0521, +0.1330, +0.2284, -0.4433, -0.2233, +0.6624,
+ -0.0413, -0.5773, +0.0100, +0.0626, -0.5787, +0.5139, -0.7480,
+ -0.1786, +0.2617, -0.1276, -0.0327, +0.3131, +0.2643, -0.0968,
+ +0.1409, -0.3147, +0.6659, -0.4285, -0.2072, -0.0548, +0.1973,
+ +0.0799, +0.4575, +0.3171, -0.2175, -0.2405, -0.0591, -0.2228,
+ +0.1632, -0.0162, -0.1352, -0.2736, -0.6039, -0.5106, +0.1240,
+ +0.3908, +0.0334, -0.1636, -0.2803
+ ],
+ [
+ +0.0894, -0.1313, -0.5267, -0.3037, +0.0560, -0.0589, -0.0811,
+ +0.2186, -0.0574, -0.2032, +0.4292, +0.1375, -0.1661, +0.1344,
+ +0.1416, -0.2339, -0.1400, -0.1990, -0.2908, +0.0187, -0.1002,
+ -0.5780, +0.0609, -0.2537, -0.2208, -0.0817, -0.0625, +0.3360,
+ +0.3056, -0.0835, +0.0158, +0.1561, -0.5691, -0.0537, -0.0060,
+ +0.0156, -0.0768, +0.1259, +0.0801, -0.3652, -0.2935, -0.0957,
+ -0.3882, -0.0806, -0.1767, -0.1223, -0.2980, -0.0602, +0.0748,
+ +0.1073, -0.2273, -0.0432, +0.0205, -0.1205, +0.0701, +0.2412,
+ -0.0545, +0.4093, +0.1213, -0.1339, +0.2695, -0.1651, -0.3032,
+ +0.2259, +0.2772, -0.4091, -0.2053, +0.1683, +0.3017, +0.0795,
+ -0.0465, -0.1519, +0.1913, -0.0878, -0.3027, -0.1999, -0.1650,
+ +0.0766, +0.3527, +0.0193, -0.0428, -0.3020, +0.1492, +0.0307,
+ -0.0845, -0.3916, +0.2446, -0.2790, -0.1062, +0.0129, -0.0355,
+ -0.0179, +0.0488, -0.1491, -0.1360, -0.5012, -0.1146, -0.6466,
+ -0.0591, -0.2473, -0.0138, -0.0251, -0.3729, -0.4206, +0.0316,
+ +0.4263, +0.1346, +0.0591, -0.0302, -0.3306, +0.2092, +0.1464,
+ -0.2104, -0.0266, -0.5471, +0.3618, -0.0120, -0.0801, -0.6509,
+ -0.1565, +0.2461, -0.2794, +0.1373, -0.3501, -0.0141, -0.3659,
+ -0.0823, +0.0433, -0.4913, +0.1867, -0.1787, -0.2530, -0.0858,
+ +0.0631, +0.4656, -0.0758, +0.1346, +0.3409, -0.0766, +0.1549,
+ -0.1865, +0.0163, +0.1177, -0.1294, -0.0539, -0.1648, -0.3973,
+ -0.0093, +0.0441, +0.2224, +0.2009, -0.1244, +0.2471, -0.1195,
+ +0.2794, -0.1653, -0.0777, +0.2899, -0.0727, -0.0180, -0.1459,
+ +0.1405, +0.2990, -0.3099, -0.0493, -0.0159, -0.3430, +0.2833,
+ -0.0530, -0.1604, -0.0790, -0.0641, +0.4894, +0.1193, +0.0302,
+ +0.0596, -0.3592, -0.0790, -0.3708, +0.1281, -0.1684, -0.1438,
+ +0.1309, -0.1472, +0.0636, +0.0655, -0.2718, -0.3099, -0.2452,
+ -0.3439, -0.2408, -0.2503, +0.0348, +0.1378, -0.1481, +0.0495,
+ -0.0593, -0.2129, -0.1782, -0.1991, -0.0801, -0.0231, -0.2544,
+ +0.3121, -0.6851, +0.1245, +0.1280, +0.0607, +0.1181, +0.2037,
+ -0.0248, -0.0015, +0.2572, +0.1095, -0.4549, +0.0161, -0.0200,
+ -0.3575, -0.3766, -0.1733, -0.1862, -0.2414, -0.4685, -0.1836,
+ -0.3641, -0.1041, +0.0687, -0.1580, +0.1813, -0.0349, +0.2789,
+ +0.1194, -0.2338, +0.3210, +0.0017, -0.4004, +0.2656, +0.2545,
+ -0.2993, +0.1564, -0.3086, +0.0336, +0.0466, -0.0968, -0.2550,
+ +0.2261, -0.0329, -0.1153, -0.1083, -0.2512, +0.0684, -0.1142,
+ +0.1333, -0.0650, +0.2348, +0.3584
+ ],
+ [
+ +0.4732, -0.1606, +0.6582, -0.2787, -0.4086, +0.4893, -0.4595,
+ +0.1070, -0.2998, -0.3381, +0.4717, +0.0695, +0.0694, -0.1232,
+ -0.3385, +0.5312, -0.7533, -0.6750, +0.5398, -0.0136, -1.7436,
+ -0.4604, +0.1915, -0.0144, -0.8186, +0.6056, -1.0079, -0.6666,
+ -0.5122, +0.1853, +0.3952, +0.3490, -0.4289, -0.8478, -0.7121,
+ -0.3623, -1.4662, +0.2201, +0.5418, -0.3230, -0.6259, +0.1299,
+ -0.6091, -0.0094, +1.4666, -0.0719, -0.9252, +0.3602, +0.1149,
+ +0.3030, -0.2658, -0.4848, -0.1590, -0.5769, +0.0430, +0.2988,
+ +0.0350, +0.5103, +0.7586, +0.2644, -0.0157, -0.6312, -0.2371,
+ +0.1164, -0.9660, -0.9717, -0.1487, -0.1394, -0.5667, +0.3729,
+ -0.3456, +0.3801, +0.4136, +0.3297, +0.6520, +0.3534, +0.5755,
+ +0.4200, +0.3596, -0.0550, +0.0103, -0.2814, +0.1925, -0.1471,
+ +0.2325, -0.1932, +0.2907, +0.9803, +0.4304, -0.2703, +0.4069,
+ +0.0140, +0.3637, -0.1827, +0.2379, -0.0605, +0.1779, -1.0385,
+ -0.3431, +0.3169, +0.8508, -0.5855, +0.4819, -0.2676, -0.2594,
+ +2.1076, -1.0596, +0.4236, -0.3660, +0.6359, +0.4310, -1.0984,
+ -0.9941, +0.8232, +0.0712, +0.3779, -0.7529, +0.0185, +0.2977,
+ -0.6670, +1.1753, +0.0192, -0.2653, -0.9421, -0.1875, -0.4444,
+ +0.2785, +0.6543, -0.0886, +0.1154, -0.7106, -0.5924, -1.0759,
+ -0.0793, -0.5093, +0.2754, +0.4661, +0.6569, -0.0456, +0.8637,
+ -1.5313, -0.3027, +0.2600, -0.4001, -0.0731, -0.9646, -1.3496,
+ -0.5664, +0.6005, +0.7289, +1.0823, +1.0336, -1.1099, -1.7396,
+ -0.0138, -0.7396, -0.4744, +0.5657, -0.4586, +0.7394, +0.3641,
+ +0.1860, -0.2638, -0.0889, -0.1331, -0.8559, -0.1339, +1.0111,
+ -0.7366, -0.8960, +0.9621, -0.2681, +0.3126, +0.2824, +0.1901,
+ +0.1823, +0.1325, -0.3736, -0.2325, +0.3365, +0.2287, -0.0605,
+ +0.2358, +0.0979, +0.5472, -0.2089, -0.0947, -0.2847, -0.4178,
+ -0.4625, +0.9301, -0.4498, -0.1724, +0.1641, -0.2897, +0.7335,
+ +0.1285, +0.5672, +0.0944, -1.2222, -0.4112, +0.0133, -0.3927,
+ +0.7011, +0.1873, -0.9979, -0.6419, +0.0528, +0.2162, -0.9908,
+ -0.0299, -0.0079, -0.1600, +0.4196, -0.5376, -0.5944, +0.5843,
+ -1.4553, -0.3420, -0.0111, -0.3172, -0.7095, +0.3238, -1.5251,
+ -0.6495, +0.1290, +0.5290, +0.8379, -0.0186, +0.3914, +0.6254,
+ -0.9157, +0.5162, -0.7548, +0.2652, -0.1713, +0.6144, +0.3886,
+ -1.0187, +0.4616, -0.1282, +0.1885, +0.4676, -0.5539, -1.3952,
+ +0.1609, -1.3798, -0.9262, -0.0862, +0.4384, +0.1909, +0.6169,
+ -0.2354, +0.0560, -0.4729, +0.5102
+ ],
+ [
+ -0.2623, -0.5500, -0.8934, -0.5827, -0.3098, +0.0409, -0.5424,
+ +0.1890, +0.2709, -0.4536, -0.2234, -0.0921, -0.0883, -0.1581,
+ -0.2704, +0.1434, +0.5878, -0.1153, +0.3998, -0.5189, -0.0398,
+ -0.8323, -0.2917, -0.3440, +0.1746, +0.1797, -0.0405, +0.1575,
+ -0.4795, -0.0746, -0.0424, -0.3207, +0.5470, +0.0724, +0.6805,
+ -0.1680, +0.8424, -0.1252, -0.9788, +0.5110, -0.3236, -0.0378,
+ -0.3926, +0.3545, +0.6891, +0.0941, -0.4593, +0.3817, -0.4011,
+ -0.1867, +0.1241, -0.0399, +0.0399, +0.4695, +0.0817, +0.2802,
+ -0.2934, +0.1742, +0.2839, -0.6293, -0.0622, -0.3654, +0.3869,
+ +0.0138, +0.3932, +0.3312, +0.0329, -0.5800, -0.2554, -0.0443,
+ -0.1353, +0.3262, -0.1477, +0.3355, +0.4989, +1.0883, -0.1484,
+ -0.0356, -0.1507, +0.0998, +1.0423, +0.8652, +0.0962, -0.7090,
+ +0.0557, +0.4462, -0.5165, +0.3132, -0.1200, -0.7751, -0.2078,
+ +0.0040, +0.1418, +0.0903, +0.1258, -0.7325, -0.0397, +0.2254,
+ -0.0790, +0.6261, -0.1110, +0.0273, -0.3680, -0.6284, -0.5848,
+ -0.0510, -0.3352, -0.4350, +0.7128, -0.0535, -0.3427, +0.1700,
+ -0.1675, +0.5452, -0.0314, +0.0352, +0.0463, -0.2302, +0.2769,
+ -0.1505, -0.0960, -0.1267, +0.0688, -0.3363, -0.3650, +0.1264,
+ -0.6723, -0.1585, -0.3805, -0.5702, +0.3047, +0.0726, -0.1396,
+ +0.5884, -0.5775, -0.3510, +0.4869, -0.2920, +0.2757, -0.7034,
+ -0.5380, +0.2403, +0.4119, +0.0880, +0.4356, -0.1930, +0.0740,
+ -0.1306, -0.5824, -0.1174, +0.3561, +0.0697, +0.1986, -0.1393,
+ +0.6282, -0.6205, -0.1164, +0.2631, +0.2449, +1.0627, -0.6674,
+ +0.7347, -0.0015, -0.2780, +0.0399, +0.2840, -0.5423, -0.3100,
+ -0.2520, -0.5139, +0.2372, +0.0145, -0.3361, +0.2923, +0.0887,
+ +0.0496, +0.1057, +0.5594, -0.0216, +0.0017, -0.0902, -1.1624,
+ +0.2974, -0.0896, +0.0014, -0.1058, -0.2326, -0.4239, -0.6721,
+ -0.1929, -0.0481, +0.2104, +0.4768, +0.2210, -0.2804, -0.0495,
+ -0.2478, +0.0522, -0.0218, -0.0644, +0.2885, -0.2548, +0.0693,
+ -0.4215, -0.0662, -0.4346, +0.2659, +0.0776, -0.1521, -0.4458,
+ -0.0882, -0.0582, +0.8444, -0.5577, -0.3347, -0.0834, -0.6310,
+ +0.3409, -0.3974, -0.6091, +0.3574, +0.2273, -0.4237, +0.1367,
+ -0.1327, +0.0987, -0.9152, +0.5622, -0.0676, -0.6499, +0.3606,
+ +0.4399, -0.3099, -0.6367, +0.3527, +0.0088, -0.2020, -0.1820,
+ +0.0846, -0.6191, +0.1769, +0.3711, -0.1939, -0.3972, +0.0426,
+ +0.0640, +0.5209, +0.2030, +0.3277, -0.5862, +0.1393, -0.2087,
+ +0.5449, +0.1910, +0.0607, -0.1638
+ ],
+ [
+ +0.3326, -0.2192, -0.1261, -0.7672, -0.0726, +0.0749, +0.1123,
+ +0.2187, +0.0284, +0.2690, -1.0084, +0.3601, -1.6456, +0.1946,
+ +0.3244, -0.8317, +0.0052, +0.3999, -0.0599, -0.2789, +0.4927,
+ -0.0105, +0.6244, +0.6483, +0.2249, +0.2885, -0.0790, +0.6272,
+ +0.2172, +0.7959, -0.3381, -0.4279, +0.1254, +0.8320, -0.3991,
+ -0.4147, +0.0855, -0.0195, -1.0794, -0.2158, +0.6702, +1.1494,
+ +0.5560, +0.2204, +0.5365, -0.4700, +0.1475, +1.1094, -0.3511,
+ +0.0416, -0.2719, +0.1314, +0.6246, +0.5698, -0.1744, +0.2456,
+ -0.5748, +0.2735, +0.2794, -0.3873, -0.3518, -0.4836, -0.9445,
+ -0.7092, -0.1050, -0.5319, -0.0415, -0.4103, -0.8021, -0.4810,
+ -0.3130, +0.2015, -0.2658, +0.7122, -0.9539, -0.1401, +0.3261,
+ -0.1090, +0.1664, +0.8160, +0.8901, -0.4834, -0.9219, +0.2213,
+ +0.7483, -0.0979, +0.4085, +0.6627, -0.0915, -0.1968, -0.3771,
+ +0.0993, +0.7787, +0.2916, -0.1056, -0.9319, -0.6357, -0.2824,
+ -0.2307, -0.0626, +0.4354, +0.1002, -0.4637, -0.6664, -0.5818,
+ +0.3427, -0.1501, -0.4927, +0.1051, +0.9686, +0.4639, +1.0309,
+ +0.4054, +0.5349, -0.5620, +0.0207, -0.0858, -0.6535, +0.4465,
+ -0.0544, +0.4589, -0.3666, +0.5363, -0.2222, -0.2747, +0.3050,
+ -1.1584, +0.1305, +0.3800, +0.8084, +0.6366, +0.2893, +0.1092,
+ -0.0087, +0.9411, -0.5530, -0.4102, +0.2868, +0.3403, +0.1751,
+ -0.2593, -0.2496, +0.0389, +0.9976, -0.4269, +0.1595, +0.6351,
+ +0.2016, -0.0273, +0.3620, +0.8245, +0.5060, -0.2563, +0.2884,
+ -0.3763, -0.3475, -0.6837, +0.1288, -0.4847, +0.2518, -0.6590,
+ +0.4302, +0.0284, -0.3004, +0.1761, +0.0353, -0.3861, +0.6957,
+ +0.1880, -0.5363, +0.7874, -0.0366, -0.1364, +0.5343, +0.6380,
+ +1.6283, +0.0523, +0.5491, +0.3073, +0.7776, -0.5433, -1.0954,
+ -0.4400, +0.3572, +0.4507, +0.2235, +0.4191, -0.0030, +0.2167,
+ +0.0241, -0.2959, -0.1926, -0.0548, +0.6186, +0.1567, +0.0447,
+ -0.1605, -1.2927, -0.0799, -0.8015, +1.0467, +0.1503, -0.1165,
+ -0.3578, +0.0835, +0.3518, +0.6534, -1.6320, -0.4974, -1.2648,
+ +0.0539, -0.7212, -0.4364, -0.5707, -0.3332, +0.8711, -0.2449,
+ +0.2042, +0.1523, +0.2714, -0.1228, -0.3889, -0.8836, -0.0737,
+ -0.1996, +0.3627, +0.1584, +1.3699, +0.5986, +0.4335, +0.7518,
+ +0.4746, -0.6336, -0.6632, -0.1306, -0.2863, -1.0185, -0.5354,
+ +0.0729, -0.2683, +0.2188, +0.0261, -0.3163, -0.0834, +0.0905,
+ +0.2801, +0.6009, -0.2417, -0.5704, -0.4598, -0.5413, -0.0954,
+ -0.1351, +0.9718, +0.4152, -0.8522
+ ],
+ [
+ -0.1711, -0.1063, +0.0715, -0.3206, +0.1503, +0.3791, -0.1802,
+ -0.0566, +0.2265, -0.1800, -0.0480, -0.3589, +0.0047, +0.2423,
+ +0.3973, -0.1336, -0.1008, -0.2685, -0.0073, -0.0393, -0.1822,
+ -0.3134, +0.3055, +0.2837, +0.2647, +0.0811, -0.0392, +0.1127,
+ -0.1816, +0.1328, +0.0866, -0.1994, +0.0885, +0.0459, +0.6323,
+ -0.0745, -0.1675, -0.1628, -0.2264, +0.2328, +0.2803, +0.3329,
+ -0.0857, -0.0834, +0.0058, +0.2387, -0.0153, +0.1075, -0.1300,
+ -0.0398, +0.0271, -0.0736, +0.0525, -0.3868, +0.1940, -0.4156,
+ -0.0022, +0.0494, -0.0423, -0.2591, -0.0749, +0.0908, -0.0273,
+ +0.1700, -0.1291, +0.1797, -0.2058, -0.1395, -0.4264, -0.2898,
+ -0.1726, -0.0213, +0.1089, +0.0923, -0.0280, +0.2194, +0.0694,
+ +0.4390, -0.0365, +0.2571, +0.0334, -0.0207, -0.0985, +0.0378,
+ +0.0380, -0.0329, +0.3669, -0.1063, -0.1286, -0.0433, +0.1327,
+ -0.0711, +0.4962, -0.2371, -0.1473, -0.0841, -0.1811, +0.0358,
+ +0.1089, -0.1886, -0.1936, -0.2577, -0.0633, +0.4586, -0.1914,
+ +0.2095, -0.1539, +0.0479, +0.2096, -0.0109, +0.4658, +0.1918,
+ -0.1946, -0.4688, +0.0825, -0.0409, -0.0128, +0.0776, +0.0104,
+ -0.1060, +0.0913, +0.1380, -0.3030, +0.2420, -0.1261, +0.0273,
+ +0.2801, +0.1011, -0.2845, -0.0056, +0.0449, -0.2219, -0.3166,
+ -0.0995, +0.3312, +0.0378, +0.3752, +0.1273, -0.0218, +0.1467,
+ +0.7130, -0.1773, -0.0020, +0.0221, -0.2904, -0.3301, -0.0714,
+ -0.3943, -0.2730, -0.3627, +0.0126, +0.1011, +0.0552, -0.0592,
+ +0.1397, +0.4257, -0.5063, -0.1791, +0.3605, -0.0214, +0.0775,
+ +0.3434, -0.4018, -0.1175, +0.0876, -0.2879, +0.1134, +0.4348,
+ -0.0254, +0.0863, +0.1131, +0.1835, +0.2308, +0.3229, +0.3254,
+ +0.4667, -0.3888, -0.1415, +0.0981, +0.0166, -0.1201, +0.2934,
+ +0.3937, +0.2242, -0.5198, -0.3040, -0.0367, +0.1663, -0.3662,
+ +0.1434, -0.2027, +0.0861, +0.0767, +0.2295, -0.0056, +0.0315,
+ +0.0541, +0.2837, -0.1139, +0.0808, -0.0422, +0.0673, +0.1571,
+ -0.3419, -0.1489, -0.1222, -0.0932, -0.1747, -0.2475, +0.2277,
+ -0.2570, -0.1233, +0.2159, +0.0146, +0.0969, +0.0559, +0.2020,
+ -0.1456, +0.4296, -0.3832, +0.5871, +0.3385, +0.1100, -0.1362,
+ -0.0197, -0.1770, -0.1053, -0.1967, +0.1094, -0.1991, +0.4991,
+ -0.0012, -0.1015, -0.0932, -0.3859, +0.1861, -0.2871, +0.4395,
+ -0.2905, +0.3829, -0.1480, -0.0701, +0.1316, +0.0267, +0.1225,
+ +0.2529, -0.2509, -0.2783, +0.1156, +0.1564, -0.0783, -0.0978,
+ +0.2723, +0.2160, -0.1469, +0.3120
+ ],
+ [
+ +0.0315, -0.2696, -0.0547, +0.1758, -0.2117, +0.4463, +0.8609,
+ -0.1051, -0.0676, -0.3982, +0.9245, -0.1324, -0.1016, +0.6617,
+ -0.2366, -0.4399, +0.3019, +0.1689, -0.0158, -0.1818, -0.4215,
+ +0.0936, +0.5601, -0.0098, -0.1283, -0.0398, -0.0200, +0.2282,
+ +0.1735, +0.0721, -0.2770, -0.0388, +0.0866, -0.0641, -0.3395,
+ -0.0183, -0.2307, +0.2022, -0.0453, +0.1410, +0.1753, -0.2238,
+ -0.0288, +0.3948, +0.1377, -0.2461, -0.2781, +0.1382, +0.0858,
+ +0.0087, -0.2323, +0.0826, +0.3201, +0.0201, +0.1398, +0.4103,
+ +0.1346, +0.1654, -0.2246, +0.4345, -0.0825, +0.0604, -0.4920,
+ -0.1070, -0.2675, +0.0284, -0.6419, -0.0281, -0.1501, -0.1668,
+ -0.0765, +0.0647, -0.0766, +0.1001, -0.1794, +0.2516, +0.4290,
+ -0.7728, +0.2099, +0.0732, -0.2205, -0.5481, +0.1747, +0.2618,
+ -0.1887, +0.2324, +0.3140, -0.0721, +0.0421, -0.0456, +0.0669,
+ -0.3454, -0.0662, +0.4177, -0.1038, +0.2780, +0.0996, -0.5959,
+ -0.5961, -0.4114, +0.2390, -0.3022, -0.1677, -0.3278, -0.3484,
+ -0.1997, -0.0566, -0.0892, +0.7018, +0.6478, +0.1005, -0.5961,
+ +0.1566, +0.0825, +0.2346, -0.3356, -0.3185, +0.0755, +0.0411,
+ -0.0793, +0.3258, -0.1396, +0.1283, +0.1896, -0.5171, +0.1120,
+ -0.1224, +0.0367, +0.0743, +0.1430, +0.0132, +0.0149, +0.1147,
+ -0.4125, -0.2080, +0.1968, +0.8142, -0.0721, +0.3152, -0.2247,
+ +0.3908, +0.0971, -0.1424, +0.1374, +0.2706, -0.3770, +0.1096,
+ -0.0568, +0.3264, +0.4506, -0.4569, +0.1727, -0.2381, +0.4214,
+ +0.1191, -0.3278, +0.1992, -0.2243, -0.4143, +0.8708, -0.2386,
+ +0.7603, -0.1501, +0.0901, +0.4924, -0.2237, -0.3817, +0.1332,
+ +0.1977, +0.2710, +0.2726, -0.0557, +0.0365, -0.2051, +0.4295,
+ -0.0173, -0.0251, -0.2283, -0.5470, +0.2785, +0.4134, +0.1839,
+ -0.2030, -0.0077, -0.3212, +0.1286, -0.2258, -0.2953, -0.3600,
+ +0.0362, -0.2548, +0.1616, -0.2418, +0.2031, +0.1168, +0.1147,
+ -0.0406, -0.0521, -0.8852, -0.2120, -0.0571, +0.0538, +0.2702,
+ -0.2204, -0.2196, +0.0400, +0.1007, -0.4083, -0.1119, +0.3729,
+ +0.3893, -0.2311, +0.3263, +0.3975, +0.2199, +0.1641, +0.7579,
+ -0.3420, +0.3819, +0.0741, +0.7023, -0.1790, +0.3570, +0.1058,
+ -0.1609, -0.0125, +0.1419, -0.2185, +0.1101, +0.2555, -0.5080,
+ -0.2319, -0.0974, -0.4406, +0.3373, +0.7219, -0.2865, +0.0826,
+ -0.1259, +0.1188, -0.0105, -0.1039, -0.0604, +0.3308, +0.0726,
+ +0.0293, +0.4745, -0.6289, -0.2740, -0.5608, +0.1218, -0.0781,
+ +0.0437, +0.1166, -0.0665, +0.7765
+ ],
+ [
+ +0.1900, +0.1304, +0.1306, +0.1685, +0.0547, -0.1907, -0.0987,
+ +0.3965, +0.0377, +0.3136, +0.3067, +0.0101, -0.0786, -0.2354,
+ +0.2159, +0.2700, +0.1332, +0.0464, +0.0145, -0.3109, -0.1940,
+ +0.3194, -0.0398, -0.0600, -0.1790, +0.0580, +0.3900, +0.3714,
+ -0.3819, +0.1061, +0.0045, -0.2275, +0.0156, +0.1695, +0.1446,
+ +0.0291, +0.2628, -0.0779, +0.2689, +0.1189, +0.4291, +0.3251,
+ -0.2835, -0.1831, +0.5168, +0.2814, -0.2532, +0.1688, -0.0255,
+ +0.0595, -0.0628, -0.0292, +0.4426, +0.0847, -0.0432, +0.1771,
+ -0.1106, +0.0703, -0.0249, +0.0689, -0.0916, -0.0069, -0.0343,
+ -0.1095, -0.0536, +0.0074, -0.0784, -0.1075, -0.2998, -0.0088,
+ +0.1853, +0.0493, -0.1932, +0.0370, +0.2847, -0.0820, -0.1846,
+ -0.0661, -0.3196, +0.3797, -0.0899, +0.5101, +0.0220, +0.4859,
+ +0.3703, -0.0893, +0.0720, +0.0627, +0.0008, +0.2151, +0.2527,
+ -0.0721, +0.2133, +0.1272, +0.2210, -0.2012, +0.1135, +0.8663,
+ +0.3867, +0.5365, +0.1263, +0.2323, -0.0163, -0.1178, +0.4859,
+ +0.1277, -0.5319, +0.0241, +0.1482, -0.2447, +0.1440, -0.1298,
+ -0.0774, +0.1329, +0.2049, -0.1232, +0.0122, +0.2751, -0.1623,
+ -0.0355, +0.2232, +0.1650, +0.0788, +0.3453, +0.3085, -0.0324,
+ +0.2696, -0.1154, -0.0087, +0.0087, -0.0158, -0.0721, -0.2802,
+ +0.6397, +0.1834, +0.1206, +0.1670, -0.0771, +0.3098, +0.0817,
+ -0.2540, -0.1481, +0.3749, -0.1109, -0.1901, +0.0763, +0.0562,
+ -0.0834, +0.4640, +0.2060, -0.0520, +0.2273, -0.5758, +0.0613,
+ -0.3936, +0.4325, +0.3668, +0.6940, +0.0661, +0.1322, +0.0727,
+ -0.1327, -0.2523, -0.0368, +0.3519, +0.0042, -0.1765, -0.0588,
+ +0.0173, +0.3305, -0.0382, -0.0072, +0.1676, +0.4529, +0.1004,
+ +0.0037, +0.4982, -0.1013, -0.1774, -0.1828, +0.0592, -0.0361,
+ +0.1937, -0.3102, -0.0329, +0.7132, +0.1081, +0.1713, -0.1541,
+ -0.1572, +0.0455, +0.0631, -0.3422, -0.0472, +0.0655, -0.1291,
+ +0.1069, +0.3075, +0.2226, -0.1803, -0.1247, -0.0509, -0.1519,
+ -0.1252, +0.2028, +0.1468, -0.0986, +0.0458, +0.0799, +0.2962,
+ -0.2362, +0.1770, -0.0585, +0.1376, -0.1471, -0.0011, +0.3521,
+ +0.1243, -0.4805, -0.2684, +0.2582, +0.5082, +0.1511, +0.5160,
+ -0.3806, +0.1276, +0.1041, -0.3635, +0.0573, +0.0853, -0.1572,
+ +0.2395, -0.0647, +0.1263, +0.2338, +0.2568, +0.0774, +0.3536,
+ +0.4368, +0.1272, +0.1465, +0.0028, +0.2233, -0.0329, -0.0857,
+ +0.0750, +0.1408, +0.3485, -0.0137, +0.1533, -0.1600, -0.1337,
+ -0.0974, -0.0299, -0.0323, +0.0912
+ ],
+ [
+ -0.3504, +0.3179, -1.0918, -0.3050, +0.9112, +0.5211, +0.6364,
+ -0.0960, -0.5305, +2.3346, -0.7544, +0.0837, -1.0392, +0.7178,
+ -0.1126, +0.7165, +0.7288, +0.6258, +0.0957, -1.2260, -0.3948,
+ +0.3753, -0.4606, -1.5339, -0.2479, +0.2242, +0.6865, +0.0099,
+ -0.0191, +0.2671, -1.2197, +0.0032, +0.1167, +0.3508, +0.8007,
+ -0.7487, -0.4238, -0.6390, +0.5996, +1.5764, +1.4712, -0.0523,
+ +0.3140, -0.9890, +0.3494, +0.4810, +0.6032, +0.9013, +0.8956,
+ +0.0639, -0.6232, -0.0639, +1.3263, -0.6084, -0.2796, -0.4429,
+ -0.1116, +1.2581, -0.3688, +0.4144, +0.1753, -0.8812, +0.1593,
+ +1.7526, +0.2204, +0.7330, +0.7426, -0.1957, -0.5876, +0.3344,
+ -0.8807, -0.3715, -0.2438, +0.2862, +0.1338, -0.8705, +1.3052,
+ -0.7570, -0.9733, +0.0851, -0.1355, +0.7726, +0.9775, +1.8582,
+ +0.4909, +0.2100, +0.6480, -0.9390, -0.0109, +0.8414, -0.0162,
+ +0.1212, -0.3045, +1.2366, +0.6475, +0.0346, -0.5155, -0.4277,
+ -0.3017, -1.3542, +0.5016, +0.3839, +1.0181, -0.2053, +1.2256,
+ +0.6403, +0.2995, +0.1694, +1.1001, -1.2428, -0.6839, -0.0096,
+ +0.2364, +0.6608, -0.0468, +1.1051, -0.4258, +0.2412, -0.0888,
+ +0.4045, -0.8473, -0.3771, +0.0673, -0.7719, +2.2755, +0.1519,
+ +0.2434, -0.3192, +1.2985, +0.1204, -1.2696, +0.5239, +0.3562,
+ +1.0429, +0.1553, -1.0302, -0.3452, +0.4931, -0.8529, -0.2207,
+ -1.4133, -0.7739, -0.9373, -0.0316, -0.0720, -0.3610, -0.9920,
+ -0.2442, +0.1684, +0.8980, -0.3976, +0.5449, -1.5636, -0.8419,
+ -0.1692, +1.3491, +0.0253, +1.9946, +0.3635, +0.5639, +0.1305,
+ -1.3483, +0.7867, -0.0294, +1.3528, -0.4485, +0.0917, -0.0045,
+ -0.8327, +0.2827, +0.4188, -0.2105, +0.3741, +0.7789, +0.7423,
+ +0.3054, +0.5409, -0.3485, +0.2274, +0.8441, +0.2397, +0.5060,
+ +0.4379, +0.3308, -0.3921, +0.2715, -1.0825, -0.5958, +1.3096,
+ +0.7103, +0.1227, +0.1876, +0.7009, +0.2243, +0.6355, -0.1630,
+ +0.2463, +0.1666, -0.3954, -0.5123, -0.7415, -0.0754, +0.2274,
+ -0.2862, +0.2964, +0.0954, +1.1562, -0.3559, +0.4572, +0.9555,
+ -0.5453, +0.1497, +0.0105, -1.4956, +1.3926, +0.0228, -0.3674,
+ -0.1625, -0.9157, +0.7016, -0.6211, +0.5463, +0.3265, +0.9720,
+ -0.3992, -0.4322, -0.4880, -1.3482, +0.7272, -0.0962, +0.1547,
+ +0.6783, +0.1496, -0.0992, +0.4034, +0.1924, -0.1571, -0.0865,
+ +2.5906, +1.2446, -0.5539, -0.0809, +0.5130, -0.0844, +0.9177,
+ -1.3037, -0.0150, -0.6602, -0.0371, +0.3352, -0.4679, -0.8509,
+ -0.6062, +1.6027, -0.5644, -1.3218
+ ],
+ [
+ +0.2795, +0.0642, -0.4321, +0.1457, +0.0121, -0.6645, +0.5804,
+ +0.1799, +0.0117, +0.5672, -0.3526, +1.0581, +0.0324, +0.3915,
+ +0.1572, +0.0034, +0.2864, +0.1973, -0.4619, +0.3294, -0.0396,
+ -0.3446, -0.0199, -0.4083, -0.5971, +0.0460, +0.5415, +0.6182,
+ +0.2403, -0.1356, -0.1049, +0.4659, -0.2931, -0.2250, -0.6128,
+ +0.4385, -0.0995, +0.3239, +0.6134, +0.3091, +0.2143, +0.1731,
+ +0.0841, +0.1188, -0.3338, +0.3281, +0.2010, +0.5196, -0.1062,
+ +0.2815, +0.2324, -0.1379, +0.0957, -0.2191, +0.1873, +0.2349,
+ -0.1210, -0.0056, +0.0639, +0.0467, +0.4666, -0.0640, +0.1107,
+ -0.0418, -0.2104, +0.1299, +0.4768, -0.1160, -0.0516, -0.1398,
+ +0.3253, -0.0154, -0.2684, -0.1671, +0.4381, +0.1137, +0.2647,
+ -0.2082, -0.5011, +0.0124, +0.2318, -0.0503, +0.0276, +0.8962,
+ +0.2799, +0.3159, -0.6777, -0.0680, +0.1874, +0.1644, +0.1518,
+ +0.1808, +0.0803, -0.2494, +0.5158, -0.2165, +0.3377, +0.8342,
+ +0.0527, -0.6154, +0.1771, -0.1781, -0.0620, -0.7147, -0.3531,
+ +0.2948, +0.0663, +0.3923, +0.6540, +0.0174, +0.6028, -0.1087,
+ +0.4604, -0.0161, +0.2117, +0.3383, -0.2849, +0.9566, -0.4082,
+ +0.2355, +0.0818, -0.0087, -0.1493, +0.1262, +0.5054, -0.1072,
+ -0.1005, +0.2100, +0.2903, +0.3424, -0.1168, +0.1297, -0.4548,
+ -0.4380, +0.6081, -0.8408, +0.4011, -0.0471, +0.3515, -0.2566,
+ +0.8423, +0.1594, +0.1761, -0.0926, -0.3069, +0.2977, +0.0840,
+ +0.2581, -0.1953, +0.2386, +0.2111, +0.4178, -0.1321, -0.0219,
+ +0.5732, -0.0419, -0.2215, -0.5132, +0.3878, +0.0862, -0.3056,
+ +0.3618, +0.7162, -0.0857, +0.1711, -0.1898, +0.2286, +0.6806,
+ +0.3809, +0.2188, +0.2804, -0.2275, +0.6766, +0.1952, +0.0073,
+ -0.3949, -0.1420, +0.3417, -0.3001, +0.1640, -0.1118, -0.5296,
+ -0.0676, -0.1672, +0.2324, -0.0308, +0.0786, +0.9096, +0.7681,
+ -0.2398, +0.0431, -0.1578, +0.3719, -0.3167, +0.8528, -0.0046,
+ -0.0758, +0.2415, -0.2559, -0.1975, +0.2967, -0.1169, +0.0701,
+ +0.1372, -0.0018, +0.2277, -0.2830, -0.1139, +0.4305, -0.3147,
+ -0.3947, -0.2646, -0.1233, +0.6040, +0.2712, +0.5285, -0.3873,
+ +0.1587, -0.0579, -0.4679, -0.2148, -0.1199, -0.3221, +0.0139,
+ +0.2610, -0.2710, -0.0914, -0.3749, +0.8469, -0.0296, +0.0442,
+ +0.4900, +0.0576, +0.9743, +0.1762, -0.1878, -0.2236, +0.2311,
+ -0.1199, -1.0481, -0.3038, -0.3667, +0.0169, -0.1208, +0.0286,
+ +0.1759, +0.1569, +0.1607, +0.8348, +0.0245, +0.1323, -0.3582,
+ +0.6256, -0.2299, +0.2870, +0.0372
+ ],
+ [
+ +0.4222, -0.0573, +0.5081, -0.3760, +0.7451, -0.3354, +0.9356,
+ +0.3947, +0.3637, -0.1050, -0.9781, +0.0794, -0.0114, -0.2344,
+ +0.9890, +0.2250, +0.6542, +1.0132, +0.4594, +0.1899, -0.5553,
+ -1.0695, -0.0464, -1.0895, -1.4412, -0.4980, +0.1758, +0.2815,
+ +0.6579, -0.0964, -0.0780, +0.3784, -0.4967, -0.2489, -0.4366,
+ +0.4137, +0.5941, +0.9789, +0.0680, -0.1903, +0.4329, -1.2772,
+ -0.2180, +0.1931, -0.5630, -0.7352, +1.4870, -0.7178, -0.2086,
+ +0.0265, -0.1702, +0.1937, -0.0929, -0.7027, +0.1547, +0.8569,
+ -0.3356, +0.3963, +0.7436, +0.5573, -0.0482, +0.1243, +0.5669,
+ +1.2589, -0.1877, -0.2490, +0.0755, +0.6648, -0.4557, -0.9240,
+ +0.0784, +0.3344, -0.4727, -0.2906, +0.2908, -0.0087, -0.8507,
+ +0.9188, -1.0174, -0.3030, -0.1066, -0.1418, +0.6422, -0.4228,
+ +0.8031, -0.0486, +0.0789, +0.0159, +0.4195, +0.7959, -0.4948,
+ +1.0052, -0.4370, -0.3082, +0.4453, -0.8982, +0.1833, -0.0529,
+ -0.2152, -0.6723, -0.5515, -0.5945, +0.1152, +0.2134, -0.1846,
+ -0.0981, +0.0175, +0.3448, -0.5466, -0.3407, +0.8680, -0.2085,
+ +0.9641, -0.1393, -0.2101, -0.2797, +0.4820, -0.4386, -0.8097,
+ +0.0695, +0.3653, +0.4081, -0.0723, +0.6429, -1.1749, +0.0525,
+ -0.3654, -0.7180, +0.1074, -0.2005, +0.3934, -0.5641, -0.3977,
+ -0.7490, -0.7064, -0.2359, +0.3631, -0.7209, +0.4213, +0.5278,
+ +0.1775, -0.0226, +0.2676, -0.8443, +0.6325, -0.6958, -0.0446,
+ +0.0145, +0.6466, +0.4083, +0.2505, -0.3254, -1.3595, -0.2900,
+ +0.3684, +0.2849, -0.0168, -0.9716, +0.0890, +0.1455, +0.1932,
+ -0.2316, -0.2257, +0.1177, +0.1743, -0.0457, -0.7849, +0.7017,
+ -0.4356, +0.1590, +0.2895, -0.5398, +0.2746, -0.1955, -0.9924,
+ +0.4579, +0.0071, -0.0746, +0.2151, -0.1827, +0.5044, -0.5401,
+ -0.4354, +0.1411, -0.2633, +0.7402, +0.0019, -0.0907, +0.3447,
+ -0.6141, -0.2552, +0.5652, +0.2047, -0.5309, +0.2966, +0.0315,
+ +0.2328, -0.1916, -0.2069, -0.1830, +0.6357, +0.4643, -0.5741,
+ +0.4861, +0.7827, -0.0479, -0.3617, -0.1293, -0.0768, -0.3499,
+ +0.2789, -0.1915, +0.0334, +0.0698, -0.1463, +0.4034, -0.1668,
+ +0.9289, -0.9585, -0.4268, -0.3682, +0.1801, -0.8269, -0.3515,
+ +0.3098, +0.1076, +0.6027, -0.1172, +0.0588, +0.7357, -0.0441,
+ -0.1213, +0.2665, -0.4022, -0.2895, -0.3017, -0.3352, -0.3031,
+ -0.1225, -0.1627, -0.6134, -0.3426, +0.4558, -0.3361, +0.5679,
+ +0.5502, -0.0751, -0.7189, +0.6709, +0.5030, +0.3367, -0.7531,
+ +0.9245, -0.8705, +0.2312, +0.0640
+ ],
+ [
+ -0.0035, -0.0034, -0.2528, -0.3608, +0.3682, -0.2742, -0.0113,
+ -0.3332, +0.0137, -0.0303, -0.0216, +0.0627, +0.1116, +0.0642,
+ -0.3810, +0.0072, -0.0297, -0.1337, +0.2035, -0.1883, +0.0202,
+ -0.0721, +0.1509, -0.2001, +0.5420, -0.1128, -0.1005, +0.1079,
+ +0.1587, +0.0785, -0.0149, -0.0047, +0.3506, +0.3381, -0.1188,
+ +0.1962, -0.0130, -0.0012, -0.2426, +0.1351, +0.1945, +0.1089,
+ +0.2607, +0.0582, -0.2137, +0.6271, +0.1350, +0.0122, -0.1709,
+ -0.2135, -0.1653, +0.0632, +0.4087, -0.0052, +0.6810, +0.0148,
+ -0.0323, +0.3402, +0.0679, +0.1630, -0.0387, -0.0974, -0.0687,
+ -0.0846, +0.1532, +0.1129, -0.0719, +0.0268, -0.1528, +0.0340,
+ -0.0595, +0.3099, +0.0794, -0.0118, +0.0639, -0.3403, +0.0216,
+ +0.0587, +0.1669, +0.1529, -0.0114, -0.5345, -0.0442, -0.2288,
+ +0.4265, -0.3686, +0.1109, +0.0872, +0.1012, +0.1267, -0.0799,
+ +0.0821, +0.1215, -0.1414, +0.1897, +0.3936, +0.1082, +0.0621,
+ +0.4993, +0.1550, +0.0853, -0.1830, -0.0109, +0.2747, +0.0066,
+ -0.0596, -0.0209, -0.1222, +0.6425, +0.0010, -0.1389, +0.2046,
+ -0.0143, -0.1457, +0.2317, -0.3896, +0.1399, +0.0099, -0.0574,
+ +0.3197, -0.2081, +0.1138, +0.0407, -0.0042, +0.0752, +0.0459,
+ -0.2480, +0.0822, -0.3238, +0.0392, +0.3801, +0.1197, +0.2401,
+ -0.4082, +0.0690, +0.1263, +0.1912, +0.2382, +0.0859, -0.4645,
+ +0.1211, +0.0598, -0.1411, +0.2445, -0.0240, +0.1098, +0.1856,
+ +0.2397, -0.0041, +0.1188, -0.0047, +0.0424, +0.5290, +0.3475,
+ +0.1254, +0.0685, +0.0748, -0.0148, +0.1090, -0.0598, -0.0045,
+ -0.2743, +0.1616, +0.1719, -0.1873, -0.0924, -0.0310, -0.1332,
+ -0.1907, +0.1881, -0.4096, +0.1428, +0.2975, -0.0189, +0.2020,
+ +0.2217, -0.0367, +0.3606, +0.4407, -0.2666, +0.0850, -0.0286,
+ -0.1606, +0.1058, +0.0790, +0.1514, -0.0547, +0.1220, -0.2964,
+ +0.1235, +0.4847, +0.0590, +0.0304, +0.2212, +0.2509, -0.1166,
+ +0.0666, -0.1935, +0.0430, -0.1518, +0.3587, +0.0948, +0.2795,
+ +0.4758, +0.0747, -0.1021, +0.3524, +0.0737, +0.1654, +0.6264,
+ -0.0327, -0.1234, +0.0612, -0.0495, -0.2775, -0.2223, -0.0795,
+ -0.0540, +0.4101, +0.0887, +0.6357, -0.0557, +1.0091, +0.3728,
+ -0.2812, +0.0505, -0.2041, -0.0258, -0.0876, +0.0441, +0.0864,
+ -0.0484, +0.3001, +0.3026, +0.0090, -0.2822, -0.1953, -0.2267,
+ -0.2283, -0.0550, +0.4666, -0.2008, -0.1510, -0.0588, +0.0770,
+ +0.3002, +0.0200, +0.1235, -0.0181, +0.1489, +0.1830, -0.0221,
+ +0.2327, -0.2378, -0.1699, +0.4160
+ ],
+ [
+ -0.1059, +0.1515, +0.0140, +0.1541, +0.3425, -0.3510, +0.1152,
+ -0.0096, +0.0941, +0.2030, -0.5814, +0.1163, -0.1798, +0.2130,
+ -0.0308, -0.2670, -0.0307, +1.1302, -0.5876, -0.1339, +0.0085,
+ -0.4369, -0.0089, +0.2912, -0.0841, -0.0179, +0.0648, -0.2874,
+ -0.3967, +0.1606, +0.4970, +0.0788, +0.1305, +0.6643, +0.8430,
+ +0.0646, +0.0448, -0.3034, -0.1129, -0.3283, +0.0435, +0.5129,
+ -0.1075, -0.1883, +0.4669, -0.3403, -0.1316, +0.3523, -0.0285,
+ -0.1050, -0.0914, -0.0981, +1.3083, -0.3445, -0.5618, +0.0772,
+ +0.1022, -0.0018, -0.1475, -0.3236, +0.1725, -0.3069, +0.1140,
+ -0.1664, +0.1786, -0.4218, +0.2003, +0.1524, +0.2598, +0.0738,
+ +0.0487, +0.4012, -0.3416, +0.1218, -0.1210, +0.9181, +0.6536,
+ +0.4306, +0.0462, +0.6724, +0.0628, -0.5143, +0.2787, +0.1601,
+ +0.2327, -0.0700, -0.0750, -0.2287, +0.2918, -0.3260, +0.0710,
+ +0.0433, -0.6924, +1.1640, +0.4052, +0.4894, -0.0450, +0.6232,
+ +0.1674, -0.1411, -0.1690, -0.3918, -0.5933, +0.4397, +0.5854,
+ +0.6074, -0.2093, -0.2082, -0.2854, -0.2730, +0.4739, -0.1440,
+ -0.0470, +0.3595, +0.0505, +0.0261, +0.2556, +0.1997, +0.1467,
+ -0.6146, -0.1772, +0.3620, +0.2029, -0.1267, -0.5105, +0.2807,
+ -0.7753, +0.0937, -0.0990, -0.0566, +0.1463, +0.4945, -0.4445,
+ +0.2097, -0.4238, +0.3291, +0.4771, -0.0934, +0.3328, +0.0125,
+ +0.2216, +0.1743, -0.1884, -0.1027, +0.1037, +0.9080, +0.7220,
+ +0.3006, -0.4461, +0.2261, +0.3679, -0.0083, +0.1107, -0.2835,
+ -0.2122, +0.9465, +0.2494, +0.2009, +0.3854, +0.3620, -0.0232,
+ +0.7130, +0.5914, +0.2367, -0.1907, +0.0126, -0.4836, -0.7799,
+ +0.1886, +0.7844, +0.0632, -0.1651, +0.5767, -0.3709, +0.2219,
+ -0.4823, -0.4274, +0.1896, -0.2534, +0.2759, -0.0053, +0.3047,
+ +0.0830, -0.0579, -0.5030, -0.3829, +0.2817, -0.4349, -0.1430,
+ +0.1322, +0.3572, +0.0090, -0.5643, +0.1411, -0.4972, -0.3413,
+ -0.1593, +0.0419, -0.3883, +0.0232, -0.1065, -0.0463, +0.3074,
+ +0.6826, +0.1211, +0.1497, -0.0864, +0.0145, +0.6440, -0.1601,
+ +0.2847, +0.4424, +0.1406, +0.3737, -0.0508, -0.0550, +0.2662,
+ -0.1365, -0.2198, -0.1154, +0.1846, +0.3939, -0.1867, +0.2783,
+ +0.0214, -0.2052, +0.2852, +0.4517, -0.0070, +0.9497, -0.0211,
+ -0.5972, +0.0932, -0.0961, +0.0633, +0.5786, -0.2438, -0.1156,
+ +0.1324, -0.0539, +0.1527, +0.5762, -0.0996, +0.2633, -0.0446,
+ +0.2198, -0.1069, -0.1196, -0.3112, +0.2806, -0.0446, -0.3673,
+ -0.3333, -0.5466, -0.6300, -0.0539
+ ],
+ [
+ +0.0886, -0.1736, +0.2303, +0.7947, +0.0393, -0.2798, -0.5487,
+ -0.2241, -0.5310, +0.5406, -0.0532, -0.0064, +0.2742, -0.3217,
+ -0.2300, +0.1303, -0.2625, -0.4393, +0.0598, -0.2584, +0.0027,
+ +0.2343, +0.3005, -0.3532, -0.7355, -0.1263, -0.0904, +0.0143,
+ +0.0917, +0.3467, -0.1259, +0.0210, -0.0186, -0.0360, -0.4055,
+ +0.0844, +0.3825, +0.1753, +0.3408, +0.2307, +0.4749, +0.1994,
+ +0.1054, +0.3573, -0.2327, +0.0036, -0.2009, -0.1823, +0.0889,
+ -0.0884, -0.2532, +0.3909, -0.2113, -0.2426, +0.1061, +0.2335,
+ +0.3052, +0.1240, -0.2379, -0.0317, +0.0107, -0.3895, -0.0050,
+ -0.0169, +0.1984, -0.1232, -0.2768, +0.4420, +0.0246, +0.3070,
+ -0.1335, +0.2652, -1.1367, +0.2838, +0.3087, -0.5247, +0.1373,
+ -0.5731, +0.0517, -0.8331, +0.0370, +0.0661, -0.1572, +0.1051,
+ -0.4990, -0.9321, +0.2448, +0.2690, +0.2054, -0.4378, +0.0132,
+ -0.3105, -0.1545, -0.3607, +0.4425, -0.1347, +0.2146, +0.2794,
+ -0.1716, -0.0498, +0.0685, +0.4673, -0.5200, +0.4520, -0.0439,
+ +0.0930, -0.0961, -0.2375, +0.2483, -0.1084, +0.0855, +0.3815,
+ +0.1763, -0.2518, -0.0570, -0.2764, -0.9503, +0.4452, -0.2262,
+ +0.2897, +0.2107, -0.2425, -0.2231, +0.1219, -0.2070, -0.3488,
+ -0.2947, +0.0958, +0.0930, +0.1411, +0.3361, -0.2040, +0.2504,
+ -0.7070, +0.2827, -0.1822, -0.1630, -0.0348, +0.0428, +0.0818,
+ -0.1700, +0.0074, +0.1539, +0.0177, +0.3407, -0.0548, +0.5441,
+ -0.1306, -0.4407, +0.0646, -0.3218, -0.0806, +0.1349, -0.2540,
+ -0.0872, +0.4692, -0.4425, -0.5095, -1.0056, +0.4027, -0.0200,
+ -0.1376, +0.0475, -0.7649, -0.3253, -0.6835, -0.0361, +0.1053,
+ -0.0829, +0.3581, +0.3582, +0.2497, +0.0393, +0.5963, +0.3694,
+ -0.2755, -0.4194, +0.3549, +0.2054, +0.2459, -0.3597, -0.1185,
+ +0.0509, +0.6428, -0.3443, +0.2562, +0.0889, +0.3400, -0.6770,
+ -0.0713, -0.2477, +0.2696, -0.1843, +0.4073, -0.2708, -0.0514,
+ +0.2385, +0.0235, -0.1136, +0.4380, -0.0392, +0.0524, -0.4062,
+ +0.1885, -0.7391, +0.2537, +0.0709, -0.3841, -0.6341, +0.1817,
+ -0.4291, -0.5313, -0.9104, +0.3972, +0.0307, +0.2267, -0.0018,
+ +0.2399, -0.1271, -0.1045, +0.1824, -0.9698, +0.0084, -0.2353,
+ -0.0986, -0.3136, -0.0781, -0.0959, -0.3397, -0.8343, -0.6744,
+ +0.2505, +0.0941, +0.0670, +0.2594, -0.5116, -0.1491, +0.4280,
+ +0.3119, +0.6404, +0.1156, +0.2095, -0.0151, -0.0291, +0.0717,
+ -0.2272, -0.3254, +0.0794, +0.0487, +0.1850, -0.2387, -0.0572,
+ -0.2224, -0.4618, -0.5881, -0.0762
+ ],
+ [
+ +0.1613, -0.0121, -0.6823, +0.4505, +0.0159, -0.6711, -0.4259,
+ -0.0010, -0.1023, -0.0402, +0.1031, -0.1431, -0.0213, +0.4424,
+ -0.1080, -0.2636, -0.0149, -0.1129, -0.4833, +0.1006, -0.8493,
+ -0.2696, +0.3725, +0.1174, +0.3757, +0.0964, -0.1318, +0.1640,
+ +0.0253, +0.2252, -0.1748, -0.0377, -0.0120, +0.1607, +0.0376,
+ +0.0201, +0.0198, -0.3454, -0.2380, +0.4885, -0.2846, -0.3210,
+ -0.3668, +0.1292, +0.0733, -0.1518, -0.1435, +0.7051, +0.0440,
+ -0.3134, +0.1986, -0.0950, -0.2036, -0.5937, -0.5377, +0.0555,
+ +0.1399, -0.1929, -0.1455, -0.0545, -0.5609, +0.4115, -0.3768,
+ -0.6463, +0.4130, -0.0706, +0.1245, +0.2189, -0.1688, -0.4369,
+ -0.0189, -0.1132, +0.0900, -0.0476, -0.3192, -0.0721, +0.3550,
+ +0.0791, -0.1973, +0.2124, -0.3421, -0.2505, -0.4525, -0.3532,
+ -0.4306, +0.0726, -0.1936, +0.3790, +0.0773, +0.1141, +0.3051,
+ -0.1605, -0.1697, -0.3239, -0.0387, +0.0490, +0.4097, -0.1983,
+ -0.3103, -0.1348, +0.0983, -0.1906, -1.0984, -0.3224, +0.1721,
+ +0.0596, -0.0802, +0.1193, +0.5012, +0.4600, +0.1982, -1.2366,
+ -0.3397, +0.0045, +0.0963, +0.0420, +0.0534, -0.6935, -0.1704,
+ +0.2974, -0.5040, -0.4112, +0.1151, -0.3827, -0.6324, +0.1939,
+ -0.0368, +0.1991, -0.2959, +0.1311, +0.0653, -0.1839, -0.3214,
+ +0.2320, +0.2095, +0.0678, +0.0375, -0.1832, +0.4512, +0.2901,
+ -0.4755, +0.2493, +0.2288, +0.0834, -0.3465, +0.4282, +0.0664,
+ -0.2354, +0.3027, +0.2787, +0.2102, +0.1778, -0.2229, +0.2759,
+ -0.2128, +0.5151, -0.0355, -0.2695, +0.0498, -0.6670, -0.2849,
+ -0.1452, +0.4245, +0.4908, +0.4679, +0.0071, +0.3998, +0.0380,
+ -0.1295, -0.2110, -0.0502, +0.0330, +0.5156, +0.2586, -0.1972,
+ +0.1425, -0.5514, -0.1277, +0.3379, -0.1527, -0.0876, -0.1846,
+ +0.3335, -0.2494, -0.1005, +0.0055, +0.1809, +0.2810, -0.2826,
+ +0.1018, -0.1270, +0.2189, +0.2438, +0.0231, -0.0637, -0.4122,
+ -0.1142, +0.0933, -0.0771, +0.0415, -0.0525, +0.1933, +0.5861,
+ +0.1639, -0.0109, -0.1786, -0.3391, -0.0341, +0.4664, +0.3602,
+ -0.2455, -0.1581, +0.0035, -0.6658, -0.4299, +0.0850, -1.0917,
+ -0.1338, +0.4143, +0.0696, -0.3031, +0.3610, +0.2661, +0.1521,
+ +0.6565, +0.1507, -0.1110, +0.1716, +0.2436, -0.5497, -0.6088,
+ -0.4964, +0.0426, -0.4534, -0.0126, -0.2565, -0.2301, +0.0974,
+ +0.1669, +0.5493, +0.0544, +0.2104, +0.0747, +0.2049, +0.2100,
+ +0.1637, -0.5843, +0.3274, -0.4244, +0.4082, +0.2544, +0.0823,
+ +0.2458, +0.1169, +0.1472, +0.0367
+ ]])
-weights_dense2_w = np.array([
-[ -0.0446, -0.0941, -0.3955, -0.1329, +0.3261, -0.2340, +0.1304, +0.1444, -0.0064, +0.4035, +0.5651, +0.2906, -0.2569, -0.1496, -0.6781, +0.3623, +0.3923, -0.5059, +0.0361, -0.2793, -0.3257, -0.5450, +0.1372, -0.3239, +0.1807, +0.4815, -0.5801, +0.0871, +0.0759, -0.4970, +0.1630, -0.2405, +0.1363, -0.2391, -0.3084, -0.1048, -0.4797, +0.1461, -0.4725, -0.4272, -0.1229, -0.3213, -0.3729, -0.2070, -0.2260, +0.0191, +0.4376, +0.2038, +0.4303, -0.3538, -0.3511, -0.0173, -0.0621, +0.1285, -0.0412, -0.4655, -0.5779, -0.1277, -0.0267, -0.3498, +0.1073, +0.0636, -0.7525, +0.1612, +0.3821, -0.1038, -0.8780, +0.3191, +0.2394, -0.0068, +0.0812, -0.2313, -0.2938, -0.3093, -0.3838, -0.0023, -0.5775, +0.4613, +0.3519, -0.1342, -0.4099, +0.0764, -0.2711, -0.0370, +0.0079, +0.0552, +0.4197, -0.9073, -0.2105, +0.2615, -1.1096, +0.0082, +0.4138, +0.2725, +0.0815, +0.3513, -0.7101, -0.1694, -0.0091, +0.2357, -0.2003, +0.3896, -0.0686, -0.6690, -0.0813, +0.2245, +0.2243, -0.3500, +0.3599, +0.0891, -0.5524, -0.1980, -0.3951, +0.0085, +0.0538, +0.6534, -0.8200, +0.1080, -0.3786, +0.1675, -0.0115, +0.1537, +0.4711, -0.0807, -0.1799, +0.0223, +0.2167, +0.2362],
-[ -0.2444, -0.6241, -0.1147, -0.2118, +0.0857, -0.3879, +0.3546, -0.0733, -1.0193, +0.1459, +0.0498, -0.2553, -0.2879, -0.5408, -0.3574, +0.4237, -0.7382, -0.2695, +0.0282, -0.2548, -0.2155, -0.2600, -0.1573, -0.3413, -0.6334, +0.0929, -0.0176, -0.3606, +0.2845, -0.0617, -0.3122, +0.1209, -0.2462, +0.3425, +0.2171, +0.5273, -0.1572, -0.1532, +0.5552, -0.0139, +0.1994, +0.0812, -1.0411, +0.3236, -0.2614, -0.3478, -0.1349, +0.1892, +0.3215, -0.2034, -0.0209, +0.2062, -0.3500, +0.1164, +0.1389, +0.2095, +0.2791, -0.1504, +0.1044, +0.4266, -0.7286, +0.2604, -0.2693, -0.1244, +0.1317, +0.3252, -0.7114, +0.5549, -0.1956, -0.1914, -0.4135, -0.3006, -0.4114, +0.0110, -0.3341, -0.3824, -0.2613, -0.7747, +0.5477, -0.0026, -0.2780, +0.3150, -0.3447, -0.0708, -0.1666, +0.1757, +0.2413, -0.0522, -0.1630, -0.1557, +0.2338, -0.4316, +0.0440, -0.3387, +0.2614, -0.2280, +0.0125, -0.0967, -0.1448, +0.3245, +0.1507, -0.2703, -0.2256, -0.3510, -0.5730, -0.6961, +0.3662, -0.3726, +0.3866, +0.1329, -0.7782, +0.0877, -0.5175, -0.0080, -0.4061, +0.0042, -0.0629, -0.0861, +0.1035, +0.3153, -0.1609, -0.0586, +0.1450, +0.0041, +0.1466, -0.6496, +0.0201, +0.0129],
-[ +0.1386, -0.0945, +0.2795, -0.0256, -0.0028, -0.0133, -0.4415, -0.1106, +0.1377, +0.3588, -0.4300, +0.3529, +0.2544, +0.1488, +0.4599, +0.3566, +0.1138, -0.4420, -0.1201, +0.1293, -0.5788, -0.0978, -0.1088, +0.1153, -0.4146, +0.1100, +0.0620, +0.1854, -0.7047, -0.0504, +0.2937, +0.0530, +0.0955, -0.0370, +0.0178, +0.1662, -0.2216, -0.0763, -0.4237, -0.5979, +0.0670, -0.0144, +0.0355, -0.5579, +0.2910, +0.2649, +0.0297, -0.4149, -0.2434, -0.2470, -0.2179, +0.1319, -0.1494, +0.3073, -0.3072, -0.3915, +0.3447, +0.2100, -0.4788, -0.0824, +0.2316, -0.0760, -0.2466, +0.0284, -0.0477, -0.0012, -0.7704, +0.3028, -0.8417, +0.0159, +0.6322, +0.0871, +0.1442, -0.0744, -0.0640, +0.3171, +0.0569, -0.0746, -0.0438, -0.2017, -0.2061, +0.0221, -1.0163, -0.3438, -0.0295, +0.1516, -0.2567, -0.4551, +0.1802, +0.2473, -0.3067, -0.0302, -0.2944, +0.0247, +0.1530, -0.4357, -0.2943, -0.1051, -0.3184, -0.0940, +0.1110, -0.2013, +0.1567, +0.4995, -0.6288, +0.5756, +0.0462, -0.0036, -0.8926, -0.1855, +0.0631, -0.7486, +0.0764, +0.2724, -0.3770, -0.4466, +0.1047, +0.2308, +0.1856, -0.3025, -0.2538, -0.0370, -0.6129, -0.6437, +0.0648, +0.0632, +0.1569, -0.5954],
-[ -0.2110, -0.4682, +0.1521, -0.2096, +0.0752, -0.2327, -0.3026, +0.0227, +0.1361, +0.1600, -0.0204, -0.5653, +0.3198, -0.2031, -0.5835, +0.0099, -0.0005, -0.0378, +0.1420, +0.2448, -0.1970, -0.6869, +0.1893, -0.3542, +0.3116, +0.1331, +0.2216, -0.0751, +0.0818, -0.0981, -0.4190, +0.5141, -0.0763, +0.0360, -0.1761, +0.0261, -0.5464, -0.7008, -0.2040, -0.1353, +0.2963, -0.1157, +0.0362, -0.5863, -0.8737, -0.3414, +0.0769, +0.1460, -0.1560, -0.0128, +0.2671, +0.3803, +0.2876, -0.1158, +0.0046, -0.1798, -0.0418, -0.2737, -0.4797, -0.4231, -0.1860, -0.5159, -0.8221, +0.3182, -0.7719, +0.1197, +0.1327, -0.3147, -0.1979, -0.3086, +0.1928, -0.0266, -0.2050, -0.0781, +0.4301, -0.0320, +0.5265, -0.2464, +0.3842, -0.1679, +0.0903, -0.0991, +0.5649, -0.2095, -0.3192, +0.5082, +0.2163, -0.1517, +0.3231, -0.0450, -0.6572, -0.2979, +0.5014, -0.6241, -0.1478, -0.3796, +0.0776, +0.0567, -0.2926, +0.2549, -0.4551, -0.1126, -0.3430, +0.0577, -0.0678, -0.6104, +0.1488, +0.0124, -0.0232, +0.1021, +0.4954, +0.0608, -0.2865, -0.1660, +0.3615, +0.2145, +0.0863, -0.0482, +0.1043, -0.0310, +0.1584, -0.1514, -0.2689, -0.2622, +0.2389, -0.0352, +0.0505, -0.4725],
-[ -0.0229, -0.4313, +0.0184, -0.8077, +0.5455, +0.2926, +0.1833, -0.1669, -0.3142, -0.2872, -0.1973, +0.1569, -0.0577, +0.2992, +0.0187, -0.3197, +0.1143, +0.3957, -0.0845, -0.0656, -0.6643, -0.1391, -0.3222, +0.7873, +0.0598, +0.3911, +0.0200, +0.1554, +0.2937, -0.4432, -0.2098, -0.5019, +0.2838, +0.1635, -0.0923, -0.3384, -0.3427, +0.3220, +0.4029, -0.3257, +0.1441, -0.0432, -0.3495, -0.5423, +0.2564, -0.0237, +0.4511, +0.0765, -0.0877, -0.0430, +0.3376, -0.2686, +0.3190, +0.0444, -0.0437, +0.1836, -0.0036, -0.1122, -0.5164, -0.0967, -0.0943, -0.0267, -0.2884, +0.1110, -0.0452, -0.5358, -0.9480, -0.0428, +0.0632, +0.5967, -0.5697, -0.5430, -0.3233, -0.1837, -0.3865, -0.1141, -0.3161, -0.3135, -0.1826, -0.2103, +0.1367, +0.0738, -0.4706, -0.2797, +0.2463, +0.0844, +0.1632, +0.2067, +0.2860, -0.1431, -0.1538, -0.4689, +0.1815, -0.7608, -0.5361, +0.0924, -0.0427, +0.0261, +0.1086, +0.0071, -0.0351, +0.1962, -0.5212, -0.2708, -0.0387, -0.4651, -0.1066, +0.1502, -0.0507, -0.4060, +0.0178, +0.1007, -0.3050, -0.3290, -0.7691, -0.2058, +0.2255, -0.4308, +0.1231, +0.2162, +0.3136, +0.1682, +0.0186, -0.2181, +0.1038, -0.7105, +0.0725, +0.1498],
-[ +0.2957, +0.3931, +0.5196, +0.0034, -0.1459, -0.4853, +0.0045, +0.3441, -0.6762, +0.3599, -0.2657, -0.0656, +0.2883, +0.2954, -0.3889, +0.5849, +0.0604, +0.2256, -0.7857, +0.0923, +0.1446, -0.4545, -0.0598, -0.0619, +0.0932, -0.0672, +0.1070, +0.2962, +0.1364, -0.0010, +0.0422, +0.1428, -0.0486, -0.6373, -0.1726, +0.1041, +0.0355, +0.1551, -0.8913, -0.6888, -0.1694, -0.7115, +0.2172, -0.7797, +0.2613, -0.6847, -0.3206, -0.0662, -0.1301, -0.2691, -0.3250, -0.5412, +0.3733, -0.6999, -0.1384, +0.2234, -0.6276, -0.6873, -0.1056, -0.2576, -0.3469, -0.0035, -0.3412, -0.4947, -0.2108, +0.2637, -0.4840, -0.7649, +0.0512, -0.5292, -0.1976, -0.3880, -0.1312, -0.2244, -0.5623, +0.1554, -0.0144, +0.1044, -0.3046, -0.0893, +0.0786, +0.1556, -2.0057, -0.2783, +0.2209, -0.6801, +0.1200, -0.0627, -0.1416, +0.0931, -0.1593, +0.6807, -0.0833, -0.3581, -0.1243, -0.2332, +0.0648, -0.2536, +0.0485, -0.3385, -0.3248, -0.2046, -0.0735, +0.1252, -0.0138, -0.2593, +0.3831, -0.2624, -0.0680, +0.1553, -0.6539, -0.3949, -0.2072, -0.3056, +0.0470, -0.2456, -0.2607, -0.1460, +0.1578, -0.4485, -0.1730, +0.0905, -0.5966, +0.1038, +0.4146, +0.0169, -0.2569, +0.0757],
-[ -0.0059, +0.2504, -1.8223, +0.0071, +0.0843, +0.0531, +0.0537, -0.4270, -0.0225, +0.0206, +0.1877, -0.0539, -0.1275, -0.1903, -0.2041, +0.1867, -0.2453, +0.0968, -0.7747, -0.0996, -0.1644, -0.2217, -0.0222, -0.0323, +0.1196, -0.4662, -0.0733, -0.2897, -0.0650, +0.1710, +0.3257, -0.6486, +0.1965, +0.4933, -0.1914, -0.7322, -0.7016, -0.2255, +0.0376, +0.2672, -0.5327, +0.2688, -0.0806, -0.2247, -0.1833, -0.4959, -0.7814, -0.6611, +0.1856, -0.1662, -0.0610, +0.4234, +0.1225, +0.0887, +0.1060, +0.1328, +0.1165, -0.3699, -0.3317, +0.1403, +0.1845, +0.0305, -0.2385, -0.0139, +0.2337, -0.0865, -0.4594, +0.0413, -0.3618, +0.1392, +0.0640, +0.3269, -0.4006, +0.6018, -0.1011, +0.1064, +0.0764, -0.7746, -0.2271, -0.8182, -0.1293, -0.5567, -0.3629, -0.6294, +0.1535, -0.5792, +0.0733, -0.1860, +0.3598, -0.0287, +0.3026, -0.4029, +0.0910, +0.3008, +0.3386, +0.0652, +0.1527, +0.2761, +0.2965, -0.4328, -0.1331, -0.0883, +0.1920, -0.2682, +0.2188, -0.3514, -0.2600, -0.0027, -0.9167, -0.3502, +0.6296, +0.1959, +0.0535, +0.2855, +0.1944, +0.6012, -0.8331, +0.3115, +0.3111, +0.0916, -0.1444, -0.0131, -0.2425, +0.2020, -0.2527, +0.2171, +0.0902, +0.2377],
-[ +0.1734, -0.3360, +0.0102, -0.1136, +0.0421, +0.0059, +0.0081, -0.1179, -0.2811, -0.3038, -0.0654, -0.0284, +0.1823, -0.5043, -0.0641, +0.3135, +0.2485, -0.1943, -0.7957, -0.4855, +0.3363, -0.3024, +0.0201, -0.0095, -0.2435, -0.3528, +0.1311, -0.1494, -0.2564, +0.0214, +0.0812, -0.0815, -0.3220, +0.0243, +0.1589, +0.2596, +0.0788, -0.1100, -0.0409, -0.0636, +0.0915, -0.0302, -0.1303, +0.2093, -0.7333, -0.4362, -0.0231, +0.1416, -0.0775, -0.6113, +0.1495, +0.1520, +0.1515, -0.2184, +0.2908, -0.4809, +0.1760, -0.5343, +0.0255, +0.3853, -0.6806, -0.0456, -0.0844, -0.2962, -0.2281, +0.2654, -1.0656, +0.0755, -0.1765, +0.1391, +0.1288, +0.2546, -0.0349, +0.0460, +0.0746, -0.3408, -0.1496, -0.7456, -0.2263, -0.1545, -0.3210, -0.1699, -0.0215, -0.0136, +0.3570, +0.2186, +0.0431, -0.2374, -0.1237, -0.0502, +0.3524, -0.3504, -0.8003, -0.1479, -0.1306, -0.1243, -0.0349, +0.0689, -0.1313, -0.1078, -0.0253, -0.0653, -0.0671, -0.4589, +0.1150, -0.2785, -0.4662, -0.0127, -0.2129, +0.2506, -0.3115, +0.3973, -0.0523, +0.1712, -0.0820, +0.0759, -0.0481, -0.0596, +0.1819, -0.3091, +0.1873, +0.2186, -0.5450, +0.0715, +0.1790, -0.2883, +0.0226, +0.1730],
-[ -0.2602, -0.3215, -0.0906, +0.1177, -0.1313, -0.5380, -0.4104, -0.4251, -0.0429, +0.1910, +0.2934, -0.0522, -0.0154, +0.0940, -0.7726, -0.0532, -0.1507, -0.4646, +0.0155, -0.1635, +0.4168, +0.3530, -0.0973, -0.0352, -0.1655, -0.2412, +0.1004, +0.3036, -0.0438, -0.6966, -0.3239, -0.8388, +0.0405, -0.0482, -0.4399, +0.5633, -0.0991, +0.0878, -0.4014, -0.3725, -0.1872, +0.1927, -0.0272, +0.2497, -0.3443, +0.0991, -0.2369, +0.2886, +0.0404, -0.3542, -0.3079, -0.3784, -0.1192, -0.5404, +0.1479, +0.1591, +0.2231, +0.2725, -0.1559, +0.2966, +0.0741, +0.0748, +0.3326, -0.7224, -0.0826, -0.0814, +0.0424, -0.4582, +0.3849, -0.0785, -0.1042, +0.1102, -0.2348, -0.0806, -0.0245, -0.1454, +0.3831, -0.0851, -0.6094, -0.4785, -0.1979, -0.2312, -0.3423, -0.1665, +0.3068, -0.6060, +0.1745, -1.2672, -0.3371, +0.0945, -0.0562, -0.6999, -0.2454, -0.1074, +0.2825, -0.3700, +0.3908, -0.1738, +0.0191, -0.5917, -0.0799, -0.4251, -0.9711, +0.0096, -0.7487, -0.1138, +0.2945, -0.4373, +0.1421, -0.1377, +0.2897, -0.0829, +0.2462, +0.1447, +0.0142, -1.0093, -1.0673, -0.6900, -0.2250, +0.1916, -0.8061, -0.3221, +0.1838, +0.0782, +0.0042, +0.0976, +0.4808, -0.2449],
-[ -0.0186, +0.0312, -1.1666, +0.4912, +0.0535, -0.0724, +0.4590, +0.5356, -0.2967, +0.0945, +0.3760, +0.1753, +0.5287, -0.3805, -0.8444, -0.1378, -0.2789, -0.0429, +0.5450, -0.0904, +0.0773, -0.4917, -0.7371, +0.0729, +0.1716, +0.0492, +0.2712, -0.4112, +0.4279, -0.2601, +0.1060, -0.1974, -0.0752, -0.0291, +0.0424, -0.3498, +0.3540, +0.4572, -0.0620, -0.1689, -0.7175, -0.0296, +0.0981, -0.0719, +0.1335, -0.0579, -0.7234, +0.5031, +0.0332, +0.2731, -0.3885, -1.1700, +0.2232, +0.1357, -0.1256, -0.3946, +0.1373, +0.2081, +0.0855, -0.5177, -0.0246, +0.2997, -0.5857, -0.3490, +0.1922, -0.6260, -0.2010, -0.0540, -0.5983, -0.1169, -0.0199, +0.2142, -0.0344, -0.0711, +0.2242, +0.0118, +0.1590, +0.1529, +0.1587, -0.7301, +0.1030, -0.2880, +0.2163, -0.2043, -0.0016, -0.0082, +0.1785, -0.6902, -0.1381, -0.1248, +0.3989, -0.1963, +0.4378, -0.0211, +0.2309, -0.5025, +0.1148, +0.0732, +0.0534, +0.0736, -0.3570, +0.1016, +0.0007, -0.0154, -0.2812, +0.4252, +0.0808, +0.3596, +0.2169, -0.2200, -0.8553, -0.7431, -0.0798, -0.5308, +0.0099, +0.1634, +0.1090, +0.0750, +0.0094, -0.3583, -0.2442, -0.0193, +0.1221, +0.2039, -0.4970, -0.4103, -0.2623, +0.1852],
-[ +0.0035, -0.2371, -0.0652, -0.5765, +0.2370, +0.1303, -0.1977, -0.6236, +0.1144, -0.1280, +0.0588, -0.0054, -0.1472, -0.2433, -1.1024, +0.2071, -0.1101, +0.7363, -0.0024, +0.2096, +0.0864, -0.2140, +0.1191, -0.1789, +0.2744, -0.5595, -0.4182, +0.0468, -0.2223, +0.1140, -0.0006, -0.4948, -0.2110, +0.2943, -0.0723, -0.0925, -0.4041, +0.2033, -0.5595, +0.0529, +0.1126, -0.8388, -0.2227, -0.0921, -0.2104, -0.0412, +0.1017, +0.0853, +0.2641, +0.0581, +0.2180, -1.8387, +0.3215, +0.2269, -0.1205, -0.0315, +0.0466, -0.4390, -0.9485, -0.9049, +0.1571, -0.1657, -0.1598, -0.6076, +0.3959, -0.1420, +0.0664, -0.0393, +0.2893, -0.4381, +0.0649, -0.0343, +0.1189, -0.3135, +0.0619, +0.0534, -0.0150, -0.0847, -0.3386, -0.4189, -0.2144, -0.5014, -0.4263, -0.3158, -1.1655, +0.4229, +0.1088, -0.0160, +0.0623, -0.1086, +0.0452, -0.1172, +0.0235, -0.4329, +0.0315, -0.2861, -1.8719, +0.1323, -0.1785, +0.0296, +0.0625, +0.1258, -0.2638, -0.2692, +0.2976, +0.0126, -0.5463, -0.4668, -0.1375, +0.0925, -0.1242, -0.8335, +0.1498, -0.4909, +0.0150, +0.1882, -0.3309, +0.3453, -0.0746, +0.1613, -0.0352, +0.4158, -0.6152, -0.1984, +0.3839, -0.3962, -0.0498, -0.8401],
-[ -0.2221, +0.4577, -0.3264, +0.0867, +0.2288, -0.6050, +0.0765, -0.0253, +0.0234, -0.1089, +0.2742, +0.0977, -0.2987, +0.3709, -0.6876, -0.0137, +0.2326, +0.1873, -0.0458, +0.4263, -0.1981, -0.1495, -0.2254, +0.1243, +0.2372, +0.0684, +0.0282, +0.0340, +0.2636, -0.1085, +0.1307, +0.0005, +0.2727, -0.3159, -0.0499, -0.5526, -0.4607, -0.1653, -0.1389, -0.2559, -0.3343, -0.1751, +0.0961, -0.1130, -0.3663, +0.1649, -0.0549, +0.1994, +0.3338, +0.2785, +0.3672, +0.1056, +0.3413, +0.2041, +0.2421, -0.4176, +0.0595, -0.7157, -0.8599, -0.2813, -0.5280, -0.2340, -0.3723, +0.3193, -0.0203, -0.7509, -0.4940, -0.0868, -0.0221, +0.0788, -0.0377, +0.1623, +0.0788, -0.0519, -0.2508, -0.3549, +0.2371, -0.4721, +0.5425, +0.5633, +0.0457, -0.0053, -0.4628, -0.2514, -0.1613, -0.2032, +0.0440, +0.3368, +0.0844, -0.1580, -0.7842, +0.1071, +0.0913, +0.2130, -0.3305, +0.1332, +0.1810, -0.1177, +0.2646, -0.4359, -0.3863, -0.0371, +0.2614, -0.1002, +0.1836, -0.2881, +0.4521, -0.1639, -0.0507, +0.1292, -0.2386, -0.2004, -0.0219, -0.9069, +0.2525, -0.0051, +0.5764, +0.1496, +0.2575, -0.1619, +0.1981, -0.0817, -0.0992, +0.1743, -0.1275, -0.2257, -0.0344, +0.1149],
-[ +0.0552, -0.1676, +0.0500, +0.0371, +0.2764, -0.2129, -0.2672, +0.3881, +0.3348, +0.1618, -0.0235, -0.2225, +0.0011, +0.3560, +0.2559, -0.2586, -0.0630, -0.0616, +0.2104, +0.1421, +0.0131, -0.5461, -0.1410, -0.2444, -0.3954, +0.2889, -0.1876, +0.5588, -0.2274, +0.0884, -0.4838, +0.0815, -0.4368, -0.0366, -0.0305, -0.2435, +0.1682, -0.1123, -0.6352, -0.1180, -0.1304, -0.3762, -0.1200, -0.0787, +0.1968, +0.0229, +0.6007, +0.3058, +0.0111, +0.0071, -0.3882, -0.4516, +0.0657, -0.4349, -0.0312, -0.3833, +0.3771, +0.5473, -1.1309, -0.2844, -0.2990, -0.3114, -0.2003, +0.1692, -0.5216, -0.2573, +0.2162, +0.4196, +0.0645, +0.1814, -0.1180, -0.1903, +0.1395, +0.3146, -0.0503, -0.0129, +0.1173, -0.1289, -0.7010, +0.1966, -0.1170, +0.1836, -0.5466, +0.2949, +0.1268, +0.2523, +0.1339, +0.2687, -0.1148, -0.9586, -0.3372, +0.0221, -0.3042, +0.1392, -0.1978, -0.4729, +0.0023, -0.0018, -0.3816, -0.2387, +0.0710, +0.0402, +0.3025, -0.0422, +0.2517, -0.1266, +0.2964, -0.0651, -0.1329, +0.0103, +0.4835, -0.1226, +0.0643, -0.1345, +0.0647, -0.3269, -0.4923, +0.2875, +0.1877, -0.1526, -0.0785, -0.0118, -0.0353, -0.6584, +0.3742, -0.1663, +0.2500, +0.0618],
-[ +0.2997, +0.2519, -0.4286, -0.7198, -0.2245, -0.1805, -0.4405, -0.4680, -0.1060, -0.3217, +0.1738, -0.2077, +0.1985, -0.3943, -0.3274, -0.5616, -0.5938, +0.0370, -0.0538, +0.2143, -0.3124, -0.3561, +0.3302, -0.2428, -0.1921, +0.0271, -0.0047, -0.2883, +0.0238, -0.2252, -0.2254, +0.1708, -0.2050, +0.2460, +0.0141, +0.0999, -0.1220, -0.1217, -0.1450, -0.0053, -0.4942, -0.4115, +0.1852, -0.1231, +0.1924, -0.3888, -0.2041, -0.4723, -0.4349, +0.0732, -0.6097, -0.3690, +0.1171, +0.1377, -0.3710, +0.4654, -0.1571, -0.8847, +0.0086, -0.0884, +0.3293, -0.5117, +0.0098, +0.2000, -0.2808, +0.0643, +0.1971, -0.0608, -0.4650, -0.3024, +0.1653, -0.0648, +0.2489, -0.1785, -0.1707, +0.3948, -0.3938, -0.6172, -0.2203, -0.7173, +0.0293, -0.3072, -0.0620, -0.2389, -0.0896, +0.1239, +0.2999, -0.0323, -0.5117, -0.0260, -0.3110, -0.1003, -0.5293, -0.0664, +0.2057, +0.1447, -0.3164, -0.0746, -0.6058, +0.1389, +0.1527, -0.2403, -0.0355, -0.1622, -0.0819, +0.2913, +0.2429, -0.0298, +0.0585, -0.0653, +0.1618, -0.0336, -0.6792, +0.3777, +0.0029, -0.2496, +0.3963, -0.0700, +0.4383, -0.4798, +0.2028, +0.1346, -0.6482, -0.1837, +0.0233, -0.0848, +0.0192, +0.2274],
-[ -0.7703, +0.3597, +0.2273, -0.0120, -0.6104, -0.3715, -1.1547, -0.8693, -0.0804, -0.3563, -0.2710, +0.1459, +0.0653, +0.0391, -1.0880, +0.1807, +0.3675, -0.1739, -0.1623, +0.1400, -0.1035, +0.1792, +0.6849, -0.7708, -0.4373, +0.1885, -0.2048, +0.0541, +0.1565, -0.4325, -0.5115, -0.0447, +0.3524, +0.1776, +0.2972, -0.0688, -0.4532, -0.0173, -0.0426, -0.1938, +0.1425, -0.4570, +0.0673, -0.0495, -0.3246, +0.2467, +0.3304, -0.1078, +0.3719, -0.0125, -0.0105, -0.1284, +0.3591, -0.3257, +0.2117, -0.3518, +0.2448, -0.5693, +0.4628, -0.4708, -0.0589, +0.2012, +0.1599, -0.3289, -0.1241, -0.8050, -1.0541, +0.2217, +0.0578, -0.0257, +0.4239, -0.3047, -0.4532, +0.5791, -0.0018, -0.1231, -0.1040, -0.2046, -0.0637, -0.1778, -0.1759, +0.3343, -0.4349, -0.6581, -0.0120, -0.3806, -0.6405, -0.1362, +0.1076, -0.9756, -1.0895, -0.5013, +0.1329, -1.0341, -0.1451, -0.0347, -0.0139, -0.2391, -0.3683, +0.0724, +0.3231, -0.7633, -0.1369, +0.0740, -0.0623, -0.0497, -0.1996, +0.0780, +0.2873, -0.2659, -0.3895, -0.6219, +0.2696, +0.4523, -0.3043, -0.2205, +0.2472, -1.0548, -0.3012, -0.6168, -0.6512, -0.2143, -0.5998, -0.2672, +0.1359, -0.0752, +0.0370, +0.0627],
-[ -0.1791, -0.2279, -0.0998, +0.1783, +0.1553, +0.0612, -0.2220, +0.1551, -0.2240, -0.0159, +0.0010, -0.0103, +0.1007, -0.3934, -0.5397, -0.2077, +0.0963, -0.1834, -0.2112, -0.0267, -0.3809, -0.2319, +0.2167, +0.0076, +0.0075, -0.0750, +0.0607, +0.1455, +0.0941, -0.0205, -0.2981, -0.0061, +0.4115, -0.4933, +0.2443, -0.9828, -0.3445, -0.2593, -0.3871, +0.0736, -0.8643, -0.0187, +0.1316, -0.2119, +0.3713, +0.0419, -0.5368, +0.1741, -0.1143, +0.0186, -0.2846, -0.4499, -0.2979, -0.0987, -0.1089, -0.1469, +0.1726, -0.4902, +0.3746, -0.1956, -0.6684, -0.1877, -0.4473, +0.3690, +0.1347, -0.1845, -1.4047, -0.1341, -0.0740, -0.0375, -0.1693, -0.3976, -0.6494, -0.0323, -0.2126, +0.3526, -0.2334, -0.3229, +0.4134, +0.0701, +0.2353, +0.4844, +0.0562, +0.3268, -0.1159, -0.1046, -0.0269, -0.0188, -0.1613, -0.2217, -0.2000, -0.0957, -0.2712, +0.3059, +0.1249, -0.1035, +0.0004, +0.3311, +0.1874, +0.3168, +0.0562, +0.1328, +0.1546, -0.1332, -0.0177, +0.2608, -0.1027, -0.4310, -0.5956, +0.0371, +0.0779, -0.1145, +0.0611, +0.1766, +0.2322, +0.3979, -0.1862, +0.3387, -0.6133, +0.0790, +0.0620, -0.1411, -0.0586, -0.0211, -0.1644, -0.4890, -0.0665, +0.2908],
-[ -0.1590, +0.3465, -0.7111, +0.0057, +0.2907, -0.4929, +0.1248, -0.0589, -0.0498, -0.3394, +0.3763, +0.2212, -0.0642, +0.4740, -0.3273, -0.3461, +0.1982, -0.4864, +0.3201, +0.1274, +0.2486, +0.0471, -0.0542, +0.2365, +0.4782, -0.9680, -0.0935, -0.0158, -0.1450, -0.3454, -0.2127, -0.2524, +0.1208, -0.0273, +0.3810, -0.0663, +0.0663, -0.2722, -0.6524, -0.3031, +0.1824, -0.5041, +0.0428, +0.3808, -0.4099, +0.1713, -0.2006, +0.3985, -0.1635, -0.0436, -0.8630, +0.0073, -0.0152, +0.2548, +0.3976, +0.2089, -0.0484, +0.0710, +0.0378, -0.0727, -0.3489, -0.2270, +0.2633, +0.0113, +0.3312, +0.0097, -0.5475, +0.1103, +0.0917, -0.2627, -0.5849, +0.1446, -0.8225, -0.3470, -0.0024, -0.2059, -0.4963, +0.0666, -1.5108, -0.2249, +0.1441, -0.2078, -0.2021, -0.2921, -0.3632, +0.0481, +0.0159, -0.3559, -0.3166, +0.2004, -0.4084, -0.3994, +0.1976, +0.0868, +0.1715, +0.0243, -0.0022, +0.3939, +0.0631, -0.5910, -0.0901, +0.0470, -0.1276, +0.0298, +0.0838, +0.2862, -0.7131, -0.1051, -0.4813, +0.1589, -0.1359, +0.1241, -0.0412, +0.1048, +0.1344, -0.3297, -0.0250, +0.1921, +0.0646, +0.1873, -0.3154, +0.1462, -0.1932, +0.4339, -0.4673, +0.1966, -0.2193, +0.1271],
-[ -0.4045, -0.4693, -0.2753, -0.0697, -0.7086, -0.1363, +0.0742, +0.5169, -0.9451, +0.0164, +0.7178, +0.4367, -0.5113, -0.0481, -0.3382, +0.3882, -0.6975, +0.3492, +0.6143, +0.2262, -0.3421, -0.1838, +0.5108, +0.2796, +0.3800, +0.0532, -0.4792, -0.4716, +0.0690, -0.0716, +0.2828, -0.7554, +0.1276, -0.2303, +0.0311, -0.2633, +0.0998, +0.2469, +0.1871, +0.6439, -0.4219, -0.2035, -0.4298, +0.0361, +0.1351, +0.2658, -0.2374, -0.1598, -0.5585, -0.0315, -0.9313, +0.2618, +0.2350, -0.0825, +0.0885, +0.1367, +0.3425, +0.0241, -0.4690, -0.1568, -0.2416, -0.2253, -0.0125, -0.1595, +0.0867, +0.4414, -0.8874, +0.0626, -0.3080, +0.5134, +0.4091, -0.2617, -0.1513, -0.1776, +0.0203, +0.2636, +0.0000, -0.4166, -0.0429, +0.2566, -0.3680, -0.1859, -0.6129, +0.4622, -0.1716, -0.0095, -0.1997, +0.3254, +0.4619, -0.4222, +0.0490, +0.2444, -0.0382, -0.0066, +0.0251, -0.7795, +0.6492, -0.4009, +0.0306, -0.6512, +0.0904, -0.5018, +0.2744, +0.6262, -0.0631, -0.7705, -0.3628, -0.0445, +0.1403, -0.3503, +0.3548, -0.4655, +0.6479, -0.2118, +0.2087, -0.8546, +0.7755, -0.2266, +0.2387, -0.6748, +0.1535, -0.3294, +0.3806, +0.1586, -0.1722, -0.2350, +0.1667, +0.3890],
-[ +0.2363, +0.0062, -0.4151, -0.2195, -0.1890, +0.1727, -0.1118, -0.2844, +0.1809, -0.2691, -0.1235, -0.1263, +0.3011, -0.5891, +0.4425, -0.1007, -0.1312, -0.2862, +0.1523, +0.0050, -0.0170, -0.3431, -0.2285, +0.0159, +0.1520, -0.6582, +0.1684, -0.4045, -0.2205, +0.1423, +0.0978, -0.0692, -0.6432, +0.2055, -0.0115, +0.0345, +0.0718, -0.1850, -0.3148, -0.0285, +0.4103, +0.3684, +0.0221, -0.9018, -0.4790, -0.2507, -0.0904, +0.3063, +0.1512, -0.0405, -0.5723, -0.7270, -0.0956, +0.1412, -0.0119, -0.3245, +0.2918, -0.4344, +0.1103, +0.2323, -0.3513, +0.3947, +0.3163, -0.3286, +0.0400, -0.4976, -0.0799, +0.1862, -0.4608, -0.4698, -0.3919, -0.1890, +0.3467, -0.4846, +0.1217, -0.4737, -0.0228, -0.0274, -0.7486, -0.7364, +0.0778, +0.1966, -0.0731, -0.7374, -0.3736, -0.5404, -0.0662, -0.2419, +0.1435, +0.1261, -0.8224, -0.2903, +0.1371, +0.0677, +0.1414, -0.7651, -0.2402, -0.2509, +0.3953, -1.0583, -0.4834, +0.1641, -0.4187, -0.3944, -0.3237, -0.2496, -0.3212, -0.0233, -0.0451, +0.0084, +0.0396, -0.5585, +0.0647, -0.7654, +0.0435, +0.2010, -0.7568, -0.0416, -0.7364, -0.1277, -0.3532, +0.1159, +0.1172, -0.0711, +0.1222, +0.1614, +0.2695, -0.1347],
-[ +0.2645, +0.1945, -0.1109, -0.0107, +0.4603, -0.0164, -0.6991, +0.0160, -0.2493, -0.0361, +0.0486, +0.1446, +0.1816, -0.3309, -0.5692, +0.3186, +0.0398, +0.1935, +0.0052, +0.1339, -0.6104, -0.0547, -0.0493, +0.1449, -0.0981, -0.4863, -0.0619, -0.0866, -0.2730, -0.0892, -0.5666, +0.0349, -0.1451, -0.0458, +0.0709, -0.0688, -0.3157, -0.1346, +0.0223, +0.1968, -0.3147, -0.2957, +0.0356, -0.4077, -0.0574, +0.1900, -0.2019, -0.4952, -0.4156, -0.2254, +0.3388, -0.1667, -0.0230, +0.0165, -0.1358, -0.0144, +0.0272, -0.2540, -0.0612, -0.0324, -0.0505, +0.1923, -0.3608, +0.3274, -0.5640, +0.2636, +0.2367, -0.1310, +0.0460, +0.0487, +0.0208, -0.3474, +0.1411, +0.2065, +0.6770, -0.1130, -0.0721, -0.6301, -0.0159, -0.0925, +0.1345, +0.1874, -0.4512, -0.2718, +0.0344, -0.2044, +0.1453, -0.0164, -0.1500, +0.3967, +0.0505, -0.0252, +0.2409, -0.4191, +0.0563, +0.0028, +0.1797, -0.6223, +0.3218, -0.3501, -0.1397, -0.3705, -0.0733, +0.2525, +0.1673, +0.2652, +0.3524, +0.2129, +0.0589, +0.0883, +0.4070, +0.3489, +0.0569, -0.1190, +0.4708, -0.2421, +0.2813, +0.1846, +0.2897, -0.2035, +0.2092, +0.1079, +0.3770, -0.0807, -0.2196, +0.1587, +0.0665, +0.1521],
-[ -0.0032, -0.5900, +0.3245, +0.2203, -0.4119, +0.0732, -0.1448, -0.2840, -0.5423, +0.4369, +0.1149, -0.1663, -0.0846, -0.4860, -0.7153, +0.2717, +0.3148, +0.0577, +0.0600, +0.1907, +0.0226, -0.8129, -0.0191, -0.1380, -0.3814, -0.2589, +0.1204, -0.1775, -0.4343, -0.3241, -0.4191, +0.2309, -0.1817, +0.1551, +0.1934, -0.6179, -0.3449, -0.3706, -0.1836, -0.0723, +0.1246, -0.1750, +0.0323, +0.0048, +0.1908, -0.0128, -0.2133, +0.2548, +0.2636, +0.2050, -0.5303, +0.2526, +0.0808, -0.5870, -0.2439, +0.2156, -0.4137, -0.7845, -0.0266, -0.1659, -0.0701, -0.0901, +0.4030, -0.2117, -0.3111, +0.2580, -0.3229, +0.2362, +0.5040, -0.0254, +0.1128, +0.0537, +0.0629, +0.0724, -0.0315, +0.3396, +0.0600, +0.2878, +0.1927, +0.0392, -0.4752, -0.1950, -0.1491, -0.4002, +0.2534, +0.0002, -0.0474, +0.3546, +0.3228, +0.4452, -0.0011, +0.0549, -0.0518, +0.2764, +0.2517, +0.2436, -0.4300, +0.2737, +0.3223, +0.0856, +0.1481, -1.0614, -0.0964, -0.6597, -0.1409, -0.1445, -0.1676, -0.5498, +0.7005, +0.3196, +0.2127, -0.0677, -0.2303, -0.2276, -0.1833, -0.2009, -0.0879, -0.1477, +0.2008, -0.1563, +0.0598, -0.0930, +0.1721, -0.2699, -0.2913, +0.0134, -0.2100, -0.2508],
-[ +0.0078, -0.1145, +0.0566, +0.2845, +0.3333, +0.0245, +0.5178, -0.2139, -0.5225, +0.1092, +0.3087, -0.2633, -0.4887, +0.5600, -0.3808, -0.4829, +0.3219, +0.3766, +0.0972, +0.4930, -0.2441, -0.2812, -0.2231, -0.0461, -0.6873, -0.0303, -0.0595, +0.1965, +0.1405, +0.2027, +0.1398, -0.5602, -0.5044, +0.3049, -0.8612, -0.0465, +0.4593, -0.1495, +0.4121, +0.3910, +0.1221, -0.3441, -0.1128, -0.3937, -0.0790, -0.2019, -0.5485, +0.1180, +0.0659, -0.0949, -0.1865, +0.8964, +0.1803, +0.2051, -0.3293, -0.3495, -0.2919, +0.1497, -0.0474, -1.0231, +0.0527, -0.4692, -0.0999, +0.0488, -0.1689, +0.1371, -0.1849, +0.1495, -1.0595, +0.4409, -0.1860, +0.3221, -0.4063, +0.2084, +0.3131, -0.0811, -0.0254, +1.0520, +0.2568, -0.1223, -0.6538, -0.3910, +0.0634, -0.1927, +0.0842, -0.5116, +0.0424, +0.0742, +0.0284, -0.9449, -0.2828, -0.2224, +0.1159, -0.0119, -0.0894, -0.2882, -0.3089, +0.2021, -0.1726, -0.1260, -0.2500, -0.0621, -0.6379, +0.2073, +0.3437, +0.2344, +0.1052, +0.0429, -0.1970, +0.7690, -0.2105, -0.6152, +0.1540, -0.1216, -0.1457, -0.0201, -0.7810, -0.5367, -0.1856, -0.3119, -0.6950, -0.0800, +0.1553, +0.7838, -0.4806, -0.7120, -1.0775, +0.4206],
-[ -0.8158, -0.0751, +0.4568, +0.1936, -0.0115, +0.0016, +0.1775, -0.3664, +0.2353, -0.1059, -0.0433, -0.2364, -0.0069, -0.0294, -0.3629, +0.4730, -0.3616, +0.2660, +0.4088, -0.0482, +0.2876, -0.0399, +0.1708, +0.3116, +0.0624, +0.1124, +0.2188, -0.1548, +0.0379, +0.2865, +0.0004, -0.3470, -0.4660, -0.1543, -0.6684, +0.3219, +0.7255, +0.2310, -0.2165, +0.0654, -0.5981, -0.2871, -0.4359, -0.0235, -0.4874, -0.6068, -0.1394, +0.0140, +0.1378, +0.0300, -0.3226, -0.1644, +0.0784, -0.3535, +0.4106, +0.3939, +0.4227, -0.2622, -0.0644, -0.7142, -0.6646, -0.3376, -0.0979, -0.1231, -0.2758, -0.7267, -0.0163, -0.3791, +0.2953, -0.0657, +0.0056, -0.4484, -1.0532, +0.5263, -1.1149, -0.1071, -0.5389, -0.0615, -0.0329, +0.1728, -0.0696, -0.3026, -0.0906, -0.1880, +0.1664, -0.4204, +0.2661, -0.6305, -0.2993, -0.1241, -0.2866, -0.1463, +0.4917, +0.1292, -0.4802, +0.3295, -0.7186, -0.1402, -0.0365, +0.0668, +0.1496, -0.3388, -0.0329, -0.2554, +0.1411, -0.6357, -0.1040, +0.1403, +0.1908, -0.7587, -0.5095, +0.2143, +0.2150, +0.2288, +0.2723, -0.8710, +0.1903, +0.0446, -0.7277, -0.1252, -0.0186, +0.2522, -0.4735, -0.0302, -0.3595, -0.3273, +0.2083, +0.0594],
-[ -0.2945, +0.3638, +0.1284, -0.5290, -0.1601, +0.1974, +0.1350, -0.3181, +0.1355, -0.1144, -0.8185, +0.3295, +0.0454, -0.2519, +0.0312, -0.0144, +0.0092, +0.1483, +0.0112, +0.1281, +0.2530, +0.0103, -0.2943, +0.0510, +0.2044, +0.0298, +0.2082, -0.0052, +0.1255, +0.1062, -0.6600, -0.0876, +0.0886, -0.1130, -0.4472, -0.0706, -0.2610, -0.4739, -0.3537, +0.0546, -0.3391, -0.5774, -0.1172, +0.1768, +0.3232, +0.0907, -0.5683, -0.6098, +0.1459, +0.3442, -0.3454, +0.0279, +0.1736, -0.1270, +0.1902, +0.0658, -0.0248, -0.2342, +0.1925, +0.1986, +0.1576, -0.6727, -0.3078, +0.1383, -0.2497, -0.1600, +0.2205, -0.3507, +0.1797, +0.5265, -0.3245, +0.0958, -0.1797, +0.0096, +0.3309, -0.2368, +0.0322, -0.2754, +0.1351, +0.5305, +0.1616, +0.5841, -0.7230, -0.3630, -0.0726, -0.5375, -0.2105, -0.1580, +0.1014, +0.1227, +0.0446, +0.0279, +0.5773, -0.5343, +0.2156, -0.0660, -0.3511, -0.0986, -0.2209, +0.1967, +0.0479, +0.4054, -0.4945, +0.2346, -0.4003, +0.1255, +0.0379, -0.3276, -0.3174, -0.1166, +0.1421, -0.3541, +0.0644, -0.2061, -0.0139, +0.1682, -0.2627, +0.0623, +0.3165, -0.2602, +0.3458, +0.2270, -0.4983, -0.1965, -0.1811, +0.1990, -0.0536, -0.3008],
-[ +0.2861, +0.2465, +0.5445, -0.6241, -0.3810, -0.2431, +0.0899, +0.0009, +0.0287, -0.2860, +0.4379, +0.1100, -0.0060, -0.0688, +0.3326, +0.4050, -0.0543, -0.3589, -0.4444, -0.1794, +0.0463, -0.4859, +0.5408, +0.1241, -0.1452, +0.1877, +0.3102, -0.5119, -0.4563, +0.2339, +0.0762, -0.0091, -0.2146, +0.0441, -0.8371, +0.1044, +0.3922, +0.0952, +0.2457, -0.1154, +0.2800, +0.0238, -0.1393, +0.1442, -0.6630, +0.3521, -0.2741, -0.0738, -0.0247, -0.0797, -0.2095, +0.5173, -1.1573, +0.4417, +0.2038, -0.2982, -0.2218, -0.0335, -0.0754, +0.0173, -0.1934, -0.7999, -0.7296, -0.1534, +0.0536, -0.5079, +0.3942, +0.1031, +0.0451, +0.3108, +0.0228, -0.5315, -0.5942, +0.1103, -0.1635, -0.0243, -0.3393, -0.2886, +0.1906, +0.0561, -0.1120, -0.2488, -0.2236, -0.3785, -0.0452, +0.2679, +0.2678, +0.4436, -0.8340, +0.0203, +0.6116, -0.3027, +0.1799, -0.2438, +0.1136, -0.2686, -0.0847, +0.0744, +0.0928, +0.2443, +0.0078, -0.0683, -0.4921, -0.0881, -0.1307, +0.3243, -0.4150, +0.0227, -0.5241, -0.5408, +0.2310, +0.2375, -0.0665, +0.2242, -0.2104, +0.2351, -0.1965, -0.3067, +0.0265, -0.1175, -0.3326, -0.3971, -0.4137, -0.0187, -0.4536, -0.0317, -0.2076, +0.1488],
-[ +0.3728, -0.0547, +0.3402, +0.0846, -0.2939, -0.4488, -0.3421, +0.3539, +0.2334, -0.1906, +0.2732, +0.2161, -0.4480, +0.1510, -0.4346, -0.0497, +0.2783, -0.1186, +0.0806, -0.0484, +0.1960, +0.2053, -0.0394, +0.0148, -0.0442, +0.1445, -0.2074, +0.2616, -0.0416, +0.2471, -0.3292, +0.2827, +0.1714, -0.0269, -0.1959, -0.3425, +0.3473, -0.2343, -0.3136, +0.2331, -0.0308, +0.1485, +0.4697, -0.1206, +0.3913, -0.1763, -0.3010, -0.2376, +0.5187, +0.1515, -0.2541, -0.0851, -0.5678, +0.1875, -0.0576, +0.2598, -0.0535, +0.0647, -0.2367, -0.5131, -0.6636, +0.0245, +0.1720, -0.1660, +0.0015, -0.5347, +0.0851, -0.1086, -0.0278, +0.3490, -0.3233, -0.1908, +0.2611, +0.2172, -0.0438, +0.1540, +0.0241, +0.3071, -0.2689, +0.0820, +0.3680, -0.1333, -0.4390, -0.0022, -0.1614, -0.2464, -0.5837, -0.1894, +0.0748, +0.2046, -0.1179, -0.3081, -0.2560, +0.0728, -0.0119, +0.1377, -0.2225, -0.1516, -0.0038, +0.0417, +0.3232, -0.1597, +0.0374, -0.2734, -0.0756, +0.2224, -0.1316, -0.1672, +0.1052, +0.1462, +0.3924, -0.1192, -0.2089, -0.0764, -0.0825, -0.1494, -0.2589, +0.1217, -0.2977, -0.2204, -0.2216, -0.3703, -0.3574, -0.1172, -0.2267, +0.2539, -0.0252, +0.0847],
-[ +0.1868, -0.6792, -0.0882, -0.4607, -0.0270, +0.1324, +0.2618, -0.6255, -0.0388, +0.3012, +0.1471, -0.1281, -0.3204, -0.1431, -0.3314, -0.0240, -0.1630, -0.2548, +0.1775, -0.1358, -0.2844, +0.0252, -0.4802, -0.0492, -0.2956, +0.0343, +0.2928, +0.2291, -0.0586, +0.1699, +0.2495, -0.0260, +0.1860, -0.0989, +0.0219, +0.0784, -0.1875, +0.2573, -0.1494, -0.0104, +0.1539, +0.3493, -0.1276, +0.2420, +0.2307, -0.1657, -0.3181, +0.0017, -0.2638, +0.1521, +0.2645, -0.9728, -0.0588, -0.3231, +0.2092, -0.3449, +0.4395, +0.2772, +0.0681, -0.0655, +0.0825, +0.0245, +0.6292, +0.1525, -0.3409, -0.0468, -0.3370, +0.1332, -0.0825, +0.1383, +0.0434, +0.3655, +0.1437, -0.2284, -0.1684, -0.0226, +0.4623, +0.1211, -0.1569, +0.0185, +0.3112, +0.1661, +0.0546, +0.2685, +0.1671, +0.0382, +0.1157, +0.2854, +0.2848, +0.0935, +0.3446, -0.3609, -0.2390, +0.1744, -0.7724, +0.0076, -0.3620, +0.4923, -0.0388, -0.1553, +0.2411, -0.0320, +0.4227, +0.2251, -0.2288, -0.6397, -0.1282, +0.4254, +0.0105, +0.2636, -0.0833, -0.0003, +0.1051, -0.0291, -0.3264, -0.0814, +0.1735, -0.0074, -0.4138, -0.0254, -0.0859, +0.0787, -0.1913, +0.1291, +0.1845, -0.0069, +0.0697, +0.1905],
-[ +0.2668, +0.0176, -0.6247, +0.0919, -0.4115, -0.2334, +0.0598, +0.1609, +0.5839, +0.1131, +0.2215, -0.2243, +0.1482, -0.3540, -0.9145, +0.0116, -0.0904, -0.3873, -0.0561, -0.1550, -0.2506, +0.1287, -0.0165, -0.3660, -0.1245, -0.5657, -0.2736, -0.4638, +0.3541, -0.0719, +0.2303, -0.2123, +0.1793, +0.1374, +0.4679, -0.3017, -0.2900, -0.0085, -0.0199, -0.0094, -0.0539, -0.4537, -0.1137, +0.1031, -0.2512, -0.5477, -0.3711, +0.0679, -0.0909, -0.4900, -0.0460, +0.1870, +0.5657, +0.0770, -0.1924, +0.5013, +0.1926, +0.4636, -0.2005, -0.6079, -0.0038, -0.3662, -0.1998, +0.2434, -0.1351, -0.1438, +0.4540, +0.3861, -0.5414, +0.1765, +0.5507, +0.0502, -0.2789, +0.0302, -0.4437, +0.1469, +0.0083, -0.0509, +0.0401, +0.0566, -0.3248, -0.1318, -1.5129, -0.6188, -0.1140, -1.1974, +0.2079, -0.1738, +0.2441, -0.8853, +0.0682, +0.0367, +0.2440, -0.6512, +0.0619, +0.2182, +0.1542, +0.2227, -0.4152, +0.4476, -0.4592, +0.6061, -0.5287, +0.5690, -0.5691, +0.0677, -0.2069, +0.0190, -0.1155, +0.5428, +0.4470, +0.0292, +0.3965, +0.0130, +0.4818, -0.6723, -0.6049, +0.1751, -0.0091, -0.0193, -0.4040, +0.1776, -0.0811, +0.5117, +0.1059, +0.2048, +0.3580, +0.0120],
-[ -0.1210, +0.0283, -0.2150, -0.8675, -0.1966, -0.1280, -0.3534, +0.1179, -0.5637, -0.0615, -0.2321, +0.0095, +0.1918, +0.0317, -0.2031, -0.1552, +0.3155, +0.4319, +0.2815, -0.0709, -0.6060, -0.0318, -0.6541, -0.3911, +0.0916, +0.1339, +0.3901, -0.0215, +0.3117, +0.3603, +0.3742, -0.2424, -0.2102, -0.0055, -0.1783, +0.2992, -0.0213, +0.2737, +0.3640, -0.0041, -0.0435, +0.1138, -0.0185, -0.0374, +0.0415, +0.4626, +0.3861, -0.2194, -0.6983, +0.1617, +0.1974, -0.0364, +0.4909, +0.1799, +0.2560, +0.0741, +0.0866, +0.0264, -0.4130, -0.0046, -0.5335, -0.0196, +0.3220, -0.0230, +0.2521, +0.1357, -0.2103, +0.1343, +0.1675, +0.0260, -0.1268, +0.2371, +0.0360, +0.2276, +0.1925, +0.2276, +0.0839, +0.1985, -0.0862, +0.1063, -0.1310, +0.1342, +0.1287, -0.1455, -0.3308, -0.1680, -0.5989, -0.5364, -0.0396, -0.4750, -0.0452, +0.2292, -0.0566, +0.3250, -0.0889, -0.1587, +0.0793, -0.2573, +0.3200, +0.4030, -0.0636, +0.4392, +0.1043, +0.0802, +0.0769, +0.4630, +0.1506, +0.0572, +0.0029, -0.3777, -1.6826, -0.0892, -0.7466, -0.1378, +0.3277, +0.1467, -0.0098, +0.0221, -0.1759, -0.7071, +0.0824, -0.0311, -0.2508, -0.0275, -0.7920, -0.3872, +0.1502, +0.2264],
-[ +0.6120, +0.3405, +0.2589, +0.0686, -0.1953, +0.6403, -0.1969, +0.0595, +0.1195, +0.2618, +0.1715, +0.0922, +0.1265, -0.1682, +0.0085, -0.0564, -0.2752, -0.2192, +0.0928, -0.1574, +0.1297, +0.1780, +0.2758, +0.0059, +0.2249, -0.2070, -0.2551, +0.0703, +0.0269, -0.2630, +0.0450, +0.2389, +0.2634, -0.2034, -0.4609, +0.4847, +0.5883, -0.3472, +0.2286, +0.0655, -0.6584, +0.3056, +0.2531, -0.0975, -0.1207, -0.1381, -0.5765, +0.4057, -0.2481, +0.1628, -0.0124, +0.1207, -0.4008, -0.1172, -0.2151, -0.0345, +0.0495, +0.0189, +0.3476, +0.0653, +0.0872, -0.1548, -0.0870, -0.5931, -0.1480, -0.0160, +0.3780, -0.0113, -0.1431, -0.2628, -0.0559, -0.4389, +0.2481, +0.0285, +0.2956, -0.2034, -0.1550, +0.0492, -0.0950, -0.1279, +0.0670, -0.2606, -0.0781, +0.1651, -0.6137, -0.2109, +0.0098, -0.4534, +0.0486, +0.1961, -0.4423, +0.1798, -0.1662, -0.1309, +0.2564, -0.3861, -0.0668, -0.2116, -0.3516, -0.0911, +0.1962, -0.6550, -0.3101, -0.1711, -0.3370, -0.2917, +0.2500, +0.2666, -0.0542, -0.4167, -0.3549, -0.0180, +0.2593, +0.0414, -0.1374, +0.3264, +0.0359, -0.4018, -0.1284, -0.0707, +0.3961, -0.3629, +0.5779, +0.3261, -0.1960, +0.0196, +0.1802, +0.1772],
-[ +0.3321, -0.0043, +0.0059, +0.1838, -0.0379, -0.6290, -0.2934, -0.0023, +0.4021, +0.1333, +0.3395, +0.3662, -0.5307, +0.4866, +0.1920, +0.1895, +0.1353, -0.0677, +0.0010, -0.1776, +0.0715, +0.1955, +0.1733, +0.0839, +0.1278, +0.0549, -0.1681, -0.0210, +0.0268, -0.2156, -0.0524, +0.0486, +0.1273, +0.0394, +0.4595, +0.1428, -0.4473, -0.1574, -0.5620, +0.0088, -0.1087, -0.3781, +0.0653, +0.0713, +0.0020, +0.1512, -0.0755, -0.1028, -0.0136, -0.0456, -0.3270, -0.0032, +0.2283, +0.2919, +0.3500, -0.5352, -0.1475, +0.2793, -0.7237, -0.3808, -1.2308, -0.2369, -0.1346, -0.1291, +0.4355, -0.2403, -0.3712, +0.0012, +0.2265, +0.4574, +0.0566, +0.5269, +0.3710, +0.5246, -0.0498, -0.3951, -0.4347, -0.3339, -0.4218, +0.0127, -0.0504, +0.2275, -0.2729, +0.2287, +0.0500, +0.2769, -0.1740, -0.3289, +0.0437, -0.1089, -0.1714, -0.3370, +0.1238, -0.2227, -0.2236, -0.0241, +0.0526, -0.1371, +0.0734, +0.1850, +0.1059, -0.1044, +0.1228, -0.1843, +0.1778, +0.1081, +0.2087, -0.7055, +0.0547, +0.0166, +0.0231, -0.1416, +0.3223, -0.1833, +0.1695, -0.2619, +0.1388, +0.2318, +0.0007, -0.1106, -0.0560, +0.1814, -0.1111, -0.2346, +0.2086, -0.1681, -0.4507, -0.2912],
-[ -0.0355, +0.2780, -0.0415, -0.6060, +0.1641, -0.1634, -0.1836, -0.2687, -0.2778, +0.3303, -0.5843, +0.2118, -0.0916, +0.1060, +0.0583, +0.0854, +0.2461, -0.2423, +0.4740, +0.3551, -0.3546, +0.0514, -0.1922, -0.8780, -0.1073, +0.0772, +0.1236, -0.2780, +0.1447, -0.6879, +0.0313, +0.2184, -0.2200, -0.0125, +0.0931, -0.1300, -0.1865, -0.4454, -0.8373, -0.0907, -0.3115, +0.0840, -0.2306, -0.1615, -0.3491, +0.2386, +0.1848, -0.5184, -0.1454, -0.2316, +0.2788, -0.0251, -0.0211, +0.0219, +0.1418, +0.0277, -0.2427, -1.2938, -0.1140, -0.2718, -0.6272, -0.0525, +0.1877, +0.2890, +0.3268, -0.0594, +0.1912, +0.4100, -0.2659, -0.0808, -0.8520, -0.7808, -0.2231, +0.4269, +0.1724, +0.3903, -0.4007, -0.3331, -0.1801, -0.3650, +0.0508, +0.4958, +0.2926, -0.2167, -0.2007, -0.0711, +0.2235, +0.0508, -0.0419, +0.2554, +0.0702, +0.0802, -0.0612, -0.0652, +0.3999, +0.4148, +0.6440, -0.1218, -0.4333, -0.2390, -0.2230, +0.0354, +0.1575, +0.0190, -0.2055, +0.1771, -0.7678, -0.2000, +0.1853, +0.1183, +0.0925, -0.2047, -0.4217, -0.0655, -0.0234, +0.2635, +0.0828, +0.2193, -0.6872, -0.3432, -0.2302, +0.1799, -0.2867, +0.0938, -0.1178, -0.0551, -0.4497, -0.1970],
-[ -0.5875, +0.3584, +0.1795, -0.4308, +0.3049, +0.3270, +0.3174, -0.1452, -0.1415, +0.2994, -1.2432, -0.3681, +0.0554, +0.1826, +0.1509, +0.6676, +0.7488, +0.0322, -0.9482, -0.0708, -0.1230, +0.3096, +0.0785, -0.0805, -0.6251, +0.1364, -0.3964, -0.9179, +0.4554, +0.0184, +0.5066, +0.1493, +0.0249, -0.5184, -1.4056, +0.0259, +0.3481, -0.4445, +0.1686, -0.0919, -0.1951, -1.3686, -0.3031, -0.7120, -0.1386, +0.3186, +0.4143, +0.1699, +0.3723, -0.5573, +0.0541, +0.7135, -0.1683, +0.3588, +0.2727, -0.5074, -0.7353, -1.2056, +0.1675, -0.3630, -0.0839, +0.2155, +0.3176, +0.2199, +0.0528, +0.1867, -0.1459, -0.1960, -0.5922, -0.1418, +0.1251, -0.2371, -0.0244, -0.3642, -0.0267, -0.3112, +0.0506, +0.2327, -0.0061, +0.0202, +0.0529, -0.1410, -0.5588, -0.3405, -0.1945, +0.0048, -0.2415, -0.0087, +0.0536, -0.2444, -0.3201, -0.0885, +0.4312, -0.0041, -0.2366, +0.2506, +0.0255, -0.4700, -0.0447, +0.1439, +0.3104, +0.1605, +0.0736, +0.1862, -0.0253, -0.1050, +0.5843, +0.0937, -0.3332, -0.2927, -0.3305, +0.0606, +0.3630, -0.0441, +0.3914, +0.1469, -0.3773, -0.1831, -0.4460, -0.2917, -0.5101, +0.5178, +0.0635, -0.3741, +0.0059, -0.3863, -0.0546, +0.2805],
-[ +0.0601, -0.3253, +0.0195, -0.1363, +0.3744, +0.0671, -0.1641, -0.4333, +0.4887, +0.2348, -0.1369, -0.2670, +0.1986, -0.5604, -1.0478, -0.3187, -0.4200, -0.2033, -0.5111, +0.1593, +0.0223, -0.2550, -0.0922, -0.2716, +0.3623, -0.1694, -0.0972, +0.1189, -0.6272, -0.0722, +0.1894, -0.6329, -0.3364, -0.7210, -0.8415, -0.3291, +0.0917, -0.4014, +0.2275, -0.3271, -0.2019, -0.3149, +0.5368, -0.0693, +0.5510, -0.1304, -0.2988, -0.1306, +0.0359, +0.1579, -0.6640, +0.1081, -1.5365, -0.1597, +0.2577, -0.0664, +0.0757, +0.1524, -0.0956, -0.1541, -0.4604, -0.4904, +0.0975, +0.2428, -0.1907, -0.7102, +0.6586, -0.1683, -0.0257, -0.3399, -0.1199, -0.0780, +0.0957, -0.2709, +0.1472, +0.0477, +0.0115, -0.1198, +0.3382, +0.4367, +0.0999, -0.6750, -0.8398, +0.0322, +0.0039, -0.3979, -0.1288, -0.5003, -0.2096, -1.1291, -0.4065, -0.3172, +0.1936, -0.6337, -0.6576, +0.0531, +0.4156, -0.9388, -0.0643, -0.7279, -0.5641, -0.3065, +0.4290, +0.0895, -0.1019, -0.3363, +0.1544, -0.0767, +0.0565, -0.7275, -0.0629, -0.8995, -0.0352, -0.0069, -0.2988, -0.5636, +0.5480, -0.3188, -0.7048, -0.3809, -0.1963, +0.3920, +0.1438, +0.1053, -0.2073, +0.2638, -0.1706, +0.0799],
-[ -0.2158, +0.0953, +0.2846, -0.2392, -0.2678, +0.0783, +0.3179, -0.2224, +0.6093, -0.5543, -0.1057, -0.2840, -0.3915, -0.2513, +0.1723, -0.3655, +0.0223, -0.4514, +0.0781, -0.3668, -0.0650, -0.2735, -1.0161, -0.0027, -0.3664, -0.0702, -0.1575, -0.2282, +0.0369, -0.0807, +0.1153, -0.0076, -0.1323, +0.4017, +0.1480, +0.2383, -0.4470, +0.1887, -0.1691, +0.3031, +0.1124, -0.5467, +0.0554, +0.0814, -0.4822, +0.0195, -0.3758, +0.4181, -0.4839, -0.3081, +0.4140, +0.1578, +0.1257, +0.2257, -0.5583, -0.5895, -0.8581, -0.3002, +0.0568, -0.3166, -0.8867, -0.0909, -0.5856, -0.1936, -0.4399, +0.1872, -0.2999, +0.4525, -0.1103, +0.1011, -0.1481, -0.0094, -0.2643, -0.3380, +0.5789, -0.2954, -0.4386, -0.7334, +0.3065, +0.4677, -0.0934, +0.2365, +0.2516, +0.3897, -0.0673, -0.0134, -0.0030, +0.1351, -0.4304, +0.0894, +0.1702, -0.1998, -0.1700, -0.1687, +0.1565, -0.3954, -0.4844, -0.3194, -0.5078, +0.0651, +0.1964, +0.0848, -0.1559, -0.1095, -0.3068, -0.0296, -0.3526, -0.5551, -0.2015, -0.3554, -0.0166, -0.0325, -0.3315, +0.6864, +0.1491, +0.4219, +0.4374, -0.1169, -0.2291, +0.5127, -0.3610, -0.4966, +0.4471, +0.0802, -0.5580, -0.5791, -0.1772, +0.2302],
-[ -0.1076, +0.1499, -0.0961, -0.2042, +0.2166, -0.2431, +0.0062, -0.7276, -0.1863, -0.3058, -0.2379, +0.1921, -0.4037, +0.0759, -0.1372, -0.1939, -0.2092, -0.7652, -0.0190, +0.3077, -0.0457, -0.0271, -0.5684, +0.0415, +0.0116, -0.8223, +0.3359, -0.1225, +0.1816, +0.2140, +0.1602, -0.1146, -0.1266, -0.0036, -0.7904, -0.2256, -0.1559, -0.2645, +0.0860, -0.0661, -0.2869, -0.6140, -0.0998, +0.2239, -0.1742, +0.2176, +0.3107, +0.0136, -0.1963, +0.5052, +0.0713, -0.3807, +0.2308, -0.5190, +0.1811, -0.1509, +0.1385, -0.0837, +0.1361, -0.2535, +0.1506, -0.3724, +0.0996, +0.1964, +0.1111, -0.0517, -0.0306, +0.1187, +0.1788, -0.0407, -0.1487, -0.0854, +0.2843, -0.0753, -0.0068, -0.0077, -0.3471, +0.0351, -0.6159, -0.4226, +0.5148, +0.0071, -0.7155, +0.2349, -0.0137, +0.1020, -0.0478, -0.0962, -0.3094, +0.0115, +0.0320, +0.1118, -0.0642, -0.6710, -0.0404, +0.2625, -0.1370, +0.0298, -0.0184, -0.1681, +0.0445, +0.0099, +0.0830, +0.2498, +0.3416, -0.2665, +0.1916, +0.0037, -0.6989, -0.3035, -0.5451, -0.0226, +0.1792, +0.2112, +0.1199, -0.4196, +0.3648, +0.1852, +0.1674, +0.3833, +0.4238, +0.2341, -0.1482, -0.0028, +0.1002, -0.2465, +0.0602, +0.2140],
-[ +0.0213, +0.1944, -0.1501, -0.7898, -0.0269, -0.1696, -0.1227, +0.3991, +0.3180, -0.0466, +0.5871, +0.0320, +0.3256, +0.0336, -0.3113, -0.0198, -0.1346, -0.6108, -0.1094, -0.5958, -0.0453, -0.5481, -0.1500, -0.0589, +0.0894, +0.1282, -0.6472, -0.0027, -0.2055, +0.2224, +0.1027, +0.1256, -0.0334, -0.1769, -0.0391, -0.3949, +0.1055, +0.2503, -0.1800, -0.3791, -0.2318, -0.0518, -0.1476, +0.1280, +0.0072, -0.0926, -0.0673, +0.2434, -0.3668, -0.9051, -0.1701, +0.0967, +0.0836, -0.0320, +0.0400, +0.0664, -0.2545, -0.2088, +0.0896, -0.3086, -0.1286, -0.1372, +0.3918, +0.2618, -0.1957, -0.2447, -0.3575, -0.3319, +0.6881, -0.1629, +0.0188, -0.3465, -0.1682, +0.2730, -0.1074, -0.0268, -0.2431, +0.0457, +0.4783, +0.2920, -0.8347, +0.0237, +0.0183, +0.2163, +0.2028, +0.0512, +0.3901, +0.3220, +0.1953, +0.2893, +0.1298, +0.1812, -0.4022, -0.2563, -0.1943, +0.0630, -0.3236, +0.3854, -0.0505, +0.0693, +0.0277, -0.5653, -0.0168, +0.0141, -0.2540, -0.5629, -0.0544, -0.1690, +0.2695, -0.5674, +0.4644, +0.5105, -0.0195, -0.4197, +0.0466, -0.3659, +0.3466, -0.1359, -0.2359, -0.3740, +0.2405, +0.1225, -0.5024, +0.0566, -0.8196, -0.1433, +0.0337, +0.0528],
-[ -0.6809, +0.2662, -0.5515, +0.0274, +0.4504, +0.3657, -0.0369, -0.0298, +0.0075, -0.1811, +0.1554, -0.5186, +0.5404, -0.3754, -0.3679, -0.0857, +0.0986, -0.5003, +0.1381, -0.2794, -0.4324, +0.0690, -0.3677, +0.0815, -0.0896, -0.6115, +0.3429, -0.1858, -0.1057, -0.4543, +0.1465, -0.1958, +0.0853, -0.1470, +0.1513, -0.2316, +0.2884, -0.4537, -0.3710, -0.0103, +0.2550, -0.1489, -0.2394, -0.2326, +0.0281, -0.1502, +0.0989, +0.2860, -0.1225, -0.4216, +0.3528, -0.2252, +0.0390, -0.5138, -0.2122, -0.0263, +0.1364, -0.4858, +0.3086, +0.1359, +0.3356, -0.6935, -0.6898, +0.2928, -0.2900, +0.4967, +0.1789, +0.0129, -0.0865, +0.1469, +0.1938, +0.3798, +0.1427, -0.3017, +0.5246, -0.0486, -0.5537, -0.0919, -0.1737, +0.0380, -0.0290, -0.3807, -0.6776, -0.2915, -0.0784, -0.2607, +0.0507, -0.0996, -0.0567, +0.3834, -0.0326, +0.1360, +0.0460, -0.1078, +0.4804, +0.2062, +0.3488, -0.1236, +0.3503, +0.0557, -0.0188, +0.2796, -0.0616, -0.0295, -0.3695, +0.1613, -0.2866, +0.3682, -0.1529, -0.0211, -0.8208, -0.5679, +0.3730, +0.2508, -0.0373, -0.5967, +0.2355, -0.0826, -0.1477, -0.4036, +0.0439, +0.3214, -0.0763, +0.1182, -0.1230, -0.0080, +0.0365, -0.3488],
-[ +0.1278, +0.3544, -0.0588, -0.9237, +0.1073, +0.2965, +0.5606, +0.1852, -0.4272, -0.6675, -0.2859, -0.7539, +0.0184, +0.0534, -0.8694, -0.1548, +0.2093, +0.0162, -0.2391, -0.3411, +0.2604, -1.3084, +0.3698, -0.0768, -0.0322, +0.0754, -0.0044, +0.1771, -0.1628, +0.4309, +0.0774, -0.0721, -0.2629, -0.0708, -0.3502, -0.0600, +0.1463, -0.5095, -1.0829, -0.9172, +0.2253, +0.1346, -0.1799, -0.0397, -0.1397, +0.0269, -0.2786, +0.1675, -0.3110, +0.0059, +0.3807, +0.1454, +0.0373, -0.0626, -0.0482, +0.3647, -0.1477, +0.4116, +0.1811, -0.3096, +0.1492, -0.0770, -0.1550, +0.3186, -0.5793, -0.0217, +0.1216, +0.0893, -1.0605, -0.0276, -0.3422, +0.0822, -0.4680, +0.2439, -0.3746, +0.0006, -0.2558, +0.1921, -0.0572, -0.0718, -0.5186, +0.0136, -0.7412, -0.2912, -0.1026, -0.3082, -0.0322, -0.1574, +0.0616, +0.1399, -0.5695, -0.5556, -0.1188, +0.0646, -0.4050, +0.3945, +0.4077, +0.1311, -0.8293, -0.0814, -0.7487, +0.0789, +0.2741, +0.1798, +0.1800, +0.0221, +0.2849, +0.1241, +0.0981, -0.0291, +0.0349, -0.2348, -1.1890, +0.2165, -0.2498, +0.3480, -0.1510, -0.0254, +0.4350, -0.2413, -0.2154, +0.1620, +0.3549, +0.1094, +0.3039, -0.1670, -0.5215, +0.2193],
-[ -0.5056, -0.2717, -0.0887, +0.1180, +0.2221, -0.0533, +0.3635, +0.0107, -0.0155, -0.3851, -0.0780, +0.4512, -0.0052, -0.2470, -0.0436, -0.3644, +0.2348, -0.3132, -0.1388, -0.3696, -0.2221, -0.1212, -0.1152, +0.1401, +0.2334, -0.2287, -0.0463, +0.0870, -0.1798, +0.0395, -0.8861, -0.8117, +0.0519, -0.0148, -0.1086, +0.2235, -0.2144, -0.2035, +0.3049, +0.2782, -0.0790, -0.3271, +0.1502, +0.0752, +0.1874, -0.2961, -0.1831, -0.1052, -0.1899, -0.1599, -0.2232, -0.0929, +0.1634, +0.2954, +0.1783, +0.1850, +0.0323, +0.1821, -0.1331, -0.0664, +0.2822, -0.3062, -0.2497, -1.2594, -0.3746, +0.1056, +0.2596, +0.0462, +0.2250, -0.5202, -0.2983, -0.3262, -0.2862, -0.4389, +0.1809, +0.1076, +0.2707, +0.4548, -0.0305, -0.0603, +0.0805, -0.3495, -0.3292, -0.4320, +0.2417, +0.1606, +0.3576, -0.0476, -0.3210, +0.1739, +0.3417, -0.2769, -0.1329, +0.6614, +0.1064, -0.5903, +0.3824, -0.0035, -0.1594, -1.0897, +0.1392, -0.0113, -0.0069, +0.3172, +0.1027, -0.1457, -1.0550, +0.2104, -0.8771, +0.1007, -0.3465, +0.3272, +0.0404, +0.0174, +0.3485, -0.2760, +0.0764, -0.0402, +0.1597, +0.4512, +0.4985, -0.8222, -0.5071, +0.0934, -0.1479, -0.6469, -0.1912, +0.2672],
-[ +0.5416, -0.0218, -0.0531, +0.0453, +0.1252, -0.1311, +0.2916, -0.0341, +0.3304, +0.0958, +0.0507, -0.2015, -0.2878, -0.5418, -0.0068, +0.0552, +0.0864, +0.4119, +0.0150, -0.0622, +0.0781, -0.4440, -0.5189, +0.0631, +0.0681, -0.0632, -0.1314, -0.0119, -0.0225, -0.1634, -0.3359, +0.1974, -0.2654, -0.1948, -0.0087, +0.0303, +0.4607, +0.1021, +0.0181, -0.0214, +0.1044, +0.0861, +0.3070, -0.2432, +0.1628, +0.0187, -0.9277, +0.1928, -0.6063, +0.3662, -0.1792, -0.0239, -0.0632, -0.6483, +0.3550, -0.1499, -0.0971, +0.2099, +0.2688, -0.0530, +0.1171, +0.5035, -0.8688, -0.3405, -0.2476, +0.4547, -0.4105, -0.1177, -0.3137, +0.1011, +0.0825, -0.3973, +0.1754, +0.2616, -0.1194, -0.0725, -0.2332, -0.5832, -0.1741, -0.4962, +0.1793, -0.3603, +0.5548, -0.2168, -0.4409, +0.2611, -0.1732, -0.2258, +0.4478, +0.2887, -0.6937, +0.4469, -0.1434, +0.2411, -0.0069, -0.8774, -0.2686, -0.0973, +0.1061, -0.0011, -0.0416, -0.2424, +0.1575, +0.1909, -0.6973, -0.0013, -0.0070, -0.2964, +0.1380, +0.5137, -0.0704, -0.2486, -0.1062, +0.1285, -0.3033, +0.0060, -0.1700, -0.0587, +0.1942, +0.3036, +0.2824, -0.8177, -0.6379, +0.4813, +0.0342, -0.1333, +0.0801, +0.4477],
-[ -0.0211, +0.2675, +0.3353, -0.3372, -0.1233, +0.2106, +0.0731, -0.1431, -0.1459, +0.2807, -0.2799, -0.2038, -0.1239, -0.4392, +0.2931, +0.4137, -0.2620, -0.1753, +0.4271, -0.1496, -0.3291, +0.3312, +0.1065, +0.1967, +0.3853, -0.0131, +0.3213, -0.1285, -0.6470, -0.2297, -0.1128, +0.3138, -0.2046, -0.0544, +0.2242, -0.1240, +0.2349, -0.4463, -0.3117, -0.1976, -0.5940, +0.5098, +0.0314, +0.1411, -0.1443, -1.3227, -0.0915, +0.0622, +0.3047, -0.6741, -0.0068, +0.1571, +0.0197, +0.3689, +0.2350, -0.7219, -0.3110, -0.3136, +0.1014, +0.1670, -0.0109, -0.1335, -0.1780, +0.2741, -0.5067, -0.0343, -0.2735, -0.1306, +0.0644, -0.0421, -0.3508, -0.0239, -0.0895, +0.7201, -0.4332, -0.2279, +0.3636, +0.4006, +0.0258, +0.0039, +0.0240, +0.0969, +0.1108, -0.3942, -0.0191, -0.0833, -0.0460, -0.0104, -0.3314, -0.3009, -0.2580, -0.0891, -0.4601, +0.0273, -0.6587, +0.0187, +0.1647, +0.2728, -0.3057, -0.6602, +0.2252, +0.0499, +0.0645, -0.3887, +0.0085, +0.2773, -0.2943, +0.0106, -0.1876, +0.1680, +0.4481, -0.6070, -0.3804, +0.0686, -0.1384, +0.0941, -0.2830, -0.3419, +0.5389, +0.0071, +0.0309, +0.3877, -0.2346, -0.2765, +0.3154, +0.5432, +0.1597, -0.0707],
-[ -0.3307, +0.0719, -0.4069, -0.4818, -0.0336, +0.2526, +0.0127, +0.1715, +0.1634, -0.1317, -0.0556, -0.6635, +0.0385, -0.1778, -0.6021, +0.0995, -0.3965, +0.5307, +0.2085, +0.0421, -0.2732, -0.4179, -0.3875, -0.2914, +0.0900, +0.1833, +0.2219, -0.4152, +0.4455, -0.3731, -0.2920, -0.0412, +0.0676, -0.4575, -0.5457, -0.3103, -0.1316, -0.6066, -0.0151, -0.2290, -0.5575, +0.4713, +0.0446, +0.1031, -0.0860, +0.1306, -0.5180, -0.0828, -0.0814, -0.0137, -1.1862, -0.0610, -0.0665, -0.4811, +0.0875, -0.1226, -0.1726, +0.1026, +0.2877, -0.2522, -0.8006, +0.0242, -0.6489, -0.1083, +0.1570, -0.0922, -0.5692, +0.2164, -0.0050, +0.0594, +0.3049, -0.1859, -0.8103, -0.2647, -0.1506, -0.3981, -0.0826, +0.2345, +0.3153, -0.3429, +0.0491, -0.1324, -0.2087, -0.0861, -0.8154, -0.0180, +0.2558, -0.2299, +0.0994, +0.0263, -0.8396, +0.1073, +0.1554, -0.3760, +0.0870, -0.0737, -0.3097, -0.1488, -0.0324, -0.2025, +0.3044, +0.1957, -0.0953, -0.1347, -0.6328, +0.0435, -0.3573, -0.6667, -0.0919, -1.0430, -0.0192, -0.1639, +0.4036, -0.1974, -0.5038, -0.0258, +0.2064, +0.2843, +0.0147, -0.0562, -0.1918, -0.3606, -0.4848, -0.1829, -0.3000, +0.0925, -0.2469, -0.0005],
-[ -0.1075, +0.0796, -0.0946, -0.4344, +0.2005, -0.1093, -0.0906, -0.3207, -0.2558, -0.0439, +0.5002, -0.5107, -0.3569, -0.2400, -0.9696, +0.1216, +0.1939, -0.0901, +0.0303, -0.5634, -0.0879, -0.0478, -0.6500, -0.1287, -0.0194, -0.4115, +0.1487, -0.3913, +0.2391, +0.2528, +0.1589, +0.1568, -0.2328, -0.3401, -0.3910, -0.4641, -0.3274, -0.2689, -0.5790, -0.2490, -0.3726, +0.1373, -0.3168, +0.1565, +0.0834, -0.1442, +0.0261, +0.0699, -0.5031, +0.1383, -0.3060, +0.0458, -0.1907, -0.1535, -0.0182, -0.2781, -0.0593, -0.3813, +0.2376, +0.0838, +0.0307, +0.1134, +0.0186, +0.0102, +0.0446, -0.0612, +0.2964, +0.0673, +0.4004, -0.1744, +0.2707, -0.0061, +0.3257, -0.8955, -0.0757, -0.6494, -0.1417, -0.2841, +0.1827, +0.0669, -0.2435, +0.0048, -0.3185, -0.2073, +0.2819, +0.0463, -0.2587, +0.1456, -0.1462, -0.1835, -0.3942, +0.1628, +0.4768, -0.3747, +0.0178, +0.1807, -0.1081, +0.0570, -0.1036, +0.3498, -0.3699, +0.1021, -0.5282, -1.1311, -0.1090, +0.3226, -0.4719, -0.1089, -0.4208, +0.4415, -0.5734, -0.4619, +0.3115, +0.3256, +0.1768, -0.3252, -0.7296, +0.6043, -0.3889, +0.1948, -0.1121, -0.3825, -0.3001, +0.0001, -0.3872, -0.0690, +0.2413, +0.2725],
-[ -0.1956, +0.4824, +0.0299, +0.0923, -0.1255, -0.0784, +0.1399, -0.0119, +0.2045, +0.1789, -0.0844, +0.0612, +0.0869, -0.1022, +0.1522, +0.1175, -0.3761, -0.8891, +0.1135, -0.1164, -0.0650, -0.4960, -0.0575, +0.3796, -0.4186, +0.5628, -0.0502, -0.2575, -1.6787, -0.1565, -0.3031, +0.2404, -1.0437, -0.0959, -0.1703, +0.1407, +0.1496, +0.1953, -0.0319, +0.3103, +0.1761, +0.0003, -0.5419, -0.6587, +0.0537, +0.2545, -0.3464, +0.0076, -0.1283, -0.4792, +0.1090, -0.2502, +0.0810, +0.5328, -0.2368, -0.2101, -0.0410, -0.0465, -0.0782, -0.0789, -0.1115, +0.0534, -0.0064, -1.3387, +0.2155, -0.0807, -0.3716, -0.1701, +0.0104, +0.0665, -0.0696, -0.6764, -0.0896, +0.1293, +0.2936, -0.2979, +0.1135, +0.1420, +0.2191, +0.0649, -1.5397, +0.0106, -0.0295, +0.0041, +0.1493, +0.2680, -0.1745, +0.0864, +0.0223, +0.1098, +0.1272, +0.1090, -0.3073, +0.0846, -0.1849, +0.2400, +0.0479, -0.1117, -0.3259, +0.2560, -0.8979, -0.2436, -0.2723, +0.0895, +0.2896, +0.5229, +0.3580, +0.2622, +0.1865, -0.0928, -0.1333, -0.0331, -0.2025, +0.0284, +0.0933, -0.4256, +0.1458, -0.0047, +0.2814, -0.5681, -0.1660, -0.0740, -0.3705, -0.1294, -0.2887, -0.1671, -0.3191, +0.0041],
-[ -0.0429, -0.2979, -0.8061, +0.0274, +0.1359, -0.0807, +0.2634, -0.1513, -0.1274, -0.0166, -0.2593, -0.0043, -0.3913, -0.4622, -1.0735, -0.2252, -0.3954, -0.2352, +0.1754, -0.3066, -0.5369, -0.2073, -0.0621, -0.2404, +0.1481, +0.1076, -0.2903, +0.0644, +0.3461, -0.8494, -0.2225, -0.4445, +0.0074, +0.1606, -0.2494, +0.1894, -0.4898, +0.2003, -0.8726, +0.1727, +0.4279, +0.0250, -0.2323, -0.4568, -0.9386, +0.4602, -0.0544, -0.6053, -0.3673, -0.2031, -0.2869, -0.0142, -0.1154, -0.0311, +0.3106, -0.1357, -0.0287, -0.6635, +0.0821, -0.7078, -0.8762, -0.4313, -1.1641, +0.1237, -0.2846, -0.7949, -0.8328, +0.1506, +0.3018, -0.0569, +0.3055, -0.2692, -0.8944, -0.6283, +0.0082, +0.1982, +0.2366, -0.2263, +0.1205, -0.3662, -0.0564, -0.8527, -0.0458, -0.2136, -0.8190, +0.3705, +0.1591, +0.0972, +0.1972, +0.1188, +0.1552, -0.0021, -0.3104, -0.0915, +0.0861, -0.0970, -0.1669, -0.2250, +0.1361, -0.2040, -0.1728, +0.0874, -0.4176, -0.0232, +0.2895, -0.3241, -0.2774, -0.6778, +0.0860, -0.1810, -0.2635, -0.3905, +0.2894, -0.5524, -0.5900, +0.0042, -0.1872, +0.0342, -0.1982, -0.3431, -0.2942, -0.1713, -0.3947, -0.0634, -0.2148, -0.3236, -0.6599, -0.4746],
-[ +0.1139, +0.0650, -0.2456, -0.1315, +0.1407, +0.0788, -0.1801, +0.4116, +0.0631, +0.3614, +0.1779, +0.2011, +0.1047, +0.1695, +0.0276, -0.1528, -0.1153, -0.3329, +0.1846, -0.2067, -0.1040, -0.3134, -0.0784, -0.0427, +0.2053, +0.1852, -0.2523, +0.0244, -0.1028, -0.4057, -0.4726, -0.4021, +0.1813, -0.1851, +0.1457, -0.4243, +0.2401, -0.1664, +0.4241, +0.1109, +0.0009, +0.4179, -0.0435, +0.0391, -0.1372, +0.1172, -0.4394, +0.2111, -0.4688, +0.0953, -0.8070, -0.0438, -0.1590, -0.5387, -0.0352, +0.1419, +0.3123, +0.4866, -0.3642, -0.1444, +0.2279, +0.1875, +0.2849, -0.0600, +0.4420, +0.3253, -0.2210, +0.0820, +0.0518, +0.2397, -0.6165, +0.2275, -0.0655, -0.5054, +0.1406, +0.0747, -0.2759, +0.2004, +0.2437, -0.9419, +0.1028, +0.0414, +0.1167, +0.0623, +0.2964, -0.1441, -0.2434, -0.0737, -0.0669, +0.4142, -0.3767, -0.4335, -0.2037, -0.4858, +0.1892, -0.0506, +0.1072, +0.0308, -0.0045, +0.1688, +0.0354, -0.1328, -0.0729, +0.1582, -0.7064, -0.2073, +0.1505, +0.1551, -0.4480, +0.3366, -0.0612, -0.4353, +0.0585, +0.0633, -0.0932, -0.0445, +0.0806, +0.1299, -0.0159, +0.3052, +0.2307, -0.1101, -0.0202, +0.0697, -0.5824, -0.0746, +0.4108, -0.0447],
-[ +0.0791, +0.1980, -0.7039, +0.0263, +0.2395, +0.6237, +0.2502, -0.5161, +0.2494, -0.2117, +0.1475, +0.0525, -0.4173, -0.3249, +0.2539, -0.1223, -0.0348, -0.2279, +0.2262, +0.0258, -0.3077, +0.2887, +0.3885, +0.1906, +0.2463, +0.3811, -0.6282, +0.0522, +0.5306, -0.4458, -0.1445, -0.3747, -0.0662, +0.2248, -0.1537, -0.2953, +0.0561, -0.2883, -0.5619, +0.0355, -0.2044, +0.1899, -0.0981, -0.2455, +0.0141, +0.0599, -0.0083, +0.0112, -0.2022, -0.2484, -0.4551, -0.3796, +0.0054, +0.0155, -0.1069, -0.0031, -0.4725, +0.2876, +0.0632, -0.6091, +0.0202, +0.0060, +0.4156, -0.3036, -0.0778, +0.2482, -0.8074, +0.2175, -0.2130, +0.2723, +0.1917, -0.1859, +0.3197, -0.1314, -0.1503, +0.1386, +0.1615, -0.5322, -0.4531, -0.2186, -0.0994, -0.4077, +0.4061, -0.0434, -0.2415, -0.6183, -0.0757, -0.2556, -0.2224, +0.0449, +0.4767, -0.0516, -0.1578, -0.5435, -0.3362, +0.5258, -0.0355, -0.0297, +0.3339, +0.0571, -0.1741, +0.4465, +0.2506, -0.6265, -0.4877, +0.2635, -0.1913, -0.0469, +0.2758, -0.1095, +0.1190, -0.0785, +0.0585, +0.3044, -0.4372, -0.4773, -0.4492, +0.2806, -0.5223, +0.4161, -0.3399, +0.0181, +0.0459, +0.0355, -0.2409, +0.3043, -0.5086, -0.3526],
-[ +0.3889, -0.1236, +0.3455, +0.0586, +0.1031, -0.0423, +0.2450, +0.3118, -0.0065, -0.2184, -0.1482, -0.3720, +0.2949, +0.2279, -0.0590, -0.1256, +0.0081, -0.0231, -0.0424, -0.0446, -0.0472, -0.0739, +0.0330, +0.2615, +0.0390, +0.0315, -0.8050, -0.0950, -0.0147, -0.0005, -0.4977, +0.1281, -0.4847, -0.0590, +0.2566, +0.0080, +0.3070, +0.0687, -0.3527, -0.0516, -0.0147, -0.1813, +0.3453, -0.0237, +0.1650, -0.5538, -0.2602, -0.4506, +0.0339, -0.2247, +0.0678, +0.3342, -0.1982, -0.0218, +0.1906, +0.1715, +0.0353, -0.0505, +0.3488, +0.1096, +0.1575, -0.1131, -0.0731, +0.0549, +0.2869, +0.0115, +0.5333, -0.3713, -0.3464, +0.1477, -0.0973, -0.5280, +0.0714, +0.2884, +0.1430, +0.1944, +0.2250, +0.2365, +0.3119, +0.0493, -0.2922, +0.2082, -0.2683, -0.2334, -0.0036, -0.1826, +0.0553, +0.0514, +0.0699, +0.4359, -0.0839, -0.1283, -0.5059, +0.0360, +0.4593, -0.2900, +0.3191, -0.0913, -0.0334, -0.0426, -0.2070, -0.0938, +0.1743, -0.0897, +0.0871, +0.0905, -0.4720, -0.0107, +0.3723, -0.0417, -0.1012, -0.0172, -0.3901, -0.3876, +0.1151, +0.0425, -0.3587, +0.0249, +0.0674, -0.2577, +0.1353, -0.1724, +0.1267, -0.2325, +0.0940, +0.4211, +0.2862, -0.4374],
-[ -0.3170, +0.3755, -0.0338, -0.6477, -0.1268, +0.4264, -0.2412, -0.3584, -0.4816, -0.0234, -0.4274, -0.0597, +0.4883, -0.4695, -0.0844, +0.2464, -0.1324, -0.1116, +0.3023, +0.2658, +0.1502, +0.0145, -0.1165, +0.0199, +0.0481, +0.2250, +0.2717, +0.0514, -0.5709, -0.8578, -0.5535, -0.1945, -0.1825, -1.0669, -0.0163, +0.2724, -0.1275, +0.4192, -0.0253, -0.0427, -0.1992, +0.2067, +0.3362, +0.0737, -0.8661, -0.2856, -0.2030, +0.0765, -0.1862, -0.7112, +0.0424, +0.3103, -0.0769, +0.2623, +0.1757, +0.0937, +0.2951, +0.0081, -0.2650, +0.4250, -0.0401, +0.0961, +0.4578, -0.1580, +0.2566, -0.1072, +0.0640, -0.2257, +0.1407, -0.2923, -0.0112, -0.3022, -0.2181, -1.1515, +0.5188, +0.1174, +0.2920, -0.1971, +0.0040, +0.0855, -1.0107, -0.2752, -0.3839, -0.2948, -0.0194, +0.2019, -0.4102, -0.3485, -0.4294, +0.1244, -0.0475, +0.0760, -0.0122, +0.0635, -0.4242, +0.1172, -0.1831, +0.2975, -0.0734, +0.0206, -0.6166, +1.0285, -0.8004, +0.2025, -0.3087, +0.0608, -0.0776, +0.4676, -0.6982, +0.0874, +0.3236, -0.1107, -0.2018, +0.0993, -0.1123, +0.5077, -0.2170, -0.8204, -0.2160, -0.1872, +0.6235, +0.2099, +0.0830, +0.5081, -0.3071, -0.3446, -0.2227, -0.3825],
-[ -0.1874, -0.1186, -0.6802, +0.0035, +0.1394, -0.3427, +0.1561, -0.0044, -0.4163, -0.6432, +0.0009, +0.0743, +0.0019, +0.3348, -0.1833, +0.0599, -0.0237, -0.8147, -0.5931, +0.0681, +0.3820, -0.4131, -0.5803, +0.5772, -0.1047, -0.1667, -0.0174, -0.4283, -0.0115, -0.2094, +0.3176, -0.4656, +0.1398, -0.2553, +0.3680, -0.2766, -0.0749, +0.3381, +0.6150, -0.5616, +0.5847, -0.2923, -0.0928, +0.2362, -0.4309, +0.2479, +0.3509, +0.0306, -0.0601, -0.0772, -0.4807, -0.0940, +0.0597, +0.2288, -0.2230, -0.1378, -0.0027, +0.1361, +0.1256, -0.0968, -0.4223, -0.1213, -0.0766, -0.3987, +0.4523, +0.1027, +0.0623, +0.1629, +0.0932, -0.1068, -0.0629, -0.2282, -0.1594, -0.2082, -0.4811, +0.2055, +0.3540, +0.0748, +0.1092, -0.3655, -0.1293, +0.5093, +0.2215, -0.3072, +0.2241, -0.0072, -0.2497, -1.0213, +0.1769, -0.1960, -0.5724, -0.1859, +0.2190, -0.4151, +0.4209, -0.1399, -0.2326, +0.1927, +0.1507, -0.3548, -0.2342, +0.3334, -0.4695, -0.0160, +0.0182, -0.0142, +0.0374, -0.4114, -0.7137, -0.0206, -0.9733, -0.2071, +0.1435, +0.0653, -0.2332, -0.5594, -0.0698, +0.1158, +0.3619, +0.0128, -0.1712, +0.5550, -0.0249, -0.2328, -1.0144, +0.0697, +0.2297, -0.0154],
-[ +0.1416, +0.2309, +0.1272, +0.3941, -0.1264, +0.0519, +0.0873, +0.1319, +0.2100, +0.5420, +0.0346, +0.1919, -0.0527, +0.2655, -0.0654, +0.0043, +0.3115, +0.4582, +0.3955, +0.0363, -0.3897, +0.2471, -0.1910, -0.3071, +0.0255, +0.1280, -0.0897, +0.4849, +0.1039, -0.2925, -0.0640, +0.1888, +0.1011, -0.2415, +0.3240, -0.7261, +0.4590, -0.3333, +0.2433, +0.1094, -0.1727, -0.0460, -0.2958, -0.1053, -0.0891, -0.0464, +0.0229, -0.1550, -0.2716, +0.0343, +0.0671, +0.0667, -0.4367, +0.2242, +0.0838, +0.1480, -0.1503, +0.1468, -0.0787, +0.1684, +0.5497, +0.3268, +0.0520, -0.3957, +0.3271, +0.0407, -0.0103, -0.6582, -0.4209, +0.2281, +0.2063, +0.1261, -0.0853, +0.1172, +0.2424, +0.2464, -0.3707, +0.2101, +0.1751, +0.1536, -0.3106, -0.2551, -0.3719, -0.4328, -0.5526, +0.3865, -0.0679, +0.4122, +0.0144, +0.5162, +0.3118, -0.0527, -0.5021, -0.0328, -0.0653, +0.2858, +0.3345, -0.1361, +0.2132, +0.0117, +0.1889, -0.1802, -0.0858, +0.2928, -0.3164, +0.0148, -0.3775, -0.1734, +0.0018, +0.2143, +0.2750, -0.4583, -0.3690, +0.0197, -0.0628, -0.0013, -0.3150, -0.0254, +0.1141, +0.1115, -0.0689, +0.2310, -0.3745, -0.1398, -0.5079, +0.0076, +0.1439, -0.2340],
-[ -0.0705, +0.2175, -0.3332, -0.1569, -0.1880, -0.0037, +0.1646, +0.1630, -0.6191, -0.8408, -0.3053, -0.1745, +0.0026, +0.4307, -0.4499, -0.1112, -0.0265, +0.2433, -0.0564, +0.2633, -0.2392, -0.0076, -0.3069, -0.4411, +0.1402, -0.6455, +0.3210, +0.0260, -0.3119, +0.5672, -0.0835, -0.5722, -0.6016, +0.1153, +0.1611, -0.7369, -1.3666, +0.0773, -0.0642, -1.0518, +0.0271, +0.1978, -0.2372, +0.6399, +0.0095, -0.1786, -0.8306, +0.1600, +0.0155, -0.0362, -0.3337, -0.6398, -0.5897, -0.0730, +0.2387, -0.2654, +0.2886, -0.0430, -0.1995, +0.8904, +0.4374, -0.5649, -0.1457, +0.4233, +0.5757, -0.1515, -0.6817, +0.2119, -1.2438, +0.0547, -0.8169, -0.2639, +0.0272, -0.0893, +0.2654, -0.0196, +0.2261, -0.5399, +0.5351, -0.0945, -0.2289, -0.8261, +0.4079, +0.3965, -0.3613, -0.3296, -0.1655, -0.3622, +0.4279, -0.0974, -0.6180, -0.2898, +0.2287, -1.0311, +0.5108, -0.5468, -0.5000, -0.0666, +0.6999, +0.0559, +0.0413, -0.5421, -0.3508, +0.6266, -0.4022, -0.8094, -0.6987, -0.0470, -0.2295, -0.0360, +0.0580, -0.6328, -0.5165, -0.6991, -0.1251, -0.3032, -0.8044, -0.0751, +0.1579, +0.2006, +0.4040, -0.0811, +0.3109, -0.0211, -0.1546, +0.1875, -0.0905, +0.0186],
-[ -0.1124, -0.0259, -1.0389, -0.2415, -0.1909, -0.0094, +0.1439, -0.2701, -0.2011, +0.1145, +0.1781, +0.0553, -0.2120, -0.2954, +0.3016, -0.0922, -0.3145, +0.2040, +0.0703, -0.2844, -0.0642, +0.4545, +0.0644, -0.1845, -0.0994, -0.8798, -0.1192, -0.5188, +0.0076, -0.2705, +0.1672, +0.4707, -0.0896, +0.3602, -0.4464, -0.1122, +0.1324, -0.1451, +0.1014, +0.0307, -0.9547, +0.0565, -0.1124, -1.5838, +0.0327, -1.1211, -0.2453, +0.1526, -0.2564, -0.0585, +0.2328, +0.0004, +0.0644, +0.4235, +0.3800, -0.0384, +0.0893, +0.0122, -0.4679, -0.2261, -0.4993, +0.4685, -0.0971, -0.1161, -0.1099, -0.1286, -0.3552, -0.5843, +0.0891, -0.7263, -0.2820, -0.0843, -0.2338, +0.0958, -0.4697, -0.1636, +0.2075, -0.1443, -0.0772, +0.1051, -0.6447, -0.6946, -0.6446, +0.1869, -0.0377, +0.2761, +0.2183, -0.2731, +0.4264, -0.0304, -0.3574, -0.1569, +0.0530, -0.2232, +0.5197, -0.2320, +0.1347, +0.2012, +0.4305, +0.5680, +0.0232, +0.0364, -0.0573, -0.0205, +0.2564, +0.1661, -0.2184, -0.0759, -0.1445, -0.0086, -0.0486, -0.3832, -0.5249, +0.3752, -0.1400, -0.4232, -0.5390, +0.1935, -0.4422, +0.5784, +0.2731, -0.1560, -0.2261, -0.1864, -0.3307, -0.4695, +0.1852, -0.3265],
-[ -0.6703, +0.0926, -0.5231, -0.0533, -0.1457, -0.4545, +0.1801, +0.3127, -0.2343, +0.3361, +0.3834, -0.7315, +0.0778, -0.3351, +0.4405, -0.4576, -0.5709, +0.2803, +0.0452, +0.0133, -0.2356, -0.6245, -0.0676, -0.2523, +0.0208, -0.5238, -0.9113, -0.2605, -0.4297, -0.5623, +0.4107, -0.0113, +0.1714, -0.4200, -0.5485, -0.0135, -0.5424, -0.9021, +0.4813, -0.0478, -0.0835, +0.2108, +0.1599, -0.2998, -0.1875, -0.1832, +0.2381, -0.3613, +0.0165, +0.2614, -0.0388, +0.0995, +0.0900, -0.3565, -0.0507, -0.4172, -0.4961, -0.0002, -0.2006, +0.3034, +0.1398, +0.3606, +0.1704, +0.0951, -0.8070, -0.0367, -0.2107, +0.3901, -0.2230, -0.1858, +0.0469, +0.3347, -1.5453, +0.0425, +0.3040, +0.7134, -0.7763, -0.1766, -0.3002, -0.5227, +0.0830, -0.1727, -0.4539, -0.1433, -0.0327, +0.4274, +0.6077, -0.0714, -0.0844, -0.1670, -0.1059, -0.1060, +0.2655, +0.3415, -0.0698, +0.0529, -0.6991, -0.0675, +0.2832, -1.2297, +0.1104, -0.1522, -0.0114, +0.0321, -0.8254, +0.2382, -0.1540, -0.4243, -0.5772, +0.2560, +0.0717, +0.5933, +0.1687, +0.5182, -0.2102, +0.0605, -0.0974, -0.6947, -0.5887, -0.1060, +0.1320, -0.5905, -0.0760, +0.1181, +0.3569, -1.1210, -0.1727, -0.3395],
-[ -0.1772, +0.3237, -0.4493, -0.3765, -0.0837, -0.1910, +0.0285, +0.0285, -0.0667, -0.3530, -0.4776, +0.1161, +0.1717, +0.0996, -0.2512, +0.1541, +0.1372, -0.4701, +0.3240, +0.2725, +0.3984, +0.2341, -0.1772, -0.0638, -0.9732, -0.2302, +0.1441, +0.2924, -0.0501, -0.1822, +0.2711, -0.4964, -0.2970, -0.0056, -0.3456, -0.2073, +0.2572, +0.1298, -1.3292, +0.1337, +0.3027, +0.1671, +0.4342, -0.2896, +0.1945, -0.0109, -0.0791, +0.4136, -0.3764, +0.1054, -0.0079, -0.9551, +0.1080, +0.1019, +0.0474, -0.6121, +0.0449, +0.0598, -1.1097, +0.0250, -0.1256, -0.1458, -0.2722, +0.1970, +0.0081, +0.0660, -0.1319, +0.2402, +0.1193, -0.2687, +0.1651, -0.0789, -0.0503, +0.1427, +0.1901, -0.4159, -0.1638, +0.0628, -0.3589, -0.0816, +0.2290, +0.0615, -0.0529, +0.5482, -0.2030, -0.1866, -0.1962, +0.1167, -0.0306, -0.0570, -0.5030, +0.2395, -0.0310, +0.1479, -0.4245, +0.1024, -0.1648, +0.0096, +0.4198, -0.0484, -0.4378, -0.1204, +0.0451, -0.1932, +0.1844, +0.0525, -0.2658, +0.2161, +0.0031, +0.0196, -0.4107, -0.0498, +0.0715, +0.0926, -0.4154, -0.8397, -0.0224, -0.0883, +0.0899, -0.2138, +0.3100, +0.0488, +0.1945, -0.2503, +0.1935, -0.2487, +0.1230, +0.1808],
-[ +0.0978, +0.2190, -0.0593, -0.2084, +0.1471, +0.2789, +0.1923, +0.0510, -0.1054, +0.0873, -0.3996, -0.3414, -0.1372, +0.4061, +0.4627, -0.3202, -0.4714, -0.9601, -0.4819, -0.0822, +0.2082, +0.4049, -0.3494, -0.2458, +0.1077, +0.0142, +0.2404, -0.2345, -0.1056, -0.2140, -0.2043, -0.0387, +0.2045, +0.0874, -0.2327, -0.2445, -0.2904, -0.5968, -0.2412, -0.0058, -0.2166, -1.6990, +0.0953, -0.4337, +0.2621, +0.0671, +0.2875, +0.2830, -0.0937, -0.1816, -0.1853, -0.2221, -0.1232, -0.2037, -0.5923, -0.1751, -0.5312, +0.0452, +0.0293, -0.1305, -0.6181, +0.3799, +0.0910, +0.2810, -0.1294, -0.3590, -0.0479, +0.5384, +0.4292, +0.2362, +0.0533, +0.3635, +0.1747, -0.0539, +0.2116, +0.1162, -0.1256, -0.1487, +0.3834, -0.1898, -0.6399, +0.3572, -0.2274, -0.3151, -0.5312, +0.2602, +0.4891, +0.5756, +0.1359, +0.0022, -0.0719, +0.1784, -0.1273, -0.1417, +0.0633, -0.0857, -0.0686, -0.1350, +0.0348, +0.0844, -0.3420, +0.4479, +0.0563, +0.3900, -0.0671, -0.2740, -0.4127, +0.2551, -0.1971, -0.2538, -0.7251, +0.1549, -0.4616, +0.0078, -0.1966, -0.2291, +0.4462, -0.0231, +0.1826, -0.2767, +0.2035, +0.2113, +0.2010, -0.1224, +0.0935, +0.0749, +0.5143, -0.2320],
-[ +0.4054, +0.2429, -0.0183, -0.0671, +0.0756, -0.3977, -0.0052, +0.3820, +0.1232, -0.6040, +0.1117, +0.1694, +0.0706, -0.0372, -0.3751, -0.1524, +0.1442, +0.2963, +0.3444, -0.1264, -0.2681, +0.2256, -0.1735, +0.1759, -0.1471, -0.0931, -0.1282, -0.0297, -0.4555, +0.1279, -0.3330, -0.0396, -0.2031, +0.0297, -0.2009, -0.4507, +0.1667, -0.0241, +0.0708, -0.0017, +0.4077, -0.4664, +0.1849, +0.2298, +0.0304, -0.1883, -0.1395, -0.4955, -0.3710, -0.1001, +0.2081, -0.1213, +0.1483, -0.0164, -0.0292, -0.2213, +0.0290, -0.1306, -0.7133, -0.2339, +0.0027, +0.3779, -0.1889, -0.4761, +0.0219, -0.3321, -0.0823, -0.3801, -0.4626, +0.0792, -0.1393, +0.0571, +0.2609, +0.5688, +0.1841, -0.1736, +0.4979, -0.2646, -0.1537, -0.0628, +0.4625, +0.1443, +0.0340, -0.2156, -0.1324, +0.1748, -0.0408, +0.2963, -0.0362, -0.0399, -0.2844, -0.1848, +0.0143, +0.2672, +0.0449, -0.0820, +0.2961, +0.0566, +0.1471, +0.0741, -0.1360, -0.3407, +0.1218, +0.2081, +0.3921, -0.1527, -0.3588, +0.1095, +0.5187, +0.1537, +0.3488, +0.1492, +0.1520, +0.0071, +0.0351, -0.4850, +0.0759, -0.1150, +0.1143, -0.2452, +0.1051, -0.3250, +0.3133, +0.1014, +0.4137, +0.0760, -0.0911, -0.1412],
-[ +0.2362, +0.1948, -0.0234, -0.3180, -0.3947, -0.4324, +0.0409, +0.3256, +0.3289, +0.2192, +0.5133, -0.0905, -0.1503, -0.2234, -0.1854, -0.1960, +0.3640, +0.5452, -0.2586, -0.2272, -0.4349, -0.4656, -0.1711, -0.6232, -0.0941, -0.0505, -0.0344, +0.4293, +0.0385, +0.5727, +0.1007, +0.5269, -0.1729, -0.1460, +0.0340, +0.0289, -0.1339, -0.5340, -0.2329, +0.0951, -0.0265, +0.0880, -0.1202, -0.2510, +0.5979, -0.3229, +0.1184, +0.0523, -0.4103, -0.3743, -0.0977, -1.0859, -0.6775, +0.3640, -0.8403, +0.0808, +0.1736, -1.3813, -0.3318, -0.0426, +0.0144, -0.0157, +0.3430, -0.2677, -0.9526, -0.1665, -0.5873, +0.5943, -0.0056, +0.1360, -0.6386, -0.0068, -0.3385, +0.3513, -0.3315, +0.2062, -0.0138, -0.0954, +0.3514, -0.2501, -0.1372, +0.1850, +0.3187, +0.2417, -0.0165, -0.0188, -0.4274, -0.6362, -0.0069, -0.2832, +0.2678, +0.1463, -0.2544, +0.1819, -0.1543, +0.5009, -0.0178, -0.3187, +0.2966, +0.2476, +0.2248, +0.1764, -0.3332, -0.4743, -0.0223, -0.1946, +0.3361, +0.3132, -0.4011, -0.0480, -0.2854, +0.0791, +0.3655, -0.0550, -0.3133, -0.0224, +0.3137, +0.0587, -0.0012, -0.0146, -0.9586, -0.4508, -0.3847, +0.7080, -0.1266, -0.0618, +0.2187, +0.1620],
-[ -0.2008, +0.1522, -0.5955, +0.6051, +0.1620, +0.0268, +0.1630, +0.2391, +0.0104, +0.1939, +0.0231, -0.2313, +0.0025, +0.1624, -0.3330, -1.0833, +0.0795, +0.4136, -0.1967, -0.1655, -0.4112, -0.5563, +0.0014, +0.2210, +0.0668, +0.0035, +0.0021, -0.3850, +0.0200, -0.1434, +0.2206, +0.4751, -0.2284, -0.3879, -0.4084, -0.3560, -0.4632, -0.4490, +0.4050, -0.1352, +0.6847, -0.1648, -0.0965, -0.1461, -0.4165, +0.1370, +0.1259, +0.4660, -0.2856, -0.2612, -0.0582, -0.3693, -0.1022, +0.2008, +0.0215, -0.0236, +0.1790, -0.6251, -0.2491, -0.3790, -0.3333, -0.4391, +0.3633, -0.2411, +0.1885, +0.4584, +0.0208, +0.1701, +0.1982, -0.0979, +0.4661, +0.0457, +0.1591, +0.1819, +0.0283, +0.4571, -0.5580, -0.1806, -0.3569, -1.1665, +0.0674, -0.2786, -0.2875, +0.4527, -1.1245, +0.3730, +0.1160, +0.1188, -0.2990, +0.0239, -0.6229, -0.2620, -0.3014, -0.4404, -0.0490, -0.3869, -0.6526, -0.5756, -0.8867, -0.7128, -0.0526, +0.0577, -0.3834, +0.0532, -0.0304, +0.0433, +0.1128, -0.6711, +0.4782, -0.0905, -0.5573, -0.4746, -0.2918, +0.4604, +0.6131, -0.1770, -0.2956, +0.3240, -0.4591, +0.0128, -1.1714, -0.1943, -0.0942, -0.0663, +0.0099, +0.3937, +0.0239, +0.2766],
-[ +0.0170, +0.1780, -0.4973, -0.0716, -0.2169, +0.4612, -0.1626, -0.4549, +0.0101, -0.2997, -0.1466, -0.4529, +0.4533, -0.2593, -0.1703, -0.0386, -0.1084, +0.2293, +0.2698, +0.1456, +0.4082, +0.0162, -0.2304, -0.1280, -0.6106, +0.1895, +0.3912, +0.1475, +0.0724, -0.0967, -0.0013, -0.5470, +0.2986, -0.1856, +0.2783, -0.0052, -0.0829, +0.4755, -0.0281, -0.3022, -0.3180, -0.2155, -0.0571, -0.4241, +0.2273, -0.1250, -0.2180, -0.1371, +0.2904, -0.1918, +0.0821, -0.0508, +0.0111, +0.4068, -0.2078, -0.2357, +0.1265, -0.3957, -0.2841, -0.1312, +0.0499, -0.1635, +0.5007, -0.1800, -0.1760, -0.2792, +0.3352, +0.2681, +0.0224, +0.0703, +0.0863, +0.4539, +0.3918, -0.2057, -0.0448, +0.4148, -0.4861, +0.0167, -0.2710, +0.2207, -0.0376, +0.1143, -0.0410, +0.2689, +0.2591, -0.1383, +0.0083, -0.0713, +0.4651, -0.0582, -0.8496, -0.5416, -0.0562, +0.0845, +0.3523, +0.0582, -0.0935, -0.9280, +0.2553, -0.1722, -0.1497, -0.0048, +0.1228, -0.0553, -0.0358, -0.0211, -0.2331, -0.0881, +0.6748, +0.1664, -0.2651, -0.3012, +0.0718, +0.2363, -0.2371, +0.2396, +0.0795, +0.1391, +0.0848, -1.2251, -0.2978, -0.3685, -0.2829, -0.2450, +0.3609, +0.3417, +0.1501, +0.3238],
-[ +0.0900, -0.2040, -0.3442, -0.0759, -0.0008, -0.1255, -0.4207, -0.1525, +0.0554, -0.0316, -0.0605, +0.0019, -0.1811, -0.4385, +0.2662, -0.0091, -0.2444, +0.4792, -0.1383, -0.0188, +0.0034, +0.0720, +0.0144, -0.0678, -0.1145, -0.3357, +0.0574, -0.0022, -0.2551, +0.2565, -0.2532, -0.5748, +0.0039, +0.2820, +0.0501, -0.2402, +0.2779, -0.3452, +0.0553, +0.2286, +0.1530, -0.2965, -0.0433, +0.2779, +0.2508, +0.2410, -0.4465, -0.3985, +0.3084, +0.3646, -0.1586, -0.2752, -0.1026, -0.1534, +0.0080, -0.1443, +0.0291, -0.0555, +0.4796, -0.3250, +0.0324, -1.3958, -0.1115, -0.4174, -0.8049, -0.1630, -0.0525, -0.1305, +0.0095, -0.0867, +0.6708, -0.0000, -0.0843, -0.0231, +0.0889, +0.3775, +0.0640, -0.2378, -0.5108, +0.5505, +0.2033, -0.0100, -0.6312, +0.2917, -0.0302, -0.6544, -0.0306, -0.1413, +0.0555, +0.0217, +0.0254, +0.1307, -0.3287, -0.2562, -0.5944, +0.1274, -0.2151, +0.1284, -0.1192, -0.0702, +0.0741, -0.4227, +0.3265, +0.4678, +0.3035, +0.0018, +0.3776, -0.1378, -0.1743, +0.3270, +0.2135, +0.1307, +0.3493, +0.0399, -0.0457, -0.2329, +0.0670, +0.1151, +0.1365, -0.0620, -0.2110, +0.3270, -0.0685, -0.1888, +0.2463, +0.0731, +0.2472, -0.1711],
-[ -0.6258, +0.0343, -0.4289, -0.0230, +0.1648, -0.2181, -0.0405, +0.2619, -0.3522, +0.2752, -0.2303, -0.8017, +0.0875, -0.5309, -0.0828, +0.0963, -0.0591, -0.1077, -0.5009, +0.0188, -0.3606, +0.1645, -0.4699, -0.0852, -0.0179, +0.1350, -0.1510, -0.3459, -0.0844, -0.3181, +0.2630, -0.4920, +0.0747, +0.1878, +0.1468, -0.1660, +0.3766, -0.7024, -0.1669, -0.3311, -0.0016, -0.4786, -0.0991, -0.1425, -0.0974, -0.2058, -0.1966, +0.2934, -0.3269, -0.3688, +0.1155, -0.1031, -0.1258, -0.4646, +0.2674, +0.1911, +0.4869, -0.1837, -0.5085, -0.5208, -0.1521, -0.0067, -0.0239, -0.2621, -0.3033, -0.5556, +0.1006, -0.0904, -0.0944, +0.0145, +0.3106, +0.1368, -0.0789, +0.0792, +0.2908, +0.2396, +0.3105, -0.6561, +0.1680, -0.1279, -0.2308, -0.2565, +0.4570, +0.5447, -0.2268, +0.1352, -0.3080, -0.1836, +0.4647, -0.3035, +0.0227, -0.0715, -0.0236, -0.2222, +0.0024, +0.1746, +0.5088, -0.3626, +0.1088, -0.4604, -0.1205, -0.0737, +0.2408, -0.4081, -0.2848, -0.0930, +0.6972, -0.6394, -0.3911, +0.3077, +0.1641, -0.2980, +0.3526, +0.4996, +0.4259, -0.4143, -0.0722, -0.0489, -1.0649, +0.1243, -0.1063, -0.2763, -0.3938, +0.0349, -0.2978, -0.1311, -0.1644, -0.2178],
-[ +0.2228, -0.1594, -0.1861, -0.4351, -0.3284, -0.3570, -0.1520, -0.3707, -0.2458, +0.1899, +0.1590, -0.4710, -0.3044, +0.2631, +0.4542, +0.5799, +0.1573, -0.0166, -0.3127, -0.2947, +0.2246, -0.2435, +0.3069, -0.2311, -0.5902, +0.4220, +0.2568, +0.1050, +0.0542, -0.3542, -0.2701, -0.0067, +0.1571, +0.0236, +0.0788, -0.3256, -0.4584, -0.2293, -0.2716, -0.0985, -0.3065, -0.1393, +0.3065, -0.2204, -0.2763, +0.5014, +0.5428, -0.3151, -0.0117, -0.5099, +0.5324, -0.0418, +0.1083, +0.2712, +0.1853, -0.0178, +0.1567, -0.8271, -0.0563, -0.0500, +0.1297, -0.0225, -0.3542, -0.0787, -0.1147, -0.0703, -0.3248, +0.2742, -0.0758, -0.5295, -0.8132, -0.0120, -0.2870, +0.3596, -0.4447, +0.1253, +0.3223, +0.0799, -0.2196, -0.1284, -0.3209, +0.6268, +0.3135, -0.3077, +0.5631, +0.0843, -0.1243, +0.3294, +0.2224, -0.3047, -0.3792, -0.5224, -0.0835, -0.0596, -0.4145, -0.4059, +0.2051, -0.5110, -0.2352, -0.1687, +0.3791, -1.1113, +0.0344, -0.5561, -0.0971, -0.1956, -0.9917, +0.0974, +0.4424, +0.2190, -0.5096, +0.1050, -0.1065, +0.1762, -0.2220, -0.3448, -0.0259, +0.0306, +0.3688, +0.0888, +0.5377, -0.0213, +0.0768, +0.1048, -0.2878, -0.1735, -0.0799, -0.3435],
-[ -0.2558, -0.1894, -0.4240, -0.1683, +0.2696, -0.6537, -0.4097, -0.8188, +0.0788, -0.0674, +0.0466, -0.1045, -0.3688, +0.1775, +0.0076, +0.0276, -0.0015, -0.2355, -0.0081, +0.3447, +0.3784, -0.5474, +0.1801, -0.1660, +0.3446, +0.4288, +0.2730, -0.1667, +0.3351, +0.1431, +0.3574, -0.8036, +0.2580, -0.0009, -0.2548, +0.2669, -0.0010, +0.2673, -0.0481, +0.2498, -0.1628, +0.0913, +0.3274, +0.1052, -0.1022, +0.4280, -0.1549, -0.4395, +0.1083, +0.3907, -0.2138, +0.2467, -0.8071, +0.2845, +0.2277, +0.0958, +0.1499, +0.0426, -1.0645, +0.2627, -1.0988, +0.0073, -0.2371, -0.1110, -0.0370, +0.1322, +0.1908, -0.0820, -0.0871, -0.0927, -0.2126, -0.1933, -0.5629, -0.0014, -0.1545, +0.4580, -0.1378, +0.0316, -0.5284, +0.1727, -0.1004, -0.2099, +0.0290, +0.1137, +0.0408, -0.1891, -0.2607, -0.5103, -0.0073, -0.3733, -0.2262, -0.5160, +0.2817, -0.1558, +0.0888, +0.3333, +0.6985, -0.2266, -0.3598, +0.1534, +0.2226, +0.2616, -1.3961, +0.2103, +0.2918, +0.1863, -0.1366, -0.0886, +0.0040, -0.1006, -0.2855, -0.3092, +0.0798, +0.0321, -0.0850, +0.1356, +0.1690, -0.0924, +0.1542, -0.1020, -0.4774, -0.2607, -0.0833, -0.1287, +0.0672, +0.2268, -0.1807, -0.0932],
-[ -0.2405, -0.3201, +0.7086, -0.1859, -0.1761, -0.2028, -0.2184, -0.1675, -0.1567, +0.0830, -0.6260, -0.0593, -0.4650, +0.2506, -0.0680, +0.4262, -0.2814, -0.5134, +0.0255, +0.1273, -0.2961, +0.1498, -0.3338, +0.0174, -0.2212, +0.3174, -0.1205, +0.4797, +0.0533, -0.0115, +0.2920, +0.2266, -0.1898, +0.1149, -0.1576, -0.2620, +0.1099, -0.3745, -0.0760, +0.0467, -0.3250, +0.1586, +0.0099, -0.2494, -0.7048, -0.4182, +0.5150, +0.5745, -0.1478, -0.2727, -0.2478, -0.2406, -0.2523, +0.1856, -0.0971, -0.6087, -0.0432, -0.9908, +0.1931, -0.1341, +0.2256, +0.3962, +0.7869, +0.0154, -0.2696, -0.0954, -0.3696, -0.0110, -0.1052, -0.0975, +0.1781, +0.1258, -0.0776, +0.0353, -0.2180, +0.1670, -0.0379, +0.3439, +0.0207, -0.1833, +0.2566, -0.0464, +0.2096, +0.4449, +0.0416, +0.1547, +0.3403, +0.0345, +0.4687, -0.2652, -0.0801, -0.0020, +0.2610, -0.1122, +0.3909, +0.0769, -0.4641, +0.0736, -0.1571, -0.3774, +0.2008, +0.0973, +0.0370, +0.2582, +0.1885, -0.1066, -0.2197, -0.4079, -0.0710, -0.4423, -0.4312, -0.0751, -0.1196, +0.3101, -0.0285, +0.5479, -0.1970, -0.2913, -0.4369, +0.5454, -0.6903, -0.8019, +0.0506, -0.1360, +0.0087, +0.0290, -0.2148, -0.1939],
-[ -0.4610, -0.2473, -0.0072, +0.1139, -0.0247, -0.0270, +0.1747, +0.2458, +0.0063, -0.0531, -0.0759, +0.0047, +0.0364, -0.5022, -0.1617, -0.7361, -0.6447, -0.2081, +0.2924, +0.2775, -0.2411, -0.0804, +0.0894, +0.2635, +0.5808, +0.0442, +0.0549, +0.3769, -0.2544, +0.1273, +0.2322, -0.0005, +0.0571, -0.2578, -0.3183, -0.0808, -0.0843, -0.4059, +0.5397, +0.4067, +0.1236, +0.0372, -0.0280, +0.3330, -0.0433, -0.6466, +0.1857, -0.0144, -0.3054, +0.4676, +0.0957, -0.0832, +0.0522, +0.1565, +0.1035, -0.1486, -0.0411, +0.1708, -0.6490, +0.2695, -1.4983, -0.0924, +0.0861, -0.3205, +0.1533, -0.5704, -0.1770, +0.0457, -0.2784, +0.1999, -0.5306, -0.3039, +0.0315, -0.0714, -0.2366, +0.2338, -0.0119, -0.1229, -0.4881, -0.1953, -0.0109, +0.3970, +0.0111, +0.0094, +0.2245, -0.3690, -0.2375, -0.5421, +0.3655, -0.1213, -0.1289, +0.4099, -0.2984, +0.2335, -1.0059, +0.3213, -0.1308, +0.0610, -0.4671, +0.1776, -0.2169, +0.0928, +0.4206, +0.0827, -0.0566, -0.1113, -0.2543, +0.0759, +0.2825, +0.0447, -0.4559, -0.0657, +0.1503, +0.0488, -0.2538, -0.1964, +0.1072, -0.1280, +0.6441, -0.4528, +0.3117, +0.2581, -0.4013, -0.0773, -0.0911, -0.3778, +0.0242, +0.0215],
-[ -0.3375, -0.5719, -0.6334, -0.0649, -0.0854, +0.0065, +0.0112, -0.8870, +0.3573, +0.4600, +0.1725, -0.0770, -0.3685, -0.0545, -0.5765, +0.0273, -0.1385, +0.2495, +0.2816, +0.2096, -0.1360, -1.0331, +0.0761, -0.2855, -0.0729, -0.2590, -0.1185, -0.2533, +0.1765, -0.4079, +0.2194, -0.5630, +0.2157, +0.2393, +0.1017, -0.7140, +0.0217, -0.4780, +0.1821, +0.2813, -0.3911, -0.3134, +0.0405, -0.0632, -0.1073, -0.1237, -0.2487, +0.6443, +0.2270, -0.2456, -0.1470, -0.4370, -0.2383, +0.1560, +0.1944, -0.4339, +0.1600, +0.2022, +0.0125, -0.9087, -0.2564, -0.1490, -0.3016, -0.3584, -0.4661, -0.1902, -0.7473, +0.2934, +0.5054, -0.0753, +0.3913, +0.2743, -0.0716, -0.0532, -0.1229, +0.3036, +0.0937, -0.6381, +0.3031, +0.0587, -0.3400, -0.0665, +0.0558, +0.1511, +0.1622, +0.1003, -0.2812, -0.1361, -0.2708, +0.2619, -0.0755, -0.3061, -0.1715, +0.0845, +0.0100, +0.0034, -0.5785, +0.1349, -0.1744, -0.2035, +0.4662, +0.1399, -0.3066, -0.4236, -0.0472, -0.2843, -0.2385, -0.5794, +0.1820, +0.3557, -0.0862, +0.3738, +0.1450, +0.1000, +0.5473, +0.1507, -0.5443, +0.0914, -0.3537, +0.3741, -0.1891, +0.3546, +0.3191, -0.5246, +0.4230, -0.5878, -0.1751, -0.0542],
-[ +0.0213, -0.1471, +0.3261, -0.4587, -0.1803, +0.3454, -0.4453, -0.3145, -0.3858, -0.2512, -0.1947, -0.1724, +0.0583, +0.0332, +0.3049, -0.2802, -0.1356, -0.1136, -0.2123, +0.5089, +0.2820, -0.1252, +0.0767, +0.0704, -0.4895, +0.2362, -0.1172, +0.0923, +0.1067, +0.3615, -0.0697, +0.2067, -0.5127, +0.0913, -0.3579, +0.2358, -0.3798, +0.0920, +0.1841, -0.2430, -0.0443, -0.0572, +0.0997, +0.1046, +0.1505, +0.4334, +0.0064, +0.1389, -0.1436, -0.1635, +0.0277, -0.1091, -0.0032, +0.2427, +0.2126, +0.1951, -0.1043, -0.4167, +0.0660, +0.3166, -0.0735, +0.4281, -0.0680, +0.2983, +0.2509, +0.0579, -0.1808, +0.2992, +0.4224, +0.1334, -0.3825, +0.2144, -0.3767, +0.0435, +0.2921, +0.3553, -0.6511, -0.4253, +0.0686, -0.3102, -0.0320, +0.1272, -0.0162, +0.3658, -0.0617, +0.2804, +0.0475, +0.2362, -0.3137, -0.3116, -0.0363, -0.0645, -0.3065, -0.0121, -0.1316, -0.1926, +0.2697, -0.3122, -0.1086, -0.2185, +0.0241, +0.1630, +0.1691, -0.2266, +0.0638, -0.3642, +0.0405, +0.0430, -0.3574, -0.2212, -0.1512, +0.2038, -0.5828, -0.2209, -0.0242, +0.2462, +0.1717, -0.0077, -0.0030, -0.0895, +0.1574, +0.4435, -0.0056, -0.1508, +0.2267, -0.9727, +0.0261, -0.1215],
-[ -0.3160, -0.1400, +0.4377, -0.3019, +0.3067, +0.2706, -0.0765, -0.0643, +0.2614, -0.2829, -0.0770, -0.4608, +0.0010, -0.7371, +0.1481, +0.0234, +0.2131, +0.5582, -0.5795, -0.1648, -0.3535, +0.2181, -0.3191, +0.0782, +0.0203, -0.1470, -0.3755, -0.2801, +0.4999, +0.1431, +0.3485, -0.0319, -0.2214, -0.5425, -0.4827, +0.0720, +0.0499, +0.0915, +0.1852, +0.4811, -0.2475, +0.3030, +0.1523, -0.8120, +0.1666, -0.1881, -0.2929, -1.0035, +0.1171, -0.1081, -0.2652, +0.2682, +0.2016, -0.1875, +0.1921, +0.1625, -0.2025, -0.6555, -0.4698, -0.6763, -0.0720, +0.0744, +0.0735, -0.2397, -0.7100, -0.0878, -0.2742, -0.0971, +0.3277, -0.0065, -0.1009, -0.2990, +0.0095, -0.1290, +0.1047, +0.2795, -0.0224, -0.1167, +0.1958, +0.0617, +0.0240, -0.1795, -0.1911, -0.3702, -0.1098, +0.0642, -0.1415, +0.2290, +0.2341, -0.1400, -0.3408, -0.1841, +0.0148, +0.1168, +0.3008, -0.3096, +0.1196, -0.4468, +0.1721, +0.1640, -0.0977, -0.0530, +0.0229, +0.1476, -0.1028, -0.1261, -0.1420, +0.1022, +0.3167, -0.6265, +0.1797, -0.0936, +0.0511, -0.1893, -0.0957, +0.6811, +0.1573, -0.2752, +0.1701, -0.2201, -0.5291, -0.2507, +0.3921, -0.1902, +0.0837, -0.0864, +0.2542, -0.3904],
-[ +0.3549, -0.3863, +0.0507, +0.2643, -0.5068, +0.0091, -0.1987, +0.2044, +0.1588, -0.1687, +0.3042, -0.2765, -0.1975, +0.3145, -0.3224, +0.0269, +0.1342, +0.1690, -0.3698, +0.0475, +0.2741, +0.1402, -0.3399, +0.1895, -0.3704, +0.0448, -0.6119, -0.4312, -0.1161, +0.1789, -0.2738, -0.0005, -0.1235, -0.1129, -0.1537, -0.4127, +0.3147, -0.4615, -0.1564, +0.1232, -0.0074, +0.4090, +0.1535, +0.1611, -0.0459, +0.0316, -0.0453, +0.2114, +0.2703, -0.1030, +0.2373, -0.1695, +0.1394, +0.2881, +0.1062, +0.2914, -0.0610, -0.0085, -0.2375, -0.0314, -0.0266, +0.0097, -0.1276, +0.2307, +0.3851, -0.0813, +0.0323, +0.3472, -0.1466, -0.0722, -0.2811, +0.1014, +0.1024, -0.0211, +0.1074, -0.0008, -0.1776, +0.2776, -0.2850, +0.1980, +0.3691, -0.0283, +0.1396, +0.1274, -0.1716, -0.1685, -0.4215, +0.0225, +0.0786, -0.1001, +0.4591, -0.0575, -0.3971, +0.1456, -0.2183, +0.0558, -0.0271, +0.3083, +0.0568, +0.2462, -0.1597, -0.0232, +0.1730, -0.3045, +0.0611, -0.0139, +0.0820, +0.1426, +0.2030, +0.1218, -0.0595, -0.0221, -0.1941, -0.2436, +0.0602, +0.3822, -0.0739, +0.3550, -0.2108, -0.1007, +0.0043, -0.1852, +0.0749, -0.1664, +0.1066, -0.0244, +0.1905, -0.0022],
-[ -0.4225, +0.0205, +0.2343, +0.6412, -0.1847, -0.3596, +0.0700, -0.0939, -0.0499, -0.0930, -0.0358, -0.8865, -0.0728, -0.0062, -0.0464, -0.0181, +0.2364, -0.0239, +0.5704, -0.0628, -0.1030, -0.4086, +0.5106, +0.1740, +0.0949, -0.1879, +0.1340, -0.0541, +0.3082, -0.0291, +0.3116, +0.0689, -0.1211, -0.1224, +0.0628, -0.4648, +0.2210, +0.0961, -0.2342, +0.0106, +0.0186, +0.0873, -1.5674, +0.2819, -0.2889, -0.2208, -0.5178, +0.4684, +0.0253, -0.4241, +0.1826, -0.1348, +0.2715, +0.2436, +0.2658, +0.2304, +0.1359, -0.0806, -0.5793, +0.3441, +0.2264, -0.2614, -0.1882, -0.3382, +0.1948, +0.4520, -0.9745, +0.1227, -0.3187, +0.1561, +0.1611, -0.2133, -0.1997, -0.4954, -0.2462, +0.1609, +0.1442, +0.1312, +0.1740, -0.3870, -0.4074, -0.3078, -0.0300, +0.2480, +0.2126, +0.2092, -0.8827, -0.5479, +0.1335, -0.3101, -0.0703, +0.0903, -0.2329, -0.1830, +0.4569, -1.1144, -0.0159, +0.6270, +0.1413, +0.3254, -0.0640, -0.9923, -0.2731, -0.8292, +0.3298, -0.3924, -0.2309, +0.2209, -0.1428, +0.1210, +0.3638, +0.0533, -0.2677, -0.4959, +0.0251, -0.2504, -0.0507, -0.0921, +0.1597, +0.1228, +0.0347, +0.1019, -0.0810, -0.1491, +0.0628, +0.2191, -0.4947, +0.0954],
-[ +0.1637, +0.0948, -0.4648, +0.3582, +0.0854, +0.0058, +0.1979, -0.5683, +0.2024, +0.6277, -0.1446, +0.1466, -0.3083, -0.0088, +0.2004, -0.5835, -0.0979, -0.4047, +0.1741, +0.2211, -0.1131, -0.9463, -0.0805, +0.2657, +0.1303, +0.3516, +0.1750, +0.1509, +0.2827, +0.0082, -0.0395, -0.2700, -0.9032, +0.0319, +0.1324, +0.1078, -0.5541, +0.7263, +0.3923, -0.0758, -0.7597, -0.5127, +0.1942, -0.2357, -0.5484, -0.1027, +0.3685, -0.3620, +0.3254, -0.2113, -0.8554, +0.4961, +0.1886, +0.2338, +0.1664, -0.5808, -0.0672, +0.1681, +0.1266, +0.0296, -1.1437, -1.3080, -0.7877, -0.2797, +0.0179, -0.3475, +0.2645, +0.2776, +0.2837, +0.3169, +0.2472, -0.0013, -0.1141, -0.0726, -0.1195, +0.2691, -1.2304, -0.3329, -0.7756, +0.3802, -0.1996, +0.2079, -0.1404, +0.2316, +0.4997, +0.1979, +0.1014, +0.0706, -0.3750, -0.8870, +0.1731, +0.3022, -0.2311, -0.2704, -0.1208, -0.1827, -0.9557, +0.1715, -0.3653, +0.2939, -0.6981, +0.2919, -0.4313, -0.3437, -0.0768, +0.0977, -0.3232, -0.3931, -0.2694, -0.2122, -0.0491, -0.3902, +0.2010, -0.4833, -0.4078, -0.0292, -0.0444, -0.3722, -0.1701, -0.0076, -0.7189, -0.1509, -0.0553, -0.9382, -0.0043, -0.5509, -0.0923, +0.0345],
-[ +0.1160, -0.2954, -0.3315, -0.1049, -0.1665, -0.6713, +0.2705, +0.2416, -0.1831, -0.4300, +0.1659, +0.0535, -0.3640, +0.4983, +0.1289, +0.1666, -0.3206, -0.0546, +0.1964, -0.0279, +0.0947, +0.0797, -0.3268, +0.1590, -0.2458, +0.0288, +0.2251, -0.3009, -0.1476, +0.2927, +0.1510, -0.0044, -0.3690, +0.3700, +0.2042, -0.3515, -0.4181, +0.0056, -0.0933, -0.4424, +0.3104, -0.0206, -0.7065, +0.4244, +0.0692, +0.0821, -0.0387, +0.0745, +0.1301, -0.1519, -0.0195, +0.0234, +0.1581, +0.2883, +0.0212, -0.4560, -0.5068, -0.5831, +0.4690, -0.1566, -0.0208, +0.1124, +0.0008, -0.3741, -0.2130, -0.2332, -0.3150, +0.0841, -0.0527, -0.1880, -0.0400, -0.1145, +0.2574, +0.1251, -1.0734, -0.2387, -0.1422, -0.2481, +0.0069, +0.0068, +0.0484, -0.0377, +0.3183, -0.2792, +0.2541, -0.2930, -0.0113, -0.1120, +0.0407, -0.0675, -1.0289, +0.2839, +0.2054, +0.0621, -0.1725, -0.6597, +0.2531, -0.1362, -0.1612, +0.2407, -0.2504, +0.0369, +0.2115, -0.4549, -0.1791, +0.1713, -0.2896, -0.1486, +0.2133, +0.0461, -0.3307, +0.0050, -0.4137, +0.2785, -0.4291, -0.0957, +0.2633, -0.0458, -0.0116, +0.2395, +0.0834, -0.1063, -0.5765, -0.1646, -0.0355, -0.6641, -0.4030, +0.1182],
-[ -0.1603, +0.1595, -0.8431, -0.6778, +0.1075, -0.2351, -0.1148, +0.0481, +0.0980, +0.1509, -0.4538, -0.6482, +0.3181, -0.7497, -0.6013, +0.1111, +0.0616, -0.1351, -0.0651, +0.3321, -0.0197, -0.1127, -0.0341, +0.3115, -0.3223, +0.0818, +0.1163, -0.0377, +0.1245, -0.3289, -0.0432, +0.1208, -0.1961, +0.0422, -0.0774, -0.0120, -0.3441, +0.5444, -0.2227, +0.0064, -0.4028, -0.0151, -0.3354, +0.3311, -0.0559, +0.0867, +0.4502, +0.0128, +0.0003, -0.1244, +0.7798, +0.5170, -0.0804, +0.6044, -0.3152, +0.0484, -0.1151, +0.5629, -0.6603, -0.2273, -0.1492, -0.2242, -0.0485, -0.5484, -0.2776, -0.5286, -0.0948, +0.0538, -0.1728, -0.2477, +0.0368, -0.0486, -0.1006, +0.0436, -0.1171, +0.5106, +0.2599, -0.2541, -0.3214, +0.0887, +0.1058, -0.0414, +0.7731, +0.4503, -0.3084, -0.3069, -0.8430, -0.2717, +0.0244, -0.0623, +0.4468, -0.0700, -0.6146, -0.4785, +0.1428, +0.0444, +0.8492, +0.0297, +0.1108, -0.1313, -0.2234, +0.0726, +0.1076, -0.1348, +0.2932, -0.8258, +0.1431, -0.2649, +0.3067, +0.1376, +0.4508, +0.1335, +0.4536, +0.1607, +0.4285, -0.0105, +0.1935, +0.0985, -0.4130, -0.3155, -0.9062, -0.3534, +0.1880, -0.5299, -0.3446, -0.2847, -0.5438, +0.2116],
-[ +0.5761, -0.3813, -0.3865, +0.1568, -0.1607, -0.2502, +0.0219, -0.8582, -0.5226, +0.5144, -0.1524, +0.0812, -0.4727, -0.3335, -0.1110, +0.3647, +0.0783, -0.5708, -0.3820, -0.3120, -0.3096, -0.0256, -0.4717, +0.1317, +0.5989, +0.4897, -0.0469, +0.0568, -0.2580, -0.2221, -0.4452, -0.2594, -0.9505, +0.4975, -0.5212, +0.2497, -0.0509, +0.1511, -0.6159, +0.0438, -0.1114, +0.2150, -0.0859, +0.2133, -0.0728, -0.3740, -0.4002, +0.4732, +0.4738, +0.5238, -0.0480, -0.2455, -0.0934, -0.2782, -0.2165, -0.1058, -0.0855, +0.5160, -0.1801, +0.0536, +0.3633, -0.2925, -0.7053, +0.0379, +0.2051, -0.0552, -0.7254, +0.1808, -0.8717, -0.2988, -0.3500, -0.4196, -0.1360, -0.3550, +0.3361, -0.4210, -0.1077, -0.4150, +0.3904, -0.2485, -0.3365, +0.2199, -0.6205, +0.1837, -0.1190, -0.3000, -0.3884, +0.2614, +0.0790, -0.0139, -0.3965, +0.3965, -0.4885, +0.4306, +0.1003, -0.0760, +0.4036, +0.0463, +0.3266, -0.2110, -0.5959, -0.4129, -0.0650, +0.3431, -0.6494, +0.2506, -0.3991, -0.1680, -0.1170, -0.0935, +0.0483, -0.0313, +0.1041, -0.5254, -0.1478, -0.0523, +0.0539, +0.0581, -0.3135, +0.4106, -0.0569, -0.1274, -0.7759, -0.1341, +0.1121, -0.2227, -0.3384, +0.2073],
-[ -0.0015, -0.0050, +0.0626, -0.2167, -0.1618, -0.1563, +0.0808, +0.3984, +0.3761, -0.7672, -0.0743, +0.1242, +0.2863, +0.0726, +0.2476, -0.2723, -0.0107, +0.0697, -0.2586, +0.0376, -0.5399, -0.5003, +0.2620, +0.0800, -0.1510, -0.3301, -0.0241, +0.2990, -0.3245, +0.4816, +0.1996, +0.1130, -0.8881, +0.3102, +0.0306, +0.0916, -0.5965, -0.4686, +0.0940, +0.0700, -0.4971, +0.3605, +0.0462, -0.3902, +0.1146, -0.5735, -0.6344, -0.9496, -0.5057, -0.1810, -0.0559, -0.2218, -0.0443, -0.2366, +0.0693, -0.4752, +0.1593, -0.3631, +0.3647, +0.1596, +0.1076, -0.1984, -0.4186, +0.3248, +0.1609, +0.2158, +0.1010, +0.2301, +0.1915, -0.1493, -0.8783, +0.0871, -0.1188, -0.2275, -0.0359, +0.3421, +0.0802, -0.6345, -0.1397, -0.1732, +0.0109, -0.1552, -1.1050, +0.0960, +0.2679, +0.0425, +0.3679, -0.4878, +0.4553, -0.8658, +0.0454, -0.6804, -0.1970, -0.4404, -0.0434, -0.3961, -0.1004, +0.2561, -0.4153, +0.1440, -0.0352, +0.4118, -0.2326, -0.0680, +0.0416, -0.2793, +0.2123, +0.1383, -0.1678, +0.1839, -0.2010, +0.2858, -0.3092, +0.2992, -0.2234, -0.2068, +0.1857, -0.2247, +0.1250, +0.0474, +0.1694, -0.3829, -0.3199, -0.0096, -0.0066, -0.4101, +0.2096, +0.1492],
-[ -1.0530, -0.1616, +0.1781, -0.2967, -0.3292, -0.1714, -0.1484, +0.0427, +0.3548, -0.0519, -0.2956, -0.8272, +0.0106, +0.5496, -0.5411, -0.0851, +0.2586, -0.2523, +0.0898, -0.3291, -0.4361, +0.2933, -0.3067, -0.1003, +0.4732, +0.3920, +0.2250, +0.2445, +0.2729, +0.6164, +0.1556, -0.6162, +0.1678, +0.1554, -0.0462, -1.0487, -0.0951, +0.0250, -0.0550, -0.0011, -0.0247, -0.4949, +0.3541, +0.2239, -0.3604, +0.2358, -0.9694, -0.5448, -0.6723, -0.5508, -0.0862, -0.5063, -0.2174, -0.2356, -0.2273, +0.0797, -0.3075, -0.0495, +0.1235, -0.1639, -0.3079, -0.1264, -0.4438, +0.3899, -0.1129, -0.5128, -0.6813, -0.1342, -0.1244, +0.0879, +0.5020, +0.0280, +0.3070, +0.2640, -0.4427, +0.1822, +0.0034, +0.2847, -0.2542, -0.4012, +0.0463, -0.4115, -0.5966, -0.3262, -0.0476, -0.5559, -0.2575, +0.2801, -0.2403, +0.2426, -0.1122, -0.0639, -0.0933, +0.3127, -0.4744, -0.1973, -0.7071, -0.2202, -1.0998, -0.1894, -0.2028, -0.2228, -0.1441, -0.4315, -0.8790, +0.1403, -0.3170, -0.1493, -0.3308, -0.5001, +0.2890, -0.4068, -0.1283, -0.4281, +0.2751, +0.1483, +0.4841, -0.3758, +0.4211, -0.1636, -0.0437, -0.1343, -1.0156, +0.2221, +0.1052, -0.5406, -0.4152, +0.0602],
-[ -0.2308, -0.2978, +0.0745, -0.2628, -0.3429, -0.0427, +0.0573, +0.1858, -0.2774, -0.2777, -0.0013, -0.1791, +0.0037, -0.0213, +0.0925, -0.0212, -0.2492, +0.0183, +0.3678, -0.0179, -0.0583, +0.0586, -0.0014, +0.1517, +0.3286, +0.6509, +0.2159, -0.3924, +0.0795, +0.2268, -0.1243, +0.2543, -0.0295, +0.0129, -0.0151, +0.1521, -0.5144, +0.1643, -0.5641, +0.0363, +0.4261, +0.0787, -0.0144, +0.2405, +0.1561, +0.1014, -0.0883, -0.1637, +0.1274, +0.0933, -0.2461, -0.2536, +0.2394, +0.4473, -0.3484, +0.1002, -0.3076, +0.0268, +0.0668, -0.0877, -0.2816, -0.6566, +0.1330, -0.3667, +0.3127, -0.1171, +0.2557, +0.3192, +0.3922, +0.2430, -0.8649, -0.3526, +0.4035, -0.0499, +0.1406, +0.1930, -0.1427, +0.1748, +0.1786, +0.0764, +0.3115, +0.2849, -0.0117, +0.0284, +0.1940, -0.5640, +0.2338, +0.2769, -0.2405, -0.4534, -0.4668, -0.0395, +0.2209, +0.0711, -0.0354, +0.4161, -0.0014, -0.2474, -0.1787, +0.2895, +0.2003, +0.0210, +0.1707, -0.1632, -0.1909, -0.0915, -0.2660, +0.0307, +0.0622, +0.0725, +0.3364, -0.0440, -0.0147, -0.4324, -0.4612, +0.2892, -0.0327, +0.0708, -0.2288, -0.6771, +0.1125, +0.4182, -0.4915, -0.2478, +0.1810, -0.4989, -0.3241, -0.0827],
-[ +0.0611, +0.2865, -0.1639, -0.5949, -0.6014, -0.0413, +0.4919, -0.1920, +0.1659, -0.4057, -0.0116, +0.1717, -1.8083, +0.3695, +0.1806, -0.4881, +0.5887, -1.2683, -0.1151, -0.5173, +0.2263, +0.2536, +0.2895, -0.4869, -0.1181, +0.0537, +0.2262, +0.1881, -0.1279, -0.7002, -0.3557, -0.0005, -0.2306, -0.8433, -0.0015, -0.1687, +0.2881, +0.0146, -1.0380, +0.0755, +0.3358, +0.1864, -0.3233, +0.3758, -0.1901, +0.0065, -0.3992, -0.3306, +0.1113, -0.2037, -0.1552, -0.3460, +0.3272, -0.2249, -0.8292, -0.1383, -0.2892, -0.1736, -0.3339, +0.0082, -0.5588, -0.0003, -1.3892, +0.1160, -0.3565, -0.0793, -0.3037, +0.1453, -0.2012, +0.1600, -0.0894, +0.1147, -0.2503, -1.0418, -0.1991, +0.0348, -0.6366, +0.1861, +0.0672, -0.4284, -0.0243, +0.1470, -1.0503, -0.4545, +0.1642, +0.5413, -0.2965, +0.4746, +0.0497, -0.0846, +0.3373, +0.1835, -0.3656, -0.9899, -0.7913, +0.2604, -0.4761, -0.3113, -0.3797, +0.0733, +0.0392, +0.0518, -0.3743, -0.1053, -0.2166, +0.0327, +0.0788, +0.2358, -0.1864, -0.4050, +0.1921, -0.8714, -0.6943, -0.1009, -0.2309, +0.0990, +0.0303, -0.2281, -0.6570, +0.1796, -0.2536, -0.7205, +0.0996, +0.1210, -0.2807, -0.0518, -0.1800, +0.1282],
-[ -0.7158, -0.0248, -0.1820, -1.0689, -0.8583, +0.1329, -0.2660, +0.0176, +0.0568, +0.3375, +0.2250, -0.0206, -0.4120, -0.8021, +0.2371, +0.1026, -0.3022, -0.1062, -0.1898, +0.0673, -0.1232, +0.2277, -0.0368, -0.0241, -0.1203, -0.3597, -0.2682, -0.0838, +0.1016, +0.0101, +0.1256, +0.0478, -0.5503, -0.0960, -0.6214, -0.3078, -0.1974, -0.4763, -0.4231, -0.8695, -0.2724, +0.1457, +0.1207, -0.3700, -0.0486, +0.1690, -0.0181, -0.2192, -0.0046, -0.3685, -0.0330, +0.2796, +0.1762, -0.2772, -0.0359, -0.2993, -0.1015, -0.1635, +0.2030, -0.1603, +0.2134, -0.1556, -0.5028, -0.4694, +0.3322, -0.0483, -0.7822, -0.8137, -0.7079, +0.0925, +0.1491, -0.1615, +0.3602, -0.5017, -0.0455, +0.1418, -0.0643, -0.2456, -0.1544, -0.3930, -0.7707, -0.1255, -0.5566, +0.3966, -0.1460, +0.0126, +0.0630, -0.1355, +0.0769, +0.2010, -0.6037, -0.2071, -0.1490, +0.2603, -0.0213, +0.0620, +0.1688, +0.1827, +0.4220, +0.3981, +0.2312, -0.3357, -0.1231, +0.1700, -0.1651, +0.0388, -0.1009, -0.2646, +0.1996, -0.3023, +0.1891, -0.4615, -0.3505, +0.1069, -0.1581, -0.0312, -0.8901, +0.0545, -0.6672, -0.5027, +0.2211, +0.1013, -0.7583, -0.1434, -0.6627, -0.2156, +0.2614, +0.3662],
-[ -0.2563, -0.0474, -0.2365, -0.1934, -0.3914, -0.0048, -0.2730, -0.2007, -0.1603, -0.2423, -0.5630, -0.3473, +0.0258, -0.9864, +0.4544, -0.4950, +0.0337, -0.0502, +0.2225, -0.7403, -0.9425, -0.4985, -0.1403, +0.0626, +0.3485, +0.2418, -0.0540, -0.7098, +0.0510, +0.0277, +0.1600, -0.1689, -0.1595, +0.1059, -0.0557, +0.0532, -0.0278, -0.5567, -0.2592, -0.5742, -1.0013, +0.1918, -0.0463, +0.1362, -0.1924, +0.3461, -0.5660, +0.1042, +0.0646, -0.1462, -0.3421, +0.2529, +0.0525, -0.2629, -0.1130, -0.6224, -0.2830, +0.3472, +0.3616, -0.1641, -0.5444, -0.3770, +0.4742, -0.3860, -0.5951, -0.1638, -0.7594, +0.1544, -0.2297, -0.5665, -0.4948, +0.2582, -0.1000, -0.1965, +0.0185, +0.1803, +0.5790, -1.2134, -0.1435, +0.2652, -0.1434, -0.3791, +0.3301, -0.7856, +0.2785, -1.0229, +0.0838, -0.2758, -0.3962, -0.4106, -0.6214, -0.1216, +0.0602, +0.0587, +0.0879, -0.9288, -0.1678, -0.5674, +0.1685, -0.4010, -0.0188, -0.1108, -0.1286, -0.1027, +0.4474, -0.5951, +0.6017, -0.6050, -0.0316, -0.1669, -0.1520, -0.0173, -0.6195, -0.0047, -0.5535, +0.2926, -0.2384, +0.1254, -0.4349, +0.1235, -0.5216, -0.7084, -0.1835, -0.1166, -0.5433, -1.7441, +0.1094, +0.0133],
-[ -0.1527, +0.2050, +0.0983, -0.1605, -0.1750, -0.1275, +0.0175, -0.4205, -0.2100, +0.0893, +0.2032, +0.0399, -0.4218, +0.0874, -0.6308, +0.2939, +0.0782, +0.0255, +0.0107, -0.2254, -0.9162, +0.2254, -0.3521, +0.2638, -0.1499, -0.1506, -0.2354, +0.2721, +0.5795, -0.3090, +0.1415, -0.3314, +0.0392, -0.5504, +0.1330, -0.2533, -0.0513, -0.5682, +0.1356, -0.7459, -0.7628, -0.0834, -0.3449, +0.3160, +0.0946, +0.3228, +0.0644, +0.1491, +0.0060, -0.3167, -0.3146, -0.8460, -0.3023, +0.2308, +0.1187, -0.5089, +0.0434, -0.0090, -0.5630, +0.0231, +0.1602, -0.2552, -0.5270, -0.7234, +0.5465, -0.4352, -0.7148, -0.3853, +0.4611, +0.4006, -0.6137, +0.4332, -0.2807, +0.0564, +0.1006, -0.2015, -0.0501, -0.1992, +0.0239, -0.0428, -0.2136, +0.0181, +0.0028, -0.2133, +0.4164, +0.0994, +0.1958, +0.0943, -0.3896, -0.1137, -0.0743, -0.0451, +0.0772, -0.2562, +0.3917, -0.2452, +0.5537, -0.0203, +0.3696, +0.1016, -0.3851, -0.0034, -0.3018, -0.4717, +0.1248, -0.0375, +0.0164, -0.2870, -0.2551, -0.3909, +0.2639, -0.5118, +0.2163, -0.1475, -0.2449, -0.1022, -0.3885, -1.1527, +0.3727, +0.3782, +0.1173, +0.4259, -0.0340, -0.0485, +0.1656, +0.2814, +0.0839, -0.5007],
-[ +0.4765, -0.1649, -0.1024, +0.0055, -0.1214, +0.1782, -0.2572, -0.4435, -0.7717, -0.1426, -0.3608, -0.7833, +0.1269, -0.0235, +0.1364, +0.3735, -0.2381, -0.0663, -0.1387, -0.4519, -0.6952, -0.2574, +0.3000, -0.3859, -0.0087, -0.0432, -0.1001, -0.3128, -0.0270, -0.3285, -0.1081, +0.1883, -0.8374, -1.1177, +0.2704, +0.1830, +0.1482, +0.4163, +0.2134, -0.7739, +0.4174, -0.3978, -0.5230, +0.2132, -0.2400, -0.1015, +0.3938, +0.6610, -0.2333, -0.0563, +0.0737, -0.3698, -0.4550, -0.2412, +0.3110, +0.0754, -0.1881, -0.1304, -0.3407, +0.2422, -0.1928, -0.6068, -0.4171, -0.1750, -0.4661, +0.1497, -0.8435, +0.4782, -0.0119, +0.0284, -1.0337, -0.0165, -0.0950, +0.4089, -0.3840, -0.0563, -0.5054, +0.0379, +0.3352, -0.1341, +0.0938, -0.8643, -0.1014, +0.0840, -0.5156, -0.1637, +0.0072, +0.3067, -0.0884, -0.7413, +0.5943, -0.0905, -0.2211, -0.5878, +0.3823, -0.3302, -0.3392, -0.5429, +0.1319, -1.0519, +0.3625, +0.3302, -0.0129, -0.1716, -0.5146, -0.0158, -0.3191, -0.2978, +0.0817, +0.1130, +0.0154, +0.6382, -0.3736, +0.2939, +0.2334, +0.2609, +0.2365, +0.2562, +0.2581, +0.3822, -0.3219, +0.0573, +0.2748, -0.0081, +0.1287, -0.5954, -0.5557, +0.3334],
-[ -0.1244, -0.0739, -0.1773, -0.0051, -0.2568, +0.0253, -0.3943, +0.4885, -1.2380, +0.1550, -0.0180, +0.0387, -0.1563, -0.0694, +0.3956, -0.1860, +0.2417, -0.0104, +0.1181, -0.1433, -0.1424, -0.2395, +0.1543, +0.0020, +0.3424, -0.8965, +0.2261, -0.0223, -0.0491, -0.1797, -0.7054, +0.0414, +0.1474, -0.0349, -0.0832, -0.0827, +0.0572, +0.2952, -0.0980, -0.5059, -0.3756, -0.3521, +0.3812, -0.2648, +0.1227, +0.5788, -0.1290, +0.1006, -0.6027, +0.0324, -0.1361, +0.1538, +0.1624, -0.4140, -0.2818, +0.2475, -0.3697, +0.0158, +0.0414, -0.4090, +0.1862, +0.3428, +0.3250, -0.2630, +0.1261, +0.2009, +0.3502, -0.0755, -0.2826, +0.1526, -0.2166, -0.2248, -0.4648, -0.6940, +0.2055, -0.2284, -0.0808, -0.1773, +0.4859, -0.8962, -0.0136, -0.5233, -0.4861, -0.1999, -0.0792, +0.6809, -0.4605, -0.0301, +0.1620, -0.5748, -0.1882, +0.2918, +0.2180, -0.0636, -0.3878, -0.0864, +0.1710, +0.1606, -0.0546, -0.3337, -0.6139, +0.1103, +0.0151, +0.0350, +0.1895, +0.3184, +0.3794, +0.0449, -0.1940, +0.1791, -0.2073, +0.1471, -0.5927, +0.0492, +0.1733, -1.0351, -0.3525, +0.2772, -0.0317, -0.9995, -0.0498, -0.1881, +0.5443, +0.2347, +0.5254, -0.3914, -0.0550, -0.1160],
-[ -0.0967, +0.3455, -0.2238, +0.2009, +0.1764, +0.0967, -0.0590, +0.3214, -0.0303, -0.2983, -0.4011, -0.5049, -0.1646, -0.0277, -0.4578, +0.7766, +0.0177, -0.6196, -0.1869, -0.7060, -0.7281, -0.3773, +0.3006, +0.1190, -0.1093, -0.3381, +0.3843, +0.2368, -0.0337, -0.1140, -0.3126, -0.4312, +0.5474, -0.4514, +0.0049, +0.3787, -0.1660, +0.7759, -0.3546, +0.0536, -0.1700, +0.0265, -0.1812, -0.2721, +0.0742, -0.2028, -0.3201, +0.1234, -0.4013, +0.1645, -0.7290, -0.1574, -0.2551, -0.6970, -0.3877, -0.3200, +0.1977, -0.8099, -0.0750, -0.0673, -0.2181, -1.0244, -0.3877, +0.0909, -0.3593, -0.5187, -0.2553, +0.0355, -0.3642, +0.0107, +0.1705, +0.4053, -0.2568, +0.1740, -0.2911, -0.1625, +0.2549, +0.0840, +0.3694, -0.6590, -0.3594, -0.1929, +0.2237, -0.1976, +0.1534, -0.3068, +0.1278, +0.4571, -0.2539, +0.2164, -0.5471, -0.0529, +0.0369, +0.4208, -0.0814, +0.3714, -0.5938, -0.3710, +0.3114, +0.6259, +0.0059, +0.0130, -0.5826, +0.0877, -0.2332, +0.0354, -0.8047, +0.1317, -0.9597, +0.1143, -0.2499, +0.1294, -0.0472, -0.5513, +0.0643, +0.1936, -0.1909, +0.1698, +0.0858, -0.1199, -0.6053, +0.0864, +0.0556, -0.3210, -0.3413, +0.0078, +0.1152, -0.4971],
-[ -0.0527, -0.0277, -0.5070, +0.1096, +0.2826, +0.3327, -0.0866, +0.0629, -0.1437, +0.2578, +0.0404, -0.3073, +0.3690, -0.3613, -0.2037, -0.5715, -0.1269, +0.1994, -0.0578, -0.1329, -0.0046, -0.6498, -0.1521, -0.2816, -0.1446, -0.0221, +0.0810, -0.3729, +0.4460, +0.6792, +0.1963, -0.0118, -0.3029, -1.0091, -0.5706, +0.1085, -0.6219, -0.3816, -0.8965, +0.4163, -0.0812, -0.1559, +0.0440, -0.2807, -1.0406, -0.2695, -0.0474, -0.1721, +0.2909, +0.2715, -1.6228, -0.3200, -0.1958, +0.0388, +0.1530, -0.9646, +0.2767, +0.4320, -0.1137, -0.6233, +0.1335, -0.2247, +0.4663, +0.0214, -0.2247, +0.3232, -0.7008, +0.4906, +0.3080, -0.0374, -0.6051, +0.2417, -0.3725, +0.4420, +0.2252, -0.3977, -0.4043, +0.1437, +0.5895, -0.9664, -0.1180, +0.5082, +0.0914, +0.3361, -0.7208, -0.5858, -0.5050, -0.0817, +0.2920, +0.0912, +0.4496, -0.2410, -0.3415, +0.1653, -0.1557, +0.7604, -0.5723, -0.5638, -0.3500, -0.8521, -0.2054, +0.0974, +0.2551, -0.2385, -0.0929, -0.0650, -0.0434, -0.3776, +0.4589, +0.2075, -0.4577, -0.0888, +0.0540, -0.3768, -0.3778, -1.2187, -0.2733, -0.3868, -0.5227, +0.5560, +0.1831, +0.1179, -0.4877, -0.1921, -0.2940, -0.1083, +0.1321, +0.0658],
-[ +0.0851, +0.1237, +0.3079, -0.3762, -0.2870, +0.1797, +0.1528, +0.1408, -0.0854, +0.2107, -0.0888, +0.1461, +0.0396, +0.0078, +0.2542, -0.0276, +0.1926, +0.0659, -0.1361, +0.0434, +0.3480, -0.0129, -0.0772, +0.0886, -0.0437, -0.0188, -0.4141, +0.1342, -0.2803, -0.0198, -0.2619, +0.0503, -0.3024, -0.1624, -0.0729, +0.0999, +0.2488, -0.5538, -0.5757, +0.0182, +0.1508, +0.0242, +0.1205, +0.0480, +0.0230, +0.0396, +0.5233, -0.4589, +0.3359, -0.2505, +0.0021, +0.1641, -0.1351, -0.2552, -0.2580, +0.0780, -0.2114, -0.0661, +0.1573, -0.0167, +0.4415, -0.1601, +0.1631, +0.2454, -0.1081, +0.0016, -0.4957, -0.0726, +0.0853, +0.2539, -0.4234, -0.0471, +0.2212, -0.2625, +0.1045, +0.1269, +0.1261, +0.1722, +0.1526, -0.1199, -0.1990, -0.3317, -0.3490, -0.1991, -0.8123, -0.1331, -0.2023, -0.4781, -0.0670, +0.1621, -0.4527, -0.0136, -0.5296, +0.1699, -0.2776, -0.4615, +0.0328, +0.3221, +0.0832, +0.0988, +0.0501, +0.0616, -0.1198, +0.0369, -0.2673, +0.1644, -0.1164, -0.7414, +0.2164, -0.2900, -0.2164, +0.1668, -0.2093, +0.0993, -0.1886, -0.3224, -0.3970, +0.1618, -0.2486, -0.5561, -0.2513, +0.0465, -0.0900, +0.0689, -0.3624, -0.5229, +0.0975, -0.1538],
-[ -0.2350, -0.0645, -0.3615, -0.0227, -0.5530, +0.1408, -0.0817, -0.2408, -0.1138, -0.1513, +0.3608, +0.4338, -0.1659, +0.6428, -0.0378, +0.3013, -0.1392, -0.3619, -0.8423, +0.3682, +0.3757, -0.0121, +0.4504, +0.0619, -0.6040, -0.6458, -0.5900, -0.1712, +0.4316, +0.0350, +0.3142, -0.7079, +0.0091, +0.4126, -0.4210, -0.0609, -0.1032, -0.3058, -0.1821, +0.3230, -0.3882, -0.9278, +0.0894, -0.0269, -0.6832, -0.7596, +0.3437, -0.7062, -0.6884, -0.2122, -0.0652, +0.1604, -0.0175, +0.3662, +0.4354, +0.3192, -0.2377, +0.1625, +0.1337, +0.0469, -0.0486, +0.2694, -0.5156, +0.0278, +0.2552, -0.4929, -0.9727, -0.1039, -0.1098, -1.2475, +0.1701, -0.2273, -0.7669, -0.5180, +0.1835, +0.1097, -0.4413, -0.4020, -0.3054, -0.3705, -0.8869, +0.2093, -0.3340, -0.1148, -0.3528, -0.1682, -0.1487, -0.4372, -0.4378, +0.1359, -0.0848, -0.7216, -0.6878, -0.2174, -0.4028, -0.2557, +0.0784, -0.1654, -0.1174, +0.3619, -0.1810, -0.0099, -1.1576, -0.0002, -1.0263, -0.3744, +0.2061, -0.8543, -0.8111, -0.4431, +0.1512, +0.2831, +0.1916, +0.4312, +0.5064, +0.0385, -0.0675, -0.1375, +0.2126, +0.0130, +0.4966, +0.2362, +0.0904, -0.7148, +0.0392, -0.1645, +0.1844, -0.7697],
-[ +0.0220, -0.0428, +0.0276, +0.3503, +0.2144, -0.1321, +0.3869, -0.1202, -0.1374, +0.0744, -0.4690, -0.1239, -1.0280, +0.3670, -0.1420, -0.1227, +0.1930, -0.1847, +0.3942, +0.2043, -0.5067, -0.1962, -0.6377, -0.3575, -0.0448, +0.1373, +0.0288, +0.3011, -0.0772, +0.0266, -0.2126, +0.4098, +0.0688, +0.2684, +0.0468, -0.7170, +0.5634, -0.1395, +0.4975, -0.1992, +0.0157, -0.3145, +0.1247, -0.2183, +0.1947, -0.0192, +0.0535, -0.2897, +0.2576, -0.0970, +0.0374, +0.1809, -0.2987, -0.1980, -0.0604, -0.2548, +0.3602, -0.0131, +0.2217, -0.4366, +0.3172, -0.4558, +0.3201, -0.6872, +0.1945, +0.1090, +0.0402, +0.0382, -0.1878, -0.1224, -0.0817, +0.1835, -0.9401, +0.0475, -0.0883, +0.2037, -0.0891, +0.1447, -0.2684, +0.1187, +0.2925, +0.0545, -0.6845, +0.1526, -0.1610, -0.2451, +0.0026, +0.1057, +0.0704, +0.1843, -0.2590, -0.0985, -0.2079, -0.7211, +0.0775, +0.2452, -0.3347, +0.2375, -0.0090, -0.2547, +0.1042, -0.0516, -0.0689, +0.3129, +0.1685, +0.0748, -0.2181, -0.3170, -0.1933, -0.0852, +0.5291, +0.0392, -0.0554, -0.1644, -0.2692, -0.2711, +0.1414, +0.2713, -0.4879, +0.0969, -0.1078, -0.0405, -0.4846, -0.1335, +0.0573, +0.0358, +0.1098, -0.1402],
-[ -0.1117, +0.1986, -0.7761, -0.3040, +0.3357, -0.3474, +0.1743, +0.1902, +0.3739, -0.2314, +0.0653, -0.1791, -0.2269, -0.5653, +0.2996, +0.1259, -0.2694, +0.2773, -0.1439, -0.1760, -0.1470, -0.2581, -0.4101, +0.0351, -0.3246, +0.2160, +0.1913, +0.2079, +0.2030, -0.0556, +0.3580, +0.0021, +0.1484, +0.2643, +0.1736, -0.2415, +0.0955, +0.0201, -0.0134, -0.0322, +0.3084, -0.4807, +0.1081, -0.5020, +0.2811, +0.0917, -0.2092, +0.0043, +0.1168, +0.4111, -0.0706, -0.2049, +0.0966, -0.2413, -0.0175, +0.3128, -0.3217, -0.5673, -0.1846, -0.2971, -0.1817, -0.2797, -0.3498, +0.0397, +0.3490, +0.0587, +0.0955, -0.1578, -0.4743, +0.1826, +0.4050, +0.3482, +0.1023, +0.0652, -0.1641, -0.2173, -0.4869, +0.0762, -0.0708, +0.2776, +0.0441, +0.3667, -0.5101, -0.5287, -0.2622, -0.2233, +0.1004, +0.2117, +0.1264, -0.0336, +0.0162, +0.4209, +0.3222, +0.3265, -0.3533, +0.1657, -0.3463, -0.7502, -0.2849, +0.1964, +0.2663, +0.1315, -0.0235, -0.1738, -0.3701, +0.1235, -0.3071, -0.1384, +0.1270, +0.5121, +0.2657, -0.4361, -0.0806, +0.3179, +0.2078, +0.1773, -0.0158, +0.4612, -0.0097, +0.0344, +0.4431, -0.0293, +0.2263, -0.3492, +0.0373, +0.3111, -0.3341, +0.3314],
-[ -0.2234, +0.3046, +0.0611, -0.2822, +0.0183, +0.0652, -0.4832, +0.2223, -0.1448, +0.0276, +0.1012, +0.3600, -0.1284, -0.6043, -1.2978, -0.8725, -0.0866, +0.1470, +0.4283, +0.0699, +0.0635, +0.5191, -0.0263, +0.0685, -0.0539, +0.3351, -0.1752, +0.3458, -0.4523, -0.2304, -0.1956, -0.0134, -0.1779, -0.1767, -0.1972, -0.1104, -0.0667, -0.2914, -0.9693, +0.2018, +0.0919, -0.3138, +0.0910, +0.2717, +0.1102, +0.0138, -0.5037, +0.0832, +0.0590, -0.3267, -0.0313, +0.1724, -0.3492, +0.2826, -0.0482, +0.0152, +0.1023, -0.7773, -0.0515, -0.2389, +0.0211, -0.0255, -0.0368, +0.5986, +0.0725, -0.2325, -0.5902, -0.1262, -0.0356, +0.1307, -0.4985, -0.1194, -0.1714, +0.0975, -0.3656, +0.3823, +0.0281, +0.0863, -0.1686, -0.2519, +0.2029, -0.0693, +0.0241, +0.4671, -0.0035, +0.1302, -0.6907, -0.2194, +0.1807, -0.7022, -0.1678, -0.0593, -1.0474, -0.3847, -0.3561, +0.0089, +0.3198, +0.1647, +0.1293, +0.0437, +0.2253, -0.0569, +0.3280, -0.3060, +0.3071, -0.0946, +0.2558, +0.1250, -0.3373, -0.7435, +0.0748, -0.1516, -0.1449, +0.2877, -0.1991, +0.0102, +0.2082, +0.3499, -0.3268, +0.1190, +0.3183, +0.0166, +0.3925, +0.3659, -1.3411, +0.3606, -0.0859, +0.1691],
-[ -0.4373, +0.5870, -0.2470, -0.4369, -0.5017, -0.7323, -1.2199, -0.2451, -0.2447, -0.1360, +0.2145, -0.4427, -0.3696, +0.1239, +0.3161, -0.1466, +0.0734, -0.0463, +0.0277, -0.3268, -0.1238, +0.0240, +0.0479, -0.0531, -0.3103, +0.4964, +0.0494, -0.0860, -0.5420, -0.1102, -0.5141, +0.2544, +0.0141, +0.1847, -0.3437, +0.2420, -0.0345, -0.1352, -0.2411, +0.0601, -0.1543, +0.2220, -0.0458, -0.0342, +0.0031, +0.3370, -0.0459, -0.3162, +0.3164, -0.2459, -0.3363, +0.0468, -0.0645, +0.5785, -1.0524, +0.0431, -0.2120, -0.1114, +0.1165, -0.0978, +0.0010, +0.1229, +0.0559, -0.4454, +0.6569, -0.1128, +0.0485, -0.3288, -0.1035, -0.1959, -0.6063, +0.2157, -0.1107, -0.0526, -0.0856, -0.6510, +0.1339, +0.5464, -0.2989, +0.5216, -1.2263, -0.0108, +0.2021, -0.1379, +0.7368, -0.3330, -0.1118, +0.0816, -0.3946, -0.7703, +0.1186, +0.0387, -0.2798, -0.4680, -0.1312, +0.5733, +0.0175, -0.8109, -0.7925, +0.2221, -0.3326, +0.1711, -0.3284, +0.5274, -0.6371, +0.3497, -0.2010, +0.3155, -0.2545, -0.1489, +0.3425, +0.1253, +0.4334, -0.4114, +0.0696, +0.1568, -0.1666, +0.3577, +0.0306, -0.6268, -0.6966, -1.0236, -0.4172, -0.5622, -0.1003, -0.5679, +0.1524, -0.3371],
-[ -0.2767, +0.0972, -0.5547, -0.2201, -0.1170, -0.1576, -0.1602, +0.1382, -0.0808, +0.2028, -0.3989, +0.0158, -0.1357, -0.3024, -0.2257, -1.2166, -0.2502, -0.5230, -0.4460, -0.1411, -0.1846, -0.4805, -0.0032, -0.4232, -0.4742, -0.5456, -0.1574, -0.3298, +0.0333, -0.0440, -0.2283, +0.0253, -1.1936, +0.2652, -0.0474, -0.0169, -0.0632, +0.3591, -0.2793, +0.0314, -0.6320, -0.8212, -0.1199, -0.3018, +0.1836, -0.1475, -0.8715, -0.3799, +0.1702, -0.2543, -0.5776, -0.0772, +0.3332, +0.2767, -0.2859, +0.2075, -0.7332, +0.4793, -1.5267, +0.1474, -0.2003, +0.0032, -0.0866, -0.4733, -0.2157, -0.5489, -0.8860, +0.0229, -0.3014, +0.0358, -0.0763, -0.0744, +0.0927, -0.5832, +0.2188, +0.1248, -0.2539, -0.6919, -0.0873, -0.4554, +0.0821, +0.2124, +0.0322, -0.0390, -0.2129, +0.2774, +0.2383, -0.2737, -0.2540, -0.8198, +0.1893, -0.2351, -0.0728, +0.4741, -0.4950, -0.3812, +0.1700, -0.8968, +0.0391, +0.3027, -0.0014, +0.0654, -0.2479, +0.0851, +0.1058, +0.4011, -0.0536, -0.6038, -0.2781, -0.0519, +0.2117, -0.4242, -0.4415, -0.3171, +0.1510, -0.0039, -0.4738, -0.1233, -1.2393, -0.0213, -0.1457, +0.0515, -0.2666, +0.0735, +0.3065, -0.2219, -0.3103, +0.1352],
-[ -0.1894, -0.3178, -0.2146, -0.0917, -0.3281, +0.3759, -0.3827, +0.2162, -0.2736, -0.5178, +0.1408, -0.1238, -0.0214, -0.0124, -0.3949, -0.3133, -0.1027, +0.0348, +0.2293, -0.1680, -0.6537, -0.2278, -0.2112, +0.2586, +0.1426, +0.0794, +0.0601, +0.1368, -0.2424, +0.1392, +0.0391, +0.1776, +0.3126, -0.4101, +0.1359, +0.2845, +0.2675, +0.1771, -0.1543, -0.3432, +0.1683, +0.2882, -0.1131, -0.1933, +0.1945, -0.3527, -0.2665, -0.0031, -0.8195, +0.0226, +0.0603, -0.0813, +0.2884, -0.1688, -0.1183, +0.3030, +0.2942, +0.2613, +0.0640, +0.1961, +0.0728, -0.1439, -0.3157, -0.0657, +0.1147, +0.2127, -0.5807, -0.3566, +0.2828, -0.3506, +0.0159, -0.3167, +0.1337, +0.1766, +0.2469, -0.0833, +0.2147, -0.1919, +0.2639, -0.0558, -0.4039, +0.1532, -0.2222, +0.2294, -0.1847, +0.1543, +0.0267, +0.3783, +0.4722, +0.1427, +0.2415, +0.4090, -0.4329, -0.2182, -0.1861, +0.4997, +0.0788, -0.5247, +0.1604, -0.1814, -0.3566, +0.2227, -0.0276, -0.1325, -0.4941, -0.2409, +0.1634, +0.2456, +0.3919, +0.1564, -0.3376, -0.0926, -0.0169, +0.0950, -0.1314, +0.0283, -0.3400, -0.4327, +0.0396, -0.1139, -0.0001, +0.0763, -0.4060, +0.3790, -0.1646, -0.7353, +0.0369, -0.0515],
-[ -0.2086, -0.1809, -0.0925, -0.3050, -0.2023, -0.3849, +0.0063, +0.3838, -0.0679, -0.4047, +0.1106, -0.2605, -0.1714, -0.0836, +0.3509, -0.1618, -0.6817, -0.5073, +0.0951, +0.0166, -0.0730, -0.3489, +0.4669, +0.0451, +0.0663, +0.3284, -0.0380, -0.3944, -0.4299, -0.1957, -0.6752, +0.1119, -0.4006, +0.0351, +0.0977, +0.3906, +0.3201, -0.3789, +0.4969, +0.0857, -1.0318, -0.0316, +0.0653, +0.1053, -0.4342, -0.5321, +0.2690, +0.2056, +0.2295, -0.0461, -0.1716, -0.9352, +0.0156, +0.0124, -0.4358, -0.0842, -0.1229, +0.5391, -0.3714, -0.0735, -0.2581, -0.2032, -0.3048, -0.4434, -0.3753, +0.4077, +0.4080, +0.0238, +0.0651, +0.1965, +0.5052, -0.2532, +0.1327, -0.5991, -0.3155, +0.1131, -0.3228, -0.1098, -0.4889, -0.3557, +0.0582, -0.8156, +0.0351, +0.0854, +0.1539, -0.0416, +0.0878, +0.5755, -0.1741, +0.3042, +0.3049, -0.1249, -0.0155, -0.0495, -0.1473, -0.0890, +0.0657, -0.4408, -0.2135, +0.1564, +0.1787, -0.3268, -0.1219, +0.1648, +0.3581, -0.0800, -0.4765, +0.2241, -0.3060, +0.1448, -0.6599, +0.1232, -0.5561, +0.2646, -0.1117, -0.0416, -0.2256, -0.0567, +0.2988, -0.1756, -0.2153, -0.2089, -0.1916, -0.1445, +0.4029, +0.5686, -0.8428, -0.3141],
-[ +0.4546, -0.2401, -0.8765, +0.1447, -0.3474, +0.2069, +0.0291, -0.3461, -0.5166, -0.2007, +0.2375, +0.0309, +0.1591, +0.2316, -0.3278, +0.0879, -0.1175, +0.1829, -0.3574, -0.0183, +0.0943, -0.8221, -0.0635, +0.1241, +0.2995, -0.4990, -0.1297, -0.0750, +0.0564, +0.3013, -0.3528, -0.0187, -0.6252, -0.0760, -0.0297, -0.3231, +0.2837, +0.0155, -0.1604, -0.0188, -0.0737, +0.1051, +0.2268, -0.8192, +0.0854, -0.4684, -0.0896, -0.1865, -0.2881, +0.2112, +0.1710, +0.1251, -0.1999, -0.2006, +0.0150, +0.2386, -0.2525, -0.2776, +0.0791, -0.1655, +0.2221, -0.6359, -0.4413, +0.0507, +0.0245, -0.1480, +0.0307, -0.4909, -0.2057, -0.5612, -0.2967, +0.0754, +0.0988, -0.4456, +0.4071, -0.3079, -0.5466, +0.1572, -0.0346, -0.5972, -0.1862, +0.0957, -0.8404, +0.3361, -0.0397, +0.1259, -0.0430, +0.4487, -0.1305, -0.0816, -0.4018, +0.0301, +0.0845, -0.3938, +0.0034, -0.1890, +0.1008, -0.2038, -0.0580, +0.0037, -0.3044, -0.2627, +0.2022, +0.0591, -0.0465, -0.3806, +0.5580, +0.0273, +0.3072, -0.0389, -0.3435, -0.2277, +0.1378, -0.0317, -0.0693, +0.2321, +0.4751, -0.1210, +0.2986, +0.1641, +0.0845, +0.1088, -0.0719, +0.0558, -0.0499, +0.1624, +0.3028, -0.0444],
-[ +0.3694, -0.0619, -0.0750, -0.4331, -0.4578, -0.2562, -0.2689, +0.2755, -0.2460, -0.0051, -0.7781, -1.0708, +0.2076, +0.3512, +0.2633, -0.0265, -0.3566, -0.2862, -0.6983, -0.1114, +0.1958, +0.0863, -0.6004, +0.1575, +0.3171, -0.1933, +0.0496, +0.6272, +0.0932, +0.2021, +0.1328, -0.5198, -0.6713, -0.0838, -0.3921, -0.2568, -0.3613, -0.1204, +0.0601, -0.6830, +0.4960, -0.2160, -0.0535, -0.3319, -0.3293, +0.2971, +0.3285, -0.0228, +0.0649, -0.4740, +0.7016, -0.4892, -0.2840, +0.2251, -0.2327, -0.8171, +0.4519, -0.1815, -0.1825, -0.7546, -0.5589, -0.1238, -0.1216, +0.0837, -0.2976, -1.7269, -1.0251, +0.1344, +0.4895, +0.1124, +0.0124, -0.6756, -0.1620, +0.1031, -0.2471, -0.6356, +0.5671, +0.4402, -0.5158, +0.0154, -0.2029, +0.3559, +0.4752, +0.4763, -0.0111, -0.0330, -0.1440, -0.5386, -0.0265, -0.8968, +0.1154, -0.2805, -0.3890, -0.5239, -0.0655, -0.3710, -0.1921, -0.2713, +0.3029, -0.0201, +0.0902, +0.0504, -0.2419, +0.3148, +0.7004, +0.0841, +0.5304, -0.1880, +0.2689, +0.0060, -0.7380, +0.2010, -0.0502, -0.4943, -0.0261, +0.1489, -0.6708, -0.1913, -0.7632, +0.0502, -0.3367, +0.1165, +0.0408, +0.1340, -0.4637, -0.4536, -0.9485, -0.3013],
-[ -0.1725, -0.1858, +0.0331, +0.3456, -0.1368, +0.2509, +0.2902, -0.2707, +0.3620, -0.4504, +0.2074, -0.3254, -0.3116, +0.1972, -0.2880, -1.5750, +0.1065, +0.2296, -0.3981, -0.6005, -0.0860, -0.1587, +0.1138, -0.0057, +0.1169, +0.1022, +0.0771, -0.5353, +0.2160, +0.2135, +0.0991, -0.0715, -0.2361, -0.5277, -0.3601, +0.1271, -0.8232, -0.9594, -0.1746, +0.2128, -1.2460, +0.0310, -0.3488, +0.0794, -0.8006, -0.0880, +0.2133, +0.1811, -0.1658, -0.1150, -0.9967, +0.0063, +0.0494, -0.8586, -0.2293, -0.2535, +0.0954, +0.3826, -0.7305, -0.5031, -0.1241, -0.4392, -0.9065, -0.0479, -0.2143, -0.5246, -0.2355, -0.4192, -0.0020, -0.1630, +0.0590, -0.1096, -0.0354, +0.1383, -0.4181, -0.1156, -0.9471, -0.5348, -0.0057, -0.9101, -0.0550, -0.8399, +0.2349, +0.0682, +0.1741, +0.3622, -0.2623, -0.3513, +0.1216, -0.1540, +0.0167, +0.0928, +0.2289, -0.5268, -0.5032, -0.5759, -0.2395, +0.1103, -0.2771, -0.3320, -0.1327, +0.0540, -0.1549, +0.5291, -0.0706, +0.0489, -0.3762, +0.0153, -0.0167, -0.4286, -0.6423, +0.8254, +0.0893, -0.5137, -0.0482, -0.1103, +0.0620, -0.0734, -0.2348, -0.2156, -0.4396, +0.8179, -0.1603, -0.0299, -0.6343, -0.8946, -0.3538, -0.3519],
-[ -0.2354, -0.0994, -0.0970, -0.1210, -0.5758, +0.2825, +0.0853, -0.0817, +0.3374, +0.3253, -0.1718, +0.2518, -0.1108, -0.4627, +0.1909, +0.0746, -0.1913, -0.4916, -0.1558, -0.2477, +0.2525, -0.0559, +0.0598, +0.0704, -0.1778, +0.2072, -0.1712, -0.0083, -0.2989, -0.1084, +0.0435, -0.2145, +0.0225, +0.6034, +0.1502, +0.1591, -0.3021, -1.0728, -0.5351, +0.0799, +0.1981, -0.0034, +0.6635, -0.2042, -0.0471, +0.2838, +0.1760, -0.4701, +0.4796, +0.1516, +0.0430, +0.6459, +0.0252, -0.3035, -0.6315, -0.1916, -0.2847, -0.6922, +0.2426, -0.2787, +0.1770, +0.1493, -0.4729, +0.3312, -0.8047, -0.3841, +0.4028, -0.1849, +0.0628, +0.1960, +0.1757, -0.1554, -0.1836, -0.2858, +0.2676, +0.2611, +0.0566, -0.9536, -0.0094, +0.0276, -0.0257, -0.1097, +0.0644, +0.1793, +0.0124, +0.0730, -0.1807, +0.0420, -0.2505, +0.2622, +0.1184, -0.5243, +0.2392, -0.2308, +0.1152, -0.2640, -0.3274, -0.0795, +0.3790, +0.3166, +0.0136, -0.4956, -0.1574, +0.2242, -0.0071, +0.1597, -0.1925, -0.3563, -0.0431, +0.4689, -0.5352, +0.1372, +0.0079, -0.4182, +0.0542, +0.0660, +0.1484, -0.0518, +0.3963, -0.1329, -0.9245, -0.2170, +0.8141, -0.2753, +0.1995, -0.8927, +0.2048, -0.9033],
-[ +0.1385, +0.2524, +0.2341, -0.0525, +0.0286, -0.1349, +0.1474, +0.1847, -0.0895, -0.2732, -0.0785, -0.3748, +0.4309, -0.1217, -0.1987, +0.1887, -0.1932, +0.0054, +0.0628, +0.3407, +0.3116, -0.1444, +0.0419, -0.1252, +0.2750, +0.1297, +0.0635, -0.2700, +0.3252, -0.4535, +0.1030, +0.0394, -0.4224, -0.1120, -0.3679, +0.0162, -0.2485, -0.2971, -0.0216, +0.1285, -0.2827, +0.0020, -0.0438, +0.0292, +0.1771, +0.1373, -0.0630, -0.4031, -0.1995, -0.0976, +0.1109, +0.2382, -0.1350, -0.0708, -0.3023, +0.0379, +0.2145, -0.2867, -0.5431, -0.0735, -0.3522, -0.4424, -0.4257, -0.7687, -0.1674, +0.3218, -0.2861, -0.5267, -0.1729, -0.4813, -0.4816, -0.4595, -0.2712, -0.2190, +0.2677, -0.1222, -0.3066, -0.1060, +0.2256, -0.0821, +0.0364, -0.5062, +0.0821, +0.1147, +0.1934, -0.4142, -0.1493, +0.2036, -0.3093, -0.0189, -0.2693, +0.2322, +0.1105, -0.3197, +0.2832, -0.1993, -0.2103, -0.6401, -0.2555, +0.1762, +0.1250, -0.1426, +0.0233, -0.0284, -0.0694, +0.2206, -0.0664, +0.3228, +0.1130, -0.2081, +0.1334, +0.0279, -0.2022, +0.3889, +0.1545, -0.3145, -0.6417, -0.2156, -0.0909, +0.1342, -0.0219, -0.5034, -0.4547, +0.0030, +0.2268, -0.6860, +0.0075, +0.1278],
-[ -0.2374, +0.0805, +0.2663, +0.1124, +0.0258, -0.3193, +0.3090, -0.0598, +0.3276, +0.0092, -0.5305, -0.0264, -0.1383, -0.3224, -0.0795, -1.0162, -0.1734, +0.0706, +0.3049, -0.4068, +0.1737, -0.7058, +0.2571, +0.1217, -0.2815, -0.5398, +0.1680, -0.3644, -0.5849, +0.1535, -0.2410, -0.0299, +0.4319, -0.4040, +0.1864, -0.4186, +0.1141, -0.0188, -0.8473, -0.4871, +0.0764, -0.6763, -0.4378, -0.3592, +0.1187, +0.4060, -0.2282, -0.0395, +0.1306, -0.0833, -0.3435, +0.0764, -0.5312, -0.0791, +0.1757, +0.0578, -0.5238, -0.0140, -0.5122, -0.2480, -0.7816, -0.6827, -0.5802, +0.1869, +0.2833, +0.2551, -0.6782, -0.1467, -0.3754, -0.0426, +0.5844, -0.3302, -0.5216, -0.1696, +0.3585, +0.1013, -0.0017, +0.1690, -0.0158, +0.1443, -0.0728, -0.2636, +0.0779, -0.3160, +0.0778, -0.0808, +0.0080, -0.0362, -0.2650, +0.0755, -0.0979, +0.3609, -0.3260, +0.0995, -0.3250, -0.4137, -0.2061, -0.5269, -0.1452, +0.2401, -0.2095, +0.0808, -0.2633, +0.0889, +0.2723, -0.3161, +0.1089, +0.2698, -0.3279, +0.2626, -0.0076, -0.2605, +0.2754, +0.1855, +0.4763, -0.1059, +0.0752, +0.0249, +0.4125, -0.4099, -0.5385, -0.0468, +0.1375, +0.1461, -0.1498, +0.0242, -0.6608, +0.2718],
-[ +0.3181, -0.0578, +0.2270, +0.2960, +0.3759, -0.0994, -0.0301, +0.0580, +0.0580, -0.1176, -0.0211, -0.1902, +0.0512, -0.2255, -0.8401, +0.0308, -0.1803, +0.0669, -0.0963, +0.4547, -0.1982, -0.0926, +0.4024, +0.3177, -0.3376, -0.2049, +0.0444, -0.3649, +0.2239, -0.0188, -0.1576, +0.0524, +0.3666, -0.1009, +0.0668, +0.0819, -0.1313, +0.4450, -0.6085, -0.3848, -0.6414, +0.2856, -0.1182, +0.0912, +0.0397, -0.5215, +0.3353, -0.2102, -0.5109, +0.0882, +0.1674, +0.0885, -0.3224, +0.0901, +0.3159, +0.4244, -0.4800, +0.1526, +0.0061, +0.1857, -0.0979, -0.2406, +0.0730, +0.1405, -0.0050, +0.1824, -0.0160, -0.2087, -0.1628, -0.2413, +0.2396, +0.6054, -0.6268, -0.0734, -0.1073, -0.1242, +0.2214, -0.4174, -0.5380, +0.4581, +0.1509, -0.7234, -0.9114, -0.0332, -0.2386, -0.0100, -0.2586, -0.2640, +0.0461, +0.1833, +0.1354, -0.3236, +0.1699, +0.1157, -0.0966, -0.5738, +0.1736, -0.4470, -0.5721, +0.3542, +0.4103, -0.3574, +0.4307, +0.0229, -0.1325, +0.3490, -0.0651, +0.1874, -0.2291, +0.0530, +0.3738, +0.1955, +0.1027, +0.1591, +0.2077, +0.2210, +0.1001, -0.3243, +0.2351, -0.3068, -0.1417, -0.0853, -0.3813, -0.3430, +0.1111, -0.3707, -0.4524, +0.3608],
-[ +0.0381, -0.3280, -1.5348, -0.2310, +0.1609, +0.2576, -0.2199, +0.1194, +0.1368, +0.5134, -0.6136, +0.5420, -0.0032, +0.0184, +0.0213, -0.6279, -0.6801, +0.2122, -0.1931, +0.0708, -0.4318, -0.1370, -0.2482, -0.0169, -0.4338, -0.1085, +0.6117, -0.1325, -0.1302, +0.4041, +0.3929, -0.0002, +0.1998, +0.0515, -0.3162, +0.4465, -0.1745, -0.3913, -0.5087, -0.1100, -0.2249, -0.2461, -0.2671, +0.1915, +0.0139, +0.0838, -0.3395, -0.1856, +0.2210, -0.0315, +0.2527, -0.0433, -0.1347, +0.2930, -0.2082, +0.2286, +0.0255, -0.2495, -0.3158, -0.3498, +0.3091, -0.0525, -0.1256, -0.3423, -0.0553, -0.0529, +0.1197, -0.7197, +0.7501, +0.0290, -0.0370, -0.6256, +0.0000, +0.0983, -0.4345, +0.0663, +0.1609, +0.0146, +0.2122, +0.1216, +0.1759, +0.0309, -0.4094, +0.2527, +0.0841, +0.4982, -0.1519, -0.1223, +0.0607, -0.1248, +0.2532, +0.1901, +0.1263, -0.2375, -0.1312, -0.2293, -0.2532, +0.5176, -0.2599, -0.0855, -0.1362, -0.5210, +0.0224, +0.3870, +0.2114, +0.3244, +0.4654, -0.7012, -0.0922, -0.9771, -0.2505, +0.5230, -0.5313, -0.5063, -0.0315, -0.5956, +0.0800, -0.0199, -0.1976, -0.9358, -0.4071, -0.1917, +0.1467, -0.2294, -0.1170, +0.0695, +0.1403, -0.4278],
-[ +0.1029, +0.1445, +0.3256, -0.0877, +0.5028, -0.2229, -0.0061, +0.0184, -0.3173, -0.1645, +0.6963, -0.0568, -0.6695, -0.3263, -0.1246, -0.6652, -0.0307, -0.2701, -0.3961, +0.3665, -1.0864, +0.1994, +0.3494, +0.1447, +0.2856, +0.1528, +0.2521, +0.0676, -0.0895, -0.1963, +0.1029, -0.0675, +0.0657, -0.0773, -0.4179, +0.1854, -0.9043, -0.3480, +0.0186, -0.0853, -0.3580, -0.6232, +0.1994, -0.3973, +0.1558, -0.2424, -0.6349, +0.2492, +0.0654, -0.4719, -0.6174, +0.2362, -0.4908, -0.0194, -0.0402, -0.0680, -0.0284, -0.0382, -0.3183, +0.0208, -0.7145, +0.0223, +0.0710, -0.5593, +0.3360, -0.0591, -0.3271, -0.2059, +0.4912, +0.3903, -0.0288, +0.5235, +0.3245, +0.0820, -0.1104, +0.0020, -0.2973, -0.7333, +0.1925, -0.1251, +0.1177, +0.4494, +0.1400, -0.5209, -0.1851, +0.0925, +0.1926, +0.3427, -0.2087, +0.1852, -0.5303, -0.7136, -0.2598, -0.3725, +0.3738, +0.6966, -0.7630, -0.4744, +0.1341, -0.0536, -0.2411, +0.4594, +0.1060, +0.2383, -0.1521, -0.0214, -0.0980, +0.0557, +0.4497, +0.1257, +0.0278, -0.0656, -0.5980, -0.0110, +0.0955, +0.4506, -0.4515, +0.1015, +0.1491, +0.0256, +0.0409, -0.2116, -0.1528, +0.1721, +0.4331, -0.5740, -0.1334, -0.1490],
-[ +0.2384, +0.1767, +0.1947, +0.0587, +0.0436, -0.4647, +0.0460, -0.3978, +0.3851, -0.6429, -0.0757, +0.0771, +0.3342, -0.5142, -0.0504, -0.0614, +0.1761, +0.2849, -0.0273, -0.2299, -0.0279, -0.1199, -0.2008, +0.3238, +0.1584, +0.2584, +0.0005, -0.0247, +0.1486, -0.0961, -0.2141, +0.0457, +0.2077, -0.4971, +0.2886, -0.0251, +0.2316, -0.0343, +0.2933, +0.2489, +0.1717, +0.3198, +0.1717, -0.0490, +0.0506, -0.7074, -0.2308, -0.2186, +0.1620, +0.0328, +0.1614, +0.1332, -0.0487, -0.3712, -0.2751, -0.1583, +0.2474, +0.0419, -0.4341, -0.2045, +0.1139, -0.0188, -0.3290, -0.0657, +0.0096, -0.2058, -0.4276, -0.1128, -0.2121, +0.3103, -0.1906, +0.0304, +0.1177, -0.0511, +0.1057, -0.7063, +0.3458, -0.2067, -0.0213, +0.1076, +0.0151, -0.1120, -0.2189, +0.1475, -0.0077, -0.3843, -0.2418, -0.6991, +0.1953, -0.4116, -0.1400, +0.1521, -0.5215, -0.1150, -0.0251, +0.0277, -0.0684, -0.0070, +0.2457, +0.2435, -0.0386, -0.0929, -0.0177, -0.2300, +0.0347, +0.1269, -0.1599, +0.2427, -0.3234, +0.0156, -0.2406, -0.1611, -0.2369, +0.1289, -0.1268, -0.1186, -0.2554, +0.1911, +0.3922, -0.7103, -0.2174, -0.3823, +0.1010, +0.1203, +0.4065, -0.1545, +0.3333, -0.1270],
-[ +0.0320, +0.3374, -0.2328, -0.5468, +0.3057, +0.0867, +0.1920, +0.3238, +0.0958, +0.0865, -0.0978, -0.9149, +0.3992, -0.7304, -0.7107, +0.1157, +0.3527, +0.1362, -0.1631, -0.1291, -0.1038, +0.0851, +0.2969, -0.1787, -0.1327, -0.0016, -0.3977, -0.2473, -0.1113, -0.3001, +0.5036, -0.0856, +0.1597, -1.0896, +0.3766, +0.1266, +0.0147, -0.7126, +0.2683, -0.3971, -0.2376, +0.1728, +0.0654, +0.0889, -0.2988, +0.0767, +0.1215, -0.4817, -0.0649, -0.0350, -0.6930, -0.2363, -1.2543, -0.0226, -0.2209, +0.0390, +0.2717, -0.1385, -0.3073, -0.1550, -0.5586, -0.4812, +0.2852, -0.0278, -0.2483, +0.0254, +0.4223, -0.1026, -0.3841, -0.1561, +0.2930, +0.3772, -0.0625, -0.0882, +0.2467, +0.1206, -0.0632, +0.2479, -0.1358, +0.0352, -0.0730, +0.1995, +0.1430, +0.0082, -0.1685, -1.1753, -0.7206, -0.2929, -0.0186, -0.2444, +0.4176, -0.7420, -0.0811, +0.1876, -0.1151, +0.1599, -0.1971, -0.5971, -0.1488, +0.1225, +0.0460, -0.0519, -0.1219, -0.1250, -0.1093, -0.2462, -0.2120, +0.1604, +0.1361, +0.2755, +0.0633, +0.2230, +0.6084, +0.2955, +0.1139, +0.0836, -0.5077, +0.2327, +0.0441, -0.7536, -0.2307, +0.0111, +0.2659, -0.3169, -0.3589, -0.0047, -0.0293, -0.1917],
-[ +0.1849, +0.4786, +0.1204, -0.3298, +0.2282, +0.3278, -0.1501, -0.0854, -0.0439, -0.2816, -0.5327, +0.3156, +0.3149, -0.0344, -0.1886, -0.4860, -0.1034, +0.0903, +0.0569, +0.1075, +0.0721, +0.1677, -0.0501, +0.3348, -0.2958, -0.5643, -0.5416, -0.0616, +0.0486, -0.2416, +0.0556, -0.1499, -0.1884, +0.0063, -0.0879, +0.2615, +0.2102, -0.0322, +0.5728, -0.7324, -0.6729, -0.1240, -0.0435, -0.2956, +0.3191, -0.2177, -0.0368, -0.0261, -0.0666, -1.2822, -0.0419, -0.2362, -0.0318, +0.3002, +0.0324, -0.0798, +0.2130, +0.1350, +0.0346, +0.2781, +0.3518, +0.3837, -0.2617, -0.9864, -0.1951, +0.0896, +0.1452, -0.0149, -0.4673, -0.2097, +0.2540, -0.3603, -0.2436, -0.5239, +0.0675, -0.2038, -0.4511, -0.9040, +0.2373, +0.2649, -0.7154, -0.0777, -0.2655, +0.0074, -0.6301, +0.3651, -0.2757, +0.0316, -0.1454, -0.0407, -0.5047, -0.4833, -0.3325, +0.1745, +0.2487, +0.3029, +0.5754, +0.1331, +0.2339, -0.5040, -0.7949, +0.3252, -0.3651, -0.0125, -0.1580, +0.0285, -0.0523, -0.2012, -0.0764, -0.1872, +0.4235, -0.7683, +0.5005, +0.1516, -0.1920, +0.3039, -0.3789, -0.1149, -0.4491, +0.1532, -0.0276, -0.5430, -0.1058, +0.0728, -0.0873, -0.0693, -0.2627, -0.4874],
-[ +0.1766, +0.2027, +0.2184, -0.2155, +0.2002, -0.0767, +0.0247, +0.0769, +0.1097, -0.5324, +0.0716, -0.6547, +0.1549, -0.3553, -0.1583, -0.6442, +0.2656, -0.0242, -0.2430, +0.2241, +0.1981, +0.1088, +0.0831, -0.5510, +0.1084, -0.6368, +0.1111, -0.5365, -0.3738, +0.3743, -0.1497, +0.1148, -0.3921, +0.0518, -0.0321, -0.2311, +0.2755, -0.7492, -0.4376, -0.2182, -0.6939, -0.8483, -0.2843, -0.1963, -0.2650, -0.1096, -0.1861, +0.0298, +0.0037, +0.1153, -0.3358, -0.3163, +0.0478, -0.3209, -0.0710, +0.3083, -0.2630, -0.1924, -0.1803, -0.1369, -0.3061, -0.1886, -0.0521, -0.0039, -0.4548, -0.3571, +0.1289, +0.0565, -0.3850, -0.1660, +0.3697, +0.0093, +0.1096, -0.7151, -0.5122, -0.1048, -0.0407, +0.1807, -0.2780, -1.1252, -0.0171, -0.0800, -0.1387, -0.5066, -0.1341, -0.4523, +0.2285, +0.1949, +0.2985, -0.3676, -0.0402, +0.3106, -0.1804, -0.1138, -0.1518, +0.0386, -0.1846, +0.4102, +0.1630, -0.3054, +0.1310, -0.0050, +0.1931, +0.2023, -0.4601, -0.4869, -0.1454, -0.7915, -0.8167, -0.1141, -0.0829, -0.5105, -0.2998, +0.1506, +0.1659, -0.0161, +0.1262, -0.2265, -0.0906, -0.1643, -0.0997, -0.7213, -0.4537, -0.1466, -0.3031, -0.1776, -0.3410, +0.3465],
-[ -0.0680, -0.5316, -0.5061, -0.0773, -0.3060, -0.2216, -0.6029, -0.1825, -0.1359, +0.2300, +0.0623, +0.0920, +0.0022, -0.1120, -0.1106, -1.1256, +0.0279, -0.3801, +0.0112, +0.1688, +0.1709, -0.5387, -0.0696, -0.3568, -0.4497, +0.4913, -0.0399, -1.3545, -0.2932, +0.1045, +0.3458, -0.4757, -0.0703, -0.1544, -0.6656, +0.3997, -0.0279, +0.2120, -1.2224, -0.6230, -0.4677, -0.1049, +0.2119, -0.1797, -0.4644, -0.1679, +0.2749, -0.1451, -0.4456, +0.3104, -0.4102, +0.3043, +0.5440, -0.1511, +0.1171, +0.3151, -0.0670, -0.1808, -0.5695, -0.5017, +0.0862, -0.3984, +0.0258, -0.5704, +0.1754, -0.0489, +0.0302, +0.4248, -0.1910, -0.5007, -0.2559, -0.0414, -0.1863, +0.1481, -0.0454, -0.3999, +0.0606, +0.1871, +0.1180, -0.0014, -0.4116, -0.8299, +0.6789, +0.0242, -0.2057, -0.3620, +0.0898, +0.4069, +0.0505, +0.1478, -0.2953, -0.1294, +0.3536, -0.2027, -0.1965, +0.2124, -0.0305, -0.1242, +0.3511, +0.0112, -0.1523, -0.2483, +0.1767, +0.0946, -0.0883, -0.2642, -0.1009, -0.1412, -0.1936, -0.0337, -0.0854, +0.1496, +0.1209, +0.1613, -0.2123, -0.5184, -0.5626, -0.1087, -0.1012, -0.6158, -0.7041, -0.4685, -0.8154, +0.2760, -0.2103, -0.1968, +0.0849, -0.3954],
-[ +0.2532, +0.4208, -0.3291, -0.5551, -0.1859, -0.1518, -0.2786, +0.0658, -0.6929, -0.2819, -0.2395, +0.1718, +0.0343, +0.0182, +0.0734, -0.8299, -0.2525, +0.1285, +0.0562, -0.1593, -0.2454, -0.1303, -0.2009, -0.2577, +0.2121, -0.4224, -0.4803, -0.2205, +0.4951, -0.0603, -0.0738, -0.0561, +0.2528, -0.7239, +0.2362, -0.1281, -0.2817, -0.0915, -0.3098, -0.3482, -0.1657, +0.1685, +0.0365, -0.1210, -0.4351, +0.1768, -0.2815, -0.2552, -0.8653, +0.2226, +0.4609, -0.5362, -0.1000, -0.5827, -0.6283, -0.1828, -0.5187, -0.4818, -0.2862, -0.3698, -0.4264, +0.5897, +0.3011, +0.1451, +0.1300, -0.6738, +0.1766, +0.4159, -0.1141, +0.4150, -0.2877, -0.4758, +0.0208, +0.0290, -0.1260, -0.2702, -0.7108, -0.0338, +0.2733, +0.0843, -0.0556, -0.0368, +0.0105, -0.3436, +0.0248, -0.1892, -0.2123, -0.0928, +0.2068, -0.3971, +0.1089, +0.3620, -0.1929, -0.5377, -0.1463, -0.1753, -0.1031, -0.2935, +0.4052, +0.0367, +0.0097, -0.5875, +0.1436, -0.4216, -0.0872, -0.2351, -0.3716, -0.1434, -1.0513, +0.2828, -0.1845, +0.1664, -0.1173, +0.2712, +0.0878, -0.7084, -0.6339, -0.4937, +0.1035, -0.2160, -0.4060, -0.2531, -0.6691, +0.1202, +0.2531, -0.0490, +0.5874, +0.0633],
-[ -0.6739, +0.0277, -0.9564, -0.5067, -0.5287, +0.0684, -0.5332, -0.2934, +0.2182, +0.1192, -0.4239, -0.3156, -0.0208, +0.4953, -0.3716, -0.3657, -0.4834, -0.1870, -0.1509, -0.3200, -0.0222, +0.0546, +0.3764, +0.5946, -0.4095, +0.2046, -0.2208, +0.1072, -0.4266, -0.7344, -0.1398, -0.3482, +0.1835, +0.0850, -0.2169, -0.1673, +0.1917, -0.0598, -0.0835, +0.3213, -0.4629, +0.0055, -0.0855, -0.0968, -0.6663, -0.4341, -0.3010, -0.5688, +0.2849, +0.1352, -0.1461, +0.0679, +0.1243, +0.0837, +0.2299, +0.3890, +0.3232, +0.8568, -0.3093, +0.1023, -0.1423, -0.0950, +0.3483, -0.0398, -0.8729, +0.0589, -0.3755, -0.1726, -0.2203, -0.3867, -0.0227, -1.0963, -0.0057, +0.0516, -0.2886, +0.1596, +0.2880, +0.1165, +0.0612, +0.2892, -0.6804, +0.2979, +0.1742, -0.0116, +0.2316, -0.0595, +0.0568, -0.5258, -0.2719, -0.4404, +0.1292, +0.1016, +0.7038, -0.0262, +0.5274, -0.0229, +0.0430, +0.2201, +0.1085, -0.0375, +0.1192, -0.0778, +0.0535, -0.5996, +0.3843, -0.5089, +0.0677, -0.2134, -0.5909, +0.0015, -0.7516, +0.0565, +0.0375, -0.5614, -0.1333, +0.2093, -0.0427, -0.4205, -1.4405, +0.3511, -0.1710, -0.5402, -0.2186, -0.1229, -0.5740, -0.1826, -0.0947, -0.2646],
-[ -0.4790, -0.0459, -0.7397, -0.1887, -0.0117, -0.0881, -0.2339, +0.4489, -0.2226, -0.2678, -0.4339, -0.5233, -0.4704, -0.2454, -0.6791, +0.5416, +0.1632, +0.0939, +0.2976, +0.4227, -0.4494, -0.5834, -0.0442, +0.0945, -0.4829, -0.1668, +0.1462, -0.0841, +0.0265, -0.5589, +0.1268, +0.6885, +0.1927, -0.3751, +0.1673, +0.2637, +0.1409, -0.2660, +0.0257, -0.0269, -0.2051, +0.4255, -0.1496, +0.1084, -0.0217, -0.2359, -0.1428, -0.1115, -0.7085, -0.6233, -0.0985, -0.1075, -0.1553, -0.2027, +0.1923, +0.0471, +0.2331, -0.7869, -0.1220, +0.1538, +0.1171, -0.1364, +0.2306, -0.3217, -1.2153, -0.2076, -0.1103, -0.3231, -0.6678, -0.4851, -0.1963, -0.6715, -0.6025, +0.2298, -0.4343, -0.1760, -0.4037, -0.2442, +0.2234, -0.1880, +0.2596, -0.1924, -1.0538, +0.1892, -0.1999, -0.0033, -0.0755, +0.0571, -0.3725, +0.0816, -0.3538, -0.3673, -0.1607, -0.7918, +0.1611, +0.4097, -0.2851, +0.3155, +0.2837, -0.7129, +0.2556, -0.7155, -0.2264, -0.0045, +0.2039, -0.0958, -0.3221, +0.1626, -0.3246, -0.3097, -0.1555, -0.0424, -0.0175, +0.2186, -0.0899, -0.3513, -0.3811, -0.4246, -0.1244, -0.1209, +0.1675, -0.5267, -0.0279, +0.4418, +0.0478, +0.1246, +0.0393, -0.4219],
-[ -0.3571, +0.0904, -0.8551, +0.4132, -0.0919, +0.3857, +0.2689, +0.2051, +0.1931, -0.3377, -0.3208, -0.0723, -0.1699, +0.0462, -0.1263, +0.0483, +0.1950, -0.1277, +0.0313, +0.2242, +0.0103, -0.2061, +0.0631, +0.1930, -0.0647, -0.4123, +0.1690, +0.1474, +0.1182, -0.5403, +0.3640, +0.0169, +0.3996, +0.2360, +0.2264, +0.0977, -0.4711, +0.3267, -0.2800, -0.4045, -0.0261, -0.0814, -0.1084, +0.0173, +0.0070, -0.1826, +0.1416, -0.3700, +0.1904, +0.3461, -0.8709, +0.2058, -0.0601, -0.1735, -0.1307, -0.0786, -0.0667, +0.0989, -0.1120, +0.5435, +0.2793, +0.3009, -0.1373, +0.1923, +0.3372, -0.0255, -0.4204, +0.0504, +0.2350, +0.1833, -0.0786, -0.2449, -0.0600, -0.1826, -0.6286, -0.0817, -0.2410, +0.1011, +0.2879, -0.7720, +0.0685, -0.5338, -1.0387, -0.2374, +0.0941, +0.2234, +0.1887, -0.6712, +0.0789, +0.0920, -0.1733, +0.2348, +0.3533, +0.5173, -0.2887, +0.1298, -1.0297, -0.0811, +0.3376, +0.4740, -0.3197, -0.1907, -0.1645, -0.5704, -0.1747, +0.1463, +0.3165, +0.3489, -0.0581, -0.2501, +0.1131, -0.1146, -0.2154, -0.1804, -0.2339, -0.2814, -0.5182, -0.3433, +0.3677, +0.2729, -0.1904, -0.0585, -0.7208, +0.3472, -0.0146, +0.2520, -0.2723, -0.5874],
-[ -0.5168, -0.1916, +0.0044, -0.2001, -0.4914, -0.2367, +0.1037, -0.3593, -0.2739, +0.0966, -0.4070, -0.6904, -0.6564, +0.0903, -0.2040, +0.4127, -0.4820, +0.1590, +0.1689, -0.6444, +0.2427, +0.0580, -0.2541, -0.0060, +0.1797, -0.7206, +0.0552, -0.2466, +0.0206, +0.4403, +0.2936, -0.4458, +0.1578, -0.2735, +0.1138, +0.3035, +0.3536, -0.0996, -0.1689, -0.0803, +0.0302, -0.0041, +0.2768, +0.0295, -0.5365, -0.1148, +0.1867, +0.4169, +0.1963, -0.1607, +0.4705, -1.0241, +0.4417, +0.1275, -0.7696, -0.2660, +0.0380, -0.2972, +0.3949, +0.7762, -0.3281, +0.0599, +0.3288, -0.4384, -0.1356, -0.1655, +0.0742, -0.2041, -0.1239, -0.1804, +0.2637, +0.0942, -0.1011, -0.2973, -0.4499, +0.0090, +0.1412, -0.2019, +0.0945, +0.1347, -0.1332, -0.3886, +0.1739, +0.1864, +0.0391, -0.0350, +0.3963, -0.2367, +0.0131, -0.5565, -0.2354, +0.3302, +0.1141, -0.2861, -0.4460, +0.4304, -0.1393, -0.4753, -0.1158, -1.3481, +0.0292, -0.1015, -0.1453, +0.2802, +0.0700, -0.3325, +0.0110, +0.2497, +0.0056, +0.3542, -0.2658, +0.2565, +0.1598, -0.0339, -0.3039, -0.2208, -0.2119, -0.0196, +0.2157, -0.3472, -0.3380, -0.0314, -0.3920, -0.3210, +0.3201, -0.8747, +0.1812, +0.0732],
-[ -0.5735, -0.1147, -0.1845, -0.0670, -0.3959, +0.0605, +0.0751, -1.3236, -0.2729, -0.0563, +0.0870, -0.2487, -0.2976, -0.1418, -0.0036, -0.3945, +0.2133, +0.1156, +0.0328, -0.2110, -0.0954, +0.0828, +0.0342, +0.2200, -0.0155, -0.2676, +0.1296, +0.2238, +0.3469, -0.4331, +0.3707, -0.0087, +0.2342, -0.1123, -0.2393, +0.0042, -0.7079, -0.5531, -0.2589, -0.1329, -0.2473, -0.0557, -0.1092, -0.1055, +0.3648, +0.0103, -0.2566, +0.0428, +0.3451, -0.1363, -0.5322, -0.7636, -0.3877, +0.2084, +0.0500, -0.9000, +0.0186, -0.6299, -0.6176, +0.2841, -0.6676, +0.1776, -0.3414, -0.3621, -0.4323, -0.8091, +0.1711, -0.5524, -0.1845, -0.1440, +0.2521, +0.3597, -0.2215, -0.0636, -0.1948, -0.0981, -0.0632, +0.3646, -0.7443, -0.2697, +0.0858, -0.1100, -0.2158, +0.2193, -0.1480, -0.7157, +0.0280, +0.1051, -0.2165, -0.0942, -0.0988, -0.0529, +0.1711, +0.5135, -0.4368, +0.2158, -0.1203, +0.2175, +0.0274, -0.1588, +0.0862, -0.2315, +0.2650, -0.4179, +0.0053, +0.2025, +0.1570, -0.4194, +0.3459, -0.6148, -0.0766, -0.5666, +0.1655, -0.1656, +0.0047, +0.1534, +0.0364, -0.1854, -0.0359, -0.1716, -0.3132, -0.1275, +0.3301, +0.0841, +0.0211, -0.1663, -0.1611, +0.3612],
-[ -0.3046, +0.1990, +0.3593, -0.0441, +0.0111, -0.3952, +0.0887, +0.2970, +0.0432, -0.3783, -0.1590, -0.1455, +0.0672, +0.3143, -0.4494, -0.2105, -0.2141, -0.5621, -0.5350, +0.1795, +0.0950, -0.6389, -0.1119, -0.3228, -0.1351, -0.0998, +0.1916, -0.6883, -0.0802, -0.2211, -0.4179, -0.4322, -0.1921, +0.2114, -0.3894, +0.3510, -0.8963, -0.2446, -0.3355, -0.2554, +0.3715, -0.0832, +0.3089, +0.1687, -0.4003, +0.2255, +0.0172, -0.0353, -0.3352, +0.1071, -1.2214, -0.2593, +0.1820, -0.3545, +0.0520, +0.0625, -0.3255, +0.0246, -0.9975, +0.5751, -0.1415, +0.1819, -0.1992, +0.0300, -0.1407, -0.6492, +0.0380, -0.1231, -0.0581, +0.2151, +0.2173, +0.0064, -0.1583, +0.0302, +0.0198, -0.1276, -0.3126, -0.2499, -0.7244, -0.5974, -0.0122, -0.3023, -0.3659, +0.0236, -0.8076, -0.0052, -0.4533, +0.1279, +0.1329, -0.4658, -0.5219, -0.0994, -0.3155, -0.2044, -1.4585, -0.4960, +0.6144, -0.2893, +0.0656, -0.3623, +0.0771, -0.0557, -0.3057, -0.0149, -0.1504, +0.1180, -0.0191, -0.2747, +0.1425, -0.5355, -0.2589, -1.0663, -0.0238, +0.2357, -0.0646, -0.8185, -0.0544, +0.0328, -0.0684, -0.0288, -0.6393, +0.0760, -0.3438, -0.4502, -0.1043, +0.2516, +0.2664, -0.2895],
-[ +0.0107, -0.3197, +0.2582, +0.1588, -0.7646, -0.7069, -0.4099, +0.1225, +0.2743, -0.3283, -0.0027, +0.1298, -0.1093, +0.4504, -0.1028, -0.5416, -0.2146, +0.2392, -0.0145, +0.1768, +0.0453, +0.1953, -0.8660, -0.5489, +0.0746, +0.3120, +0.1501, +0.0138, -0.7171, +0.1558, -0.8054, +0.0637, -0.3851, -0.4554, -0.0707, +0.0844, +0.1226, +0.0906, -0.6054, +0.5808, +0.0931, -0.4798, -0.1459, -0.3292, +0.1951, -0.2652, -0.2279, -0.5004, +0.7729, -0.2178, -0.6389, -0.2515, +0.1850, -0.6675, -0.0282, -0.3199, +0.1368, +0.3026, -0.4689, -0.0329, +0.2913, +0.0254, -0.3636, -0.1038, +0.1523, +0.1738, -0.1826, +0.0448, -0.0613, -0.0619, +0.0614, -0.1873, -0.3742, +0.0553, -0.1018, +0.0197, +0.1035, -0.2413, -0.4748, +0.2443, -0.1595, +0.1139, -0.2503, +0.3971, -0.5707, -0.6110, +0.3676, -0.6585, -0.0983, -0.8527, +0.5715, -0.5112, +0.0883, -0.1990, -0.1421, +0.5473, -0.0631, -0.3381, -0.0705, +0.2045, -0.3428, -0.3719, +0.1965, -0.4464, -0.2206, -0.0407, -0.3212, -0.0742, -0.0010, -0.0920, +0.0179, -0.1233, -0.4241, +0.0697, +0.0483, -0.4507, -0.7664, -0.4521, -0.2175, -0.3721, -0.3304, -0.2537, +0.1789, -0.2410, -0.0701, +0.3168, -0.2336, -0.2128],
-[ +0.1155, -0.0102, +0.4249, -0.0738, -0.5340, +0.0663, -0.0927, +0.1452, -0.3015, -0.2405, -0.6384, +0.0373, -0.0334, +0.1594, -0.0984, -0.3201, +0.3151, -0.3141, -0.0241, -0.2851, +0.0472, +0.5239, +0.2989, +0.0661, +0.0884, +0.1384, +0.1193, +0.3296, -0.3185, +0.2506, +0.1458, +0.1626, +0.2309, -0.3974, -0.0698, -0.1044, +0.0031, -0.5501, +0.0439, -0.7990, +0.2289, -0.1844, +0.3783, -0.4319, +0.1479, -0.1089, -0.0206, +0.0524, +0.2799, +0.1135, -0.2630, -0.3034, -0.0279, -0.3430, -0.3194, +0.2728, -0.2198, +0.0995, -0.5879, -0.0968, -0.6351, -0.2687, +0.2761, -0.1994, +0.1186, +0.0766, -0.0157, -0.4284, +0.4550, +0.0266, +0.1227, +0.1949, +0.0795, -0.1303, -0.0641, -0.2911, -0.2093, +0.1755, +0.3525, +0.2074, +0.0776, +0.0871, -0.4309, +0.0466, +0.2179, -0.7288, -0.3884, +0.0433, +0.0226, -0.5845, -0.3762, +0.1555, -0.1571, +0.1242, -0.0361, +0.0694, -0.0607, -1.1456, -0.2432, +0.2734, -0.0147, +0.0134, -0.1083, -0.1578, +0.2299, +0.1616, +0.3512, -0.1246, +0.1847, -0.1015, +0.3420, +0.1070, +0.0237, +0.1442, +0.0974, -0.0842, -0.0235, +0.2302, -0.1871, +0.0759, -0.7443, +0.0672, -0.9173, -0.2906, +0.2102, -0.0130, -0.7445, +0.2416],
-[ +0.0570, -0.1107, -0.1294, +0.2502, -0.2984, +0.0134, +0.2178, -0.2031, -0.0498, -0.9746, -0.1293, +0.3008, -0.2820, +0.2322, +0.0366, +0.0613, -0.2685, +0.0761, +0.0324, +0.6167, -0.0038, -0.3098, +0.1486, -0.2141, -0.1495, -0.0758, -0.0287, -0.1225, -0.0489, -0.2928, -0.0031, -0.2655, -0.2361, +0.0487, +0.1637, -0.0362, -0.6581, -0.2809, -0.2362, -0.3010, -0.2808, +0.1002, +0.3643, +0.1101, -0.5130, -0.1977, -0.7063, +0.0310, -0.1288, -0.0684, -0.2172, -0.9830, -0.9522, +0.2543, -0.2441, -0.2201, -0.3622, -0.6192, -0.0511, -0.3572, -0.2073, -0.3067, -0.5459, -0.8507, +0.1938, -0.8735, -0.1393, +0.1941, -0.5221, -0.2935, -0.1622, +0.2692, -0.6518, -0.0784, -0.0032, +0.0453, +0.0612, +0.0740, +0.0828, -1.5962, -0.0105, -0.2185, +0.1251, +0.2271, -0.0830, -0.3206, +0.2678, -0.3253, +0.1302, -0.2226, -0.3965, +0.0605, +0.2157, +0.0511, +0.1486, -0.0471, -0.7112, +0.1349, +0.0479, -0.3281, +0.0545, -0.1693, +0.1596, +0.0366, +0.3659, +0.4518, -0.5676, +0.0444, -0.4920, -0.4001, -0.3816, -0.3445, +0.3152, +0.2686, +0.0873, -0.6441, -0.1246, +0.0525, -0.0302, -0.6167, -0.3785, -1.3627, -0.6195, -0.2583, -0.0883, +0.0941, -0.0932, +0.1709],
-[ -0.0902, -0.0489, -0.5621, +0.1108, -0.0253, +0.2008, -0.0230, -0.1481, -0.1891, -0.0729, -0.0272, +0.0692, +0.0149, +0.4408, +0.5853, +0.1148, -0.5399, +0.1653, -0.0507, -0.0729, +0.0799, -0.5047, +0.0211, +0.0545, -0.1527, -0.0146, +0.1207, +0.2242, +0.5105, -0.1659, -0.3076, +0.0075, -0.0780, -0.0728, -0.9238, +0.0010, -0.2337, +0.1043, +0.3628, -0.3925, +0.0371, -0.0933, -0.1642, -0.4299, +0.1116, +0.3309, +0.1078, -0.1654, +0.1247, -0.0723, +0.1428, -0.0070, +0.2646, -0.2366, -0.2596, +0.0486, +0.1331, -0.3141, +0.2621, +0.1173, +0.1017, +0.3161, -0.3979, +0.0467, -0.0058, -0.1483, -0.4923, +0.3230, +0.3847, -0.8560, -0.1140, -0.2858, +0.0235, +0.0051, +0.2581, -0.1739, +0.0148, -0.0270, -0.1098, -0.4381, +0.2964, +0.0043, -0.2012, +0.3487, +0.0805, -0.3836, +0.3054, -0.2178, -0.1003, -0.8272, -0.8094, -0.1763, -0.4160, -0.0718, +0.0883, -0.5837, -0.0250, -0.2355, +0.2095, -0.3145, -0.4140, -0.1567, +0.1556, -0.1557, -0.0385, +0.4225, -0.4201, +0.4154, -0.1397, +0.0064, -0.4551, +0.0587, -0.3060, +0.2072, -0.1990, -0.6681, +0.4071, +0.1429, +0.1864, +0.0583, +0.3094, +0.1376, -0.0151, +0.2482, +0.0534, +0.3590, -0.0524, +0.0072],
-[ +0.2165, -0.0784, +0.4527, -0.2131, -0.0842, -0.2151, +0.2852, +0.3085, -0.0545, +0.0476, -0.3126, -0.1004, -0.3292, -0.3253, -0.0299, -0.3426, -0.6258, +0.2322, +0.1995, -0.7055, -0.4208, -0.2351, +0.5525, -0.0116, -0.1168, +0.3035, -0.4497, -0.0070, -0.6314, +0.2021, +0.2401, -0.6943, +0.6166, +0.0522, -0.1277, +0.0814, +0.1048, -0.1549, +0.0236, -0.0543, +0.1134, -0.1267, +0.0161, +0.0846, -0.3257, +0.3672, +0.4620, -0.0554, -0.6860, -0.5655, -0.0291, -0.0336, -0.0591, -0.0668, +0.4952, -0.6696, -0.6313, -0.4199, +0.1644, -0.1448, +0.3275, +0.0785, +0.1629, -0.3694, -0.0415, +0.3981, -0.3228, -0.4313, -0.2086, -0.3006, +0.0319, -0.1707, -0.6463, +0.4033, -0.2931, -0.2915, -0.0374, -0.5228, -0.0761, -0.0541, -0.0648, -0.4858, -0.3321, +0.0406, +0.0690, +0.1793, +0.3161, +0.3441, -0.1787, +0.1655, +0.1323, +0.0511, -0.5903, -0.4039, -0.5803, -0.0993, +0.0511, -0.4996, -0.2091, -0.8687, +0.3873, -0.8987, -0.7894, +0.4019, +0.2001, -0.0819, -0.2723, -0.1041, -0.0835, +0.3914, -0.1363, -0.0651, +0.1017, +0.1881, -0.1245, +0.1765, +0.1574, -0.4187, -0.3413, -0.4192, +0.0699, +0.2365, -0.2552, -0.6480, -0.2559, -0.0381, -0.2464, -0.2568],
-[ +0.1548, +0.0221, +0.3021, +0.0748, -0.0730, -0.3777, -0.0878, +0.1624, +0.0181, +0.0029, -1.0661, -0.2232, -0.0371, +0.2084, +0.0641, +0.3700, +0.2076, -0.1308, -0.6938, -0.0521, +0.3410, -0.1052, +0.0010, +0.1400, -0.3497, -0.0732, +0.0856, +0.1817, -0.3963, -0.3211, +0.1612, +0.0391, +0.1267, +0.1567, -0.8114, +0.0540, -0.3109, -0.1081, +0.1441, +0.1741, -0.1098, +0.2501, +0.1449, -0.0120, -0.1075, -0.2483, -0.7078, -0.2693, -0.0336, +0.0171, -0.0570, +0.1460, +0.1243, -0.1844, +0.1645, -0.4268, +0.0438, -0.2597, +0.0547, -0.1758, +0.0263, -0.8264, +0.0728, -0.2166, -0.1181, +0.2654, -0.2549, +0.0277, +0.1403, +0.4358, -0.0468, +0.0663, -0.5248, +0.2055, -0.2036, -0.2702, -0.7653, +0.1719, +0.0243, +0.0066, +0.0388, -0.1156, -0.2506, -0.1971, +0.1007, -0.0745, +0.0724, -0.1242, +0.0428, +0.0739, +0.1192, +0.1407, -0.0524, +0.0955, -0.0253, -0.0342, -0.5003, +0.0988, +0.4093, +0.0309, -0.1069, -0.4025, +0.0368, -0.0331, -0.0844, +0.1159, -0.0163, +0.1731, +0.3613, -0.0142, -0.0990, +0.0854, +0.0900, -0.1528, -0.1269, -0.3659, -0.0846, +0.1304, +0.0177, +0.2548, +0.1939, -0.0656, -0.1266, +0.0675, +0.0898, -0.0352, -0.0179, -0.0786],
-[ -0.1477, -0.3154, +0.0705, +0.0553, -0.0120, -0.2545, -0.1162, -0.0357, -0.0614, -0.1063, -0.1024, -0.2153, -0.2259, -0.0393, -0.6030, -0.7395, +0.2510, +0.6092, -0.1453, +0.1808, +0.0889, +0.0641, -0.1695, -0.1308, -0.7268, +0.1051, -0.3328, -0.5555, -0.1323, -0.0470, +0.4817, -0.2015, -0.1558, -0.2925, -0.3102, -0.1149, -0.1001, -0.2164, -0.1036, +0.3618, +0.3640, +0.0790, +0.1367, +0.1737, -0.3290, -0.2891, +0.3472, +0.0828, +0.2550, +0.0813, -0.2269, -0.5814, +0.4380, -0.3854, -0.1073, -0.3434, -0.2344, -0.3333, -0.9712, +0.3074, -0.0863, +0.0101, +0.4935, -0.4539, +0.2815, +0.4703, -0.1730, -0.4645, -0.0182, -0.6704, +0.4409, +0.0128, +0.3440, +0.0742, -0.0970, +0.0381, -0.9197, +0.1764, -0.3166, -0.5216, +0.1401, +0.1343, -1.0300, +0.0069, +0.3072, +0.0852, -0.2241, -0.0990, -0.1649, -0.0966, -0.0429, -0.0274, +0.0635, +0.3952, -0.1940, +0.1375, -0.3230, +0.6582, +0.1195, +0.0523, +0.0047, -0.4729, +0.2348, -0.1884, +0.3227, +0.0247, +0.1520, -0.4772, -0.0548, +0.1463, +0.2491, -0.0230, +0.2104, -0.0490, -0.4887, -0.7157, +0.4019, +0.1893, +0.1334, -0.3488, -0.0239, -0.6403, -0.5436, -0.3965, +0.0472, +0.0951, +0.3826, -0.0119],
-[ +0.2345, +0.0402, +0.3096, +0.1290, -0.0478, +0.1970, +0.0213, -0.4571, +0.3814, -0.0410, -0.5314, -0.2755, -0.3864, -0.9906, -0.6441, -0.0119, +0.5029, +0.0528, +0.1426, +0.1558, -0.3429, +0.3553, -0.0140, -0.1257, +0.5183, -0.1416, +0.1306, -0.1761, +0.4427, +0.1535, +0.0231, +0.2305, -0.1755, -0.5971, +0.3964, +0.4374, -0.4033, -0.1754, +0.0906, -0.0307, -0.6401, +0.3662, -0.0488, -0.0305, -0.1799, -0.9114, -0.6223, -0.6197, +0.1350, -0.2145, +0.0602, +0.4021, -0.5092, -0.3139, +0.2932, +0.0838, -0.2362, -0.0395, -0.5941, +0.0945, -0.0716, +0.2605, -0.4417, +0.3200, +0.2494, +0.0426, -0.2447, -0.5307, +0.0455, -0.1078, +0.2131, -0.2504, -0.3621, +0.1624, -0.1116, +0.1532, +0.1341, -0.2960, -0.0485, +0.2547, -0.1497, +0.5129, -0.7462, -0.2898, -0.2437, -0.3651, +0.2329, -0.0681, -0.0266, -0.5809, -0.3785, +0.3757, +0.1572, -0.0039, -1.0997, -0.3780, -0.0220, -0.6294, -0.5320, -0.0276, -0.1373, +0.4767, +0.0286, -0.6791, -0.1094, +0.2245, +0.7109, +0.2029, -0.2408, +0.1082, +0.3360, +0.3084, +0.0412, -0.0498, -0.0024, +0.0016, -1.4137, -0.2534, -0.1986, -0.4153, +0.7093, -0.2851, -0.3148, +0.4090, -0.2257, -0.3811, +0.0754, +0.1079],
-[ +0.1737, -0.1012, +0.3843, -0.3052, +0.0454, -0.0999, +0.0607, +0.5805, -0.0379, -0.1394, +0.1873, +0.2086, -0.0369, +0.2190, -0.9182, -0.1614, +0.0378, +0.0651, -0.3026, +0.1249, -0.0495, +0.7594, +0.2221, -0.1335, +0.4775, -0.3486, -0.3901, -0.2565, -0.2424, -0.2014, -0.4993, -0.3226, -0.4516, -0.0422, -0.1739, +0.2270, +0.2250, +0.2292, +0.5843, +0.3938, -0.8007, -0.1657, -0.2410, +0.0172, -0.1222, +0.3231, -0.2751, -0.2512, +0.2162, -0.6735, -0.1592, -0.5736, +0.3512, -0.1531, +0.0767, -0.1251, -0.3526, +0.2640, +0.3694, +0.0025, -0.0883, -0.9067, +0.1201, +0.0180, +0.1013, +0.1774, +0.0458, +0.1053, -0.1279, +0.1314, -0.7170, -0.0099, +0.0331, -0.6149, -0.3880, +0.3317, -0.1987, -0.1860, +0.2181, -0.2855, +0.0181, +0.1234, +0.0470, -0.4842, +0.1452, +0.0126, -0.0338, +0.0576, -0.1719, +0.4222, +0.0425, -0.1328, -0.2182, -0.3864, -0.2636, -0.4534, +0.3275, -0.4392, -0.3175, -0.0483, +0.0194, -0.2320, +0.1536, -0.0455, +0.2573, -0.3990, -0.7663, +0.0444, +0.2442, +0.2573, -0.4178, +0.0640, -0.1134, +0.0385, -0.0557, -0.1481, -0.1792, +0.1467, +0.0214, +0.0728, -0.3110, +0.2292, -0.8796, -0.1230, -0.3657, +0.3918, +0.4578, +0.0213],
-[ -0.0058, -0.0501, -0.1675, +0.2440, +0.0982, -0.3081, +0.2197, -0.0078, +0.2634, +0.4613, +0.0454, +0.0953, +0.2481, -0.9030, -0.5912, -0.1769, +0.3100, -0.0666, -0.4307, -0.2750, +0.0457, +0.4329, +0.1131, +0.1623, -0.4575, -0.0464, +0.0587, +0.0037, +0.1761, +0.1243, -0.3456, -0.1771, +0.1526, +0.1889, +0.0453, -0.0169, +0.2543, -0.2468, -0.1749, -0.1054, +0.1356, -0.0753, -0.2053, -0.5136, +0.1298, -0.3350, -0.3511, -0.6631, +0.1640, +0.0080, -0.5760, -0.1730, -0.4837, +0.0082, -0.3955, -0.1565, +0.1675, +0.3669, +0.4185, -0.1695, +0.6183, -0.4073, -0.2162, -0.4735, -0.1205, -0.6054, -0.1156, +0.0477, +0.1337, -0.3585, +0.0539, -0.3033, -1.1556, -0.6334, +0.2199, +0.1659, -0.5817, +0.1128, -0.3548, -0.0180, -0.3140, -0.3119, -0.3624, +0.3207, -0.1126, +0.2188, +0.1764, -0.2787, -0.6278, -0.0367, +0.4690, -0.1529, +0.0098, -0.4824, +0.0185, -0.1893, -0.7196, +0.0138, -0.7285, -0.1746, +0.2740, -0.6991, -0.8272, -0.0170, -0.2122, +0.0546, -0.0070, +0.0135, -0.9043, -0.2043, -0.0655, +0.0533, -0.2891, -0.3379, +0.1854, +0.0024, -0.4407, -0.4790, -0.6179, -0.4374, -1.1258, -0.8652, -0.7400, +0.2832, +0.3050, +0.3432, +0.1818, -0.3477],
-[ +0.0421, +0.0760, -0.0937, -0.3289, -0.1264, -0.2004, +0.2442, -0.7426, +0.1581, +0.1091, -0.2079, +0.1762, -0.2847, +0.2595, -0.0436, +0.0309, -0.0391, -0.3279, +0.0869, +0.1888, +0.2382, -0.1285, +0.0044, -0.0093, +0.1621, +0.0545, +0.3107, -0.0062, +0.4497, +0.2697, +0.1220, -0.3746, +0.2347, +0.1905, -0.2530, -0.0934, -0.3307, -0.2066, -0.0438, +0.1751, -0.2122, -0.2497, +0.1197, +0.3855, -0.0690, -0.0119, +0.1714, -0.1429, +0.2048, +0.3442, -0.0357, -0.3776, +0.2283, +0.1940, -0.0545, -0.3471, -0.0467, -0.4649, +0.0441, +0.0288, -0.0065, +0.0178, -0.0776, -0.2727, +0.3306, -0.4464, +0.1174, +0.1001, +0.0399, +0.0524, -0.0003, -0.1412, -0.0648, -0.2413, -0.4105, -0.0880, -0.1160, +0.1251, +0.1382, -0.0681, +0.4072, -0.1640, -0.2284, +0.1872, -0.0280, +0.2319, -0.2080, +0.0299, -0.3826, -0.1097, +0.1318, -0.1643, -0.0302, -0.5179, +0.2203, -0.0162, -0.6722, -0.0071, -0.5593, +0.1680, +0.0923, -0.1145, -0.2368, -0.0590, +0.3251, -0.3777, -0.2606, -0.3314, -0.1094, -0.2820, -0.1278, +0.1683, -0.2518, +0.1133, -0.1676, +0.0311, +0.2705, +0.2880, +0.1390, -0.0344, +0.2985, -0.0291, -0.6771, -0.3216, +0.1436, -0.3997, +0.1744, -0.0892],
-[ +0.2227, -0.2971, -0.3469, +0.4666, -0.0545, +0.1139, +0.1211, -0.3773, +0.0639, +0.3880, -0.3827, +0.1726, -0.3401, -0.2897, -0.4629, +0.1177, +0.0280, -0.3550, -0.5237, +0.0578, +0.0203, -0.4134, -0.2219, -0.1620, +0.1527, -0.3433, -0.0286, +0.1367, -0.4098, -0.0532, +0.0170, -0.1500, -0.2434, -0.1257, +0.1599, +0.3132, -0.4962, +0.0203, -0.1200, -0.3780, -0.0548, -0.1382, +0.0468, -0.2005, -0.2922, +0.0412, -0.3139, -0.2190, -0.1921, -0.3008, -0.1326, +0.1474, -0.0546, -0.3791, +0.2720, -0.4730, +0.2390, -0.2128, -0.1345, -0.3941, +0.2550, -0.3516, +0.0163, +0.2963, +0.0107, -0.0940, -0.5645, -0.3014, -0.0069, +0.2026, -0.0785, +0.4574, +0.1301, +0.2480, -0.0485, -0.2237, -0.0629, -0.2352, +0.0711, +0.2740, -0.1476, +0.3646, +0.3072, -0.2861, -0.1857, -0.0471, +0.0310, -0.3897, +0.0805, +0.0024, +0.0570, +0.3988, -0.0309, -0.0894, +0.2665, -0.3530, +0.1016, +0.2017, +0.4422, -0.0812, -0.0641, -0.4382, -0.0046, -0.3735, -0.1861, +0.2945, +0.0989, +0.1345, +0.0340, +0.0190, -0.2118, +0.0686, -0.3836, +0.1731, +0.1700, -0.2080, +0.2979, -0.5672, +0.0529, +0.1361, -0.1965, -0.1959, -0.1695, +0.0855, -0.2045, -0.1573, -0.3586, -0.1811],
-[ -0.2061, +0.1187, -0.4152, +0.3454, +0.3325, -0.4535, +0.0175, -0.1316, +0.1508, +0.0567, -0.3291, +0.0792, -0.3860, -0.6880, +0.0831, +0.0106, -0.2324, -0.1728, -0.2045, +0.5967, +0.1797, -0.7193, -0.1522, +0.4142, +0.2647, -0.1462, +0.2758, +0.2446, +0.0061, -0.0743, +0.2720, +0.1632, -0.1003, -0.2277, -0.5311, -0.1379, +0.1877, +0.0882, -0.1241, +0.0654, +0.0969, +0.0503, +0.1742, -0.0763, +0.1149, -0.1509, -0.2626, -0.0685, -0.0073, +0.5289, -0.0256, +0.3609, +0.1023, -0.4789, -0.3071, +0.2803, +0.0987, +0.0184, -0.2751, +0.0439, +0.7189, -0.4512, -0.6046, +0.3523, +0.2981, -0.1774, +0.3571, -0.2574, +0.0502, +0.2503, -0.2745, -0.2874, +0.1629, -0.2583, -0.0399, -0.2499, +0.0662, -0.0962, -0.1815, -0.4266, +0.1113, -0.8154, -0.3679, +0.0954, +0.0696, -0.2440, -0.1968, -0.3760, +0.0211, -0.5700, +0.2556, -0.3801, -0.0156, +0.0770, -0.4611, +0.0781, -0.1871, -0.1328, -0.0320, -0.7022, -0.3862, -0.0156, +0.3554, -0.2388, +0.1465, +0.1270, -0.1418, +0.1951, -0.4408, -0.5125, -1.0156, +0.4492, -0.6887, +0.2781, +0.1575, -0.3814, -0.2889, +0.2475, -0.1107, +0.0171, -0.3111, -0.2021, +0.2899, +0.1741, -0.3082, +0.0318, -0.1960, +0.3964],
-[ +0.0908, -0.0992, -0.5574, -0.1475, +0.0634, -0.2495, -0.1826, +0.3553, +0.0084, +0.2624, +0.0450, -0.1352, -0.0266, +0.0049, -0.2243, -0.0175, -0.2538, -0.0782, -0.6108, -0.1035, +0.2119, -0.2691, -0.0323, +0.0551, -0.0377, +0.3972, -0.4437, -0.7321, +0.0651, -0.1293, -0.0490, +0.1585, -0.0975, -0.1757, -0.2343, -0.0055, +0.1740, +0.0048, -0.6559, +0.0373, +0.3460, -0.9263, +0.1879, -0.0669, +0.3651, +0.5088, -1.0274, -0.3409, -0.0143, +0.2722, +0.2818, -0.1034, -0.6006, +0.4080, -0.1925, -0.1793, -0.3323, -0.5531, -0.1189, +0.1274, +0.1319, -0.4859, -0.2834, -0.5362, +0.2529, -0.0815, -0.8830, -0.1149, +0.4302, +0.3286, -0.8478, +0.3274, +0.1833, -0.8509, +0.0124, +0.1571, -0.3137, +0.2163, -0.2620, +0.3702, +0.0263, -0.8892, -0.3077, -0.5872, -0.2785, -0.0548, +0.6223, +0.1073, +0.2722, +0.1667, -0.7687, -0.3004, -0.1409, +0.0977, -0.6361, +0.0895, +0.2523, -1.1700, -0.1937, -0.0640, -0.5124, -0.2828, +0.0786, +0.1680, +0.1903, -0.0973, +0.0276, -0.2992, -0.1459, -0.5329, -0.5601, -0.3211, -0.4753, -0.5864, +0.1028, -0.3598, -0.0670, -0.2731, +0.4096, -0.2266, +0.3978, -0.0444, -0.2637, +0.2951, -0.5427, -0.2461, -0.5261, +0.0949],
-[ +0.1618, -0.4905, +0.3258, -0.1014, -0.0287, +0.5747, +0.0951, -0.1661, -1.0580, -0.0250, -0.1151, +0.1218, +0.0448, +0.0009, -0.2375, +0.1923, -0.0808, -0.1496, -0.4040, -0.0011, +0.1566, -0.0025, +0.0013, -0.1833, -0.4217, -0.1717, +0.0899, -0.1539, -0.0715, +0.2257, -0.0181, +0.3481, +0.1751, +0.1634, -0.5412, +0.0892, -0.2702, +0.1308, -0.4672, -0.3700, -0.2379, +0.1514, +0.3748, +0.0297, +0.0131, +0.2860, +0.0202, -0.4741, -0.3178, -0.2200, +0.0164, +0.0544, +0.2424, -0.3790, +0.0947, +0.0634, +0.1048, -0.5026, -0.4402, -0.2208, -0.1970, +0.2420, -0.2852, +0.1045, +0.0041, +0.1532, -0.2748, +0.2220, -0.1802, -0.1195, -0.0320, +0.0941, +0.0821, +0.1148, +0.2390, +0.3889, +0.0018, -0.3051, -0.0233, -0.0228, -0.3145, -0.0425, +0.4689, +0.1950, +0.1288, -0.6089, +0.2982, +0.1527, +0.1825, +0.1216, +0.4530, +0.1668, -0.3275, +0.1676, -0.2089, -0.0556, -0.6145, -0.0445, -0.8699, -0.2688, +0.3719, -0.7730, -0.1762, +0.0905, -0.3222, +0.3221, +0.4203, -0.0613, +0.1184, +0.2110, +0.2703, +0.0339, -0.1625, +0.2663, +0.1400, +0.0936, -0.3175, -0.3469, -0.0820, -0.0730, -0.0210, +0.1526, -0.0458, -0.0371, +0.1708, -0.1264, -0.4222, +0.2816],
-[ -0.1449, -0.4340, +0.3384, +0.1579, -0.1091, -0.2229, -0.7007, -1.1185, -0.1052, +0.1772, -0.3176, -0.0954, -0.3036, -0.3146, +0.2082, -0.6706, +0.0364, +0.1425, +0.3943, -0.2101, +0.0523, -0.2765, +0.0090, -0.0655, -0.2401, +0.4830, -0.2957, +0.0572, +0.0692, -0.1737, +0.4769, -0.4658, +0.0137, +0.0588, -0.5256, +0.3810, -0.0043, +0.0705, -0.7742, -0.2515, +0.4426, +0.0385, -0.0394, -0.0789, -0.1381, +0.2169, +0.0898, -0.4948, -0.4634, -0.0958, -0.1589, -0.4759, +0.2111, -0.2565, +0.0694, +0.0705, +0.0388, +0.1178, -0.0762, -0.4617, -0.8680, -0.2346, +0.2338, -0.7045, +0.3175, -0.1283, -0.1354, -0.4054, +0.2363, -0.0522, -0.0029, +0.1389, +0.1709, +0.3458, -0.1531, +0.1611, -0.4193, +0.1833, +0.2374, +0.6556, -0.0475, +0.3806, +0.4965, -0.2974, -0.0217, +0.2118, -0.0464, +0.3696, -0.0580, -0.8348, -0.7580, +0.0611, +0.1105, -0.1347, -0.0760, +0.1793, -0.3194, -0.6205, +0.4345, +0.0319, +0.0245, +0.3281, -0.2088, -0.8847, +0.1012, +0.1181, +0.0141, -0.4330, -0.0720, +0.3774, +0.2740, -1.0438, +0.1583, +0.0846, -0.1631, +0.3802, -0.0777, +0.1888, -0.3915, +0.2461, -0.8871, +0.0106, +0.0323, -0.0571, -0.1533, -0.4462, -0.1460, -0.3907],
-[ -0.2878, -0.0615, +0.2505, +0.1581, -0.6736, +0.2485, -0.3433, -0.5456, -0.5950, -0.1342, +0.1008, -0.0716, -0.0541, +0.1849, -0.3383, +0.2208, -1.0103, -0.3722, -0.0319, -0.0332, -0.4669, -0.1479, -0.0878, -0.1468, -0.3543, +0.5402, +0.1786, -0.0781, +0.0761, -0.5135, +0.5701, +0.1104, -0.0162, +0.2412, +0.0370, +0.0211, +0.0297, +0.2620, -0.0827, -0.6327, +0.0140, +0.0513, -0.0192, -0.2413, -0.5702, -0.0003, +0.4197, -0.3194, +0.1597, -0.2770, -0.5649, +0.1293, -1.0851, -0.4333, -0.3866, -0.8689, -0.1534, -0.1899, -0.1301, -0.2131, +0.1348, -0.1494, -0.3751, +0.3482, -0.0373, -0.1306, -0.2304, +0.5142, +0.1681, -0.5262, -0.3565, -0.2431, -0.2511, +0.4271, +0.2971, -0.3514, -0.1895, -0.0938, +0.3170, -0.0274, +0.1666, -0.2795, -0.5762, -0.3793, -0.1089, +0.1886, +0.5871, -0.2598, -0.3023, -0.8249, +0.2772, +0.1765, +0.0883, -0.0666, +0.1009, +0.2339, -0.0881, -0.3906, +0.1244, -0.1059, +0.0345, +0.1081, -0.3789, -0.3119, -0.3382, -0.3980, -0.2057, +0.0522, -0.4197, +0.2586, -0.0300, +0.1536, +0.2187, -0.0763, +0.0302, +0.3941, +0.6030, -0.6882, -0.1713, -0.2873, +0.4185, +0.3159, +0.2026, +0.1525, -0.4530, -0.0410, -0.0349, +0.2280],
-[ -0.6061, -0.0909, -0.0550, -0.2184, -0.4677, -0.4432, -0.2260, +0.1602, -0.3579, -0.2434, -0.3035, -0.3499, -0.4640, -0.0961, -0.8689, -0.3364, -0.5608, -0.2340, -0.3993, -0.4102, +0.2083, +0.0047, -0.1841, -0.8708, +0.2682, -0.2035, +0.0297, -0.1514, -0.3664, +0.0290, -0.3759, +0.3887, -0.3711, -0.5360, -0.2174, -1.1284, -0.5156, -0.1612, -0.0737, -0.4903, -0.4929, -0.1873, +0.0404, -0.1258, +0.4220, +0.2427, -0.0421, +0.4974, +0.0100, +0.3258, -0.3710, -0.0276, -0.6241, -0.2282, -0.2343, +0.5713, -0.1646, -0.3397, +0.2585, +0.0450, -0.1207, -0.1081, +0.2005, -0.5321, -0.3488, +0.0880, +0.1172, +0.1975, -0.2884, -0.3175, +0.1191, +0.1787, -0.4443, -0.2308, -0.1809, +0.1833, +0.3746, -0.1612, -0.1746, +0.1444, -0.1684, +0.1569, -0.5966, +0.0297, -1.1438, -0.3301, -0.0267, +0.1739, -0.1595, -0.7382, -0.8372, -0.2308, -0.3466, -0.4795, -0.2313, -0.7824, +0.1980, +0.2107, -0.6244, -0.0962, -0.1942, +0.2395, -0.3016, -0.1821, +0.4167, -0.0695, -0.2468, +0.0869, -0.5590, -0.2276, -0.4163, +0.2860, +0.1813, -0.0321, -0.2457, -0.0202, -0.1410, +0.1888, -0.0146, -0.7551, -0.0123, +0.1800, -0.2752, +0.0198, -0.0279, -0.4698, -0.4623, -0.3625],
-[ -0.0845, -0.0307, +0.2515, +0.0145, +0.1197, +0.3987, -0.4345, -0.3723, +0.0691, +0.1694, -0.3358, -0.0540, -0.0187, +0.5110, +0.1727, -0.1340, +0.0335, -0.1176, -1.2247, -0.0016, +0.2501, -0.1295, -0.3627, +0.2087, -0.0750, -0.0229, -0.1075, -0.4822, +0.1749, +0.2224, +0.2493, -0.8074, -0.3120, -0.1274, -0.7827, +0.0645, -0.1956, -0.1618, +0.1351, -0.2641, -0.0409, +0.2512, +0.1865, +0.1569, -0.3542, -0.1335, -0.9144, -0.3099, -0.0042, +0.0161, -0.5852, -0.4469, +0.1677, -0.5367, +0.5580, +0.0745, +0.0027, -0.1883, -0.4742, -0.3860, -0.5103, +0.4660, -0.8256, -0.7132, -0.0312, -0.3823, -0.1519, +0.2287, +0.2300, +0.1152, +0.1736, +0.2429, -0.1806, +0.2374, -0.3979, +0.1320, -0.5556, +0.2660, -0.8979, -0.6503, -0.0790, +0.1668, -0.4129, -0.4282, +0.3145, -1.3375, -0.1544, +0.1570, +0.1358, -0.4562, -0.5580, -0.0270, -0.0299, -0.2310, -0.3223, -0.2773, -1.2287, +0.0719, +0.1664, -0.1294, +0.0616, -0.1551, -0.1501, -0.1315, -0.0196, -0.1675, +0.0702, -0.1678, +0.0950, -0.2934, -0.1290, +0.0739, +0.0199, +0.1733, +0.0355, -0.7176, -0.2725, -0.2942, -0.3444, -0.3210, -0.2305, +0.0826, +0.2586, -0.2365, +0.0963, +0.0902, +0.1406, +0.0500],
-[ -0.1641, +0.1803, +0.0176, -0.0164, -0.1597, -0.1098, +0.1263, -0.3531, +0.2009, -0.2688, +0.2281, +0.0484, +0.0412, +0.4032, +0.0177, -0.7202, -0.1029, +0.2414, -0.3872, +0.4367, +0.0134, -0.3715, -0.1411, -0.0280, -0.3206, -0.0946, +0.1634, -0.5124, -0.0615, -0.1953, -0.2134, -0.3191, +0.2202, +0.0565, -0.0890, -0.2060, -0.4671, +0.2055, -1.1555, -0.0669, +0.1648, -0.1441, -0.1714, -0.1822, +0.2035, -0.7000, +0.0695, +0.0956, +0.0437, -0.0890, -0.1878, +0.2828, -0.2674, +0.1618, +0.2366, +0.0729, +0.3175, +0.0306, -0.5201, +0.0188, +0.3739, -0.5527, -0.3397, +0.0665, +0.3225, -0.2450, -0.3998, -0.1282, +0.3574, -0.2880, +0.2108, -0.1360, -0.0243, +0.0996, -0.4179, -0.2257, -0.4723, +0.4179, -0.1489, -0.0351, +0.3217, -0.4655, -0.5597, +0.2265, +0.0331, +0.1609, -0.0233, +0.3688, +0.2562, -0.0856, -0.3728, -0.0548, +0.4144, +0.1663, -0.5262, +0.3334, -0.1203, -0.0692, +0.1855, +0.0311, +0.0978, +0.0475, -0.0780, +0.3128, -0.0074, -0.6474, +0.1366, -0.2251, +0.0069, -0.0087, +0.0467, +0.0438, +0.0939, +0.4966, -0.1934, -0.6285, -0.2758, +0.1596, +0.0895, -0.2190, -0.8005, -0.2677, -0.3218, +0.3237, +0.0888, -0.2617, +0.0320, +0.1497],
-[ -0.1253, -0.0350, -0.0856, -0.0467, +0.1283, +0.2748, +0.1479, +0.2745, +0.1078, -0.3786, -0.3089, +0.0064, -0.1175, +0.0248, +0.2094, -0.2929, -1.4566, +0.2682, +0.0442, +0.3729, +0.2005, -0.5589, +0.1468, +0.4390, -0.8793, +0.2898, +0.3577, -0.6922, +0.0979, +0.3569, +0.0792, +0.1176, -0.2124, +0.1861, -0.0484, -0.0443, +0.2162, +0.0916, -0.2512, +0.0367, +0.0633, +0.0470, +0.0792, +0.0034, -0.1414, +0.3856, -0.1245, -0.1696, -0.1526, +0.1365, +0.3263, -0.0325, +0.3004, +0.2138, +0.1553, +0.2231, -0.1920, -0.5498, -1.3362, -0.0097, -0.1920, +0.2219, -0.2937, -0.2273, -0.2927, +0.2756, -0.1875, -0.1068, -0.3225, +0.0928, +0.5012, -0.3023, -0.1227, -0.5252, -0.3104, -0.5777, +0.0303, -0.2129, -0.6370, +0.4402, -0.4292, -0.2224, -0.0492, -0.2785, +0.2249, -0.3533, -0.2766, -0.1833, -0.1814, -0.9459, -0.2622, -0.6534, -0.2456, +0.3434, -0.0585, +0.0774, -0.1196, -0.2611, +0.3853, +0.1695, +0.1012, +0.0691, -0.0476, +0.0520, -0.2332, +0.0186, -0.1382, +0.3594, -0.0141, +0.3252, -0.3512, -0.0661, +0.1478, +0.4440, +0.0711, -0.1353, -0.2475, -0.0257, +0.5104, +0.1134, -0.1690, +0.0288, -0.4795, -0.1104, +0.0961, -0.1073, -0.6397, +0.0654],
-[ -0.1892, +0.0568, -0.2412, -0.6013, +0.3256, +0.2101, +0.1802, -0.2477, +0.0262, -0.4132, -0.1172, +0.1311, +0.2263, +0.1451, +0.3181, -0.1332, +0.1379, -1.1694, -0.3646, -0.1916, -0.4726, -0.4236, -0.0609, -0.0810, -0.0390, -0.0253, +0.2483, +0.4296, +0.0255, -0.9403, +0.3116, -0.8595, +0.2039, -0.3203, -0.0686, -0.2876, -0.7740, -0.4882, +0.2804, +0.1530, -0.3647, -0.2899, -0.1928, +0.0574, -0.9411, +0.2955, +0.5295, -0.1495, -0.2544, -0.0502, -0.6493, -0.0688, -0.2562, -0.0072, +0.0258, +0.2712, +0.4828, -0.0741, +0.0550, -0.1493, +0.0222, -0.0950, -0.1410, -0.0260, -0.0008, -0.2603, +0.0681, +0.0436, +0.1496, -0.0550, -1.4449, +0.2512, -1.1742, -0.6389, -0.1976, -0.2944, -0.3775, +0.2221, -0.0417, -0.0980, +0.0640, +0.0496, -0.1026, +0.2860, -0.6115, +0.0723, -0.0295, +0.1601, +0.0567, +0.2533, -0.5541, +0.4440, +0.2326, -0.3252, +0.1586, -0.2256, -0.6957, +0.0371, +0.3295, +0.4163, +0.1884, +0.0308, -0.9381, +0.1548, -0.1683, -0.1657, -0.3450, -0.0012, +0.2329, +0.3270, +0.2418, -0.0308, +0.2985, -0.2371, -1.1584, -1.2930, -0.0451, +0.1693, +0.2680, +0.4843, +0.1023, +0.0457, +0.2715, -0.0179, -0.3231, -0.0171, -0.0038, -0.2308],
-[ -0.4185, +0.0518, -0.0622, +0.1876, -0.0893, +0.0031, -0.1216, -0.8492, -0.5659, +0.2852, -0.2889, -0.1508, +0.2531, -0.0835, +0.0111, +0.0087, -0.3572, +0.2532, +0.0334, -0.3784, -0.1595, -1.3338, -0.3168, -0.3062, +0.5036, -0.3661, +0.4044, +0.3749, +0.1713, +0.0696, -0.2597, -0.2785, -0.1862, -0.0663, -0.1889, +0.3290, +0.1240, +0.5744, +0.2029, +0.6920, -0.0658, -0.2106, -0.2397, -0.7892, +0.3586, +0.2038, +0.2659, +0.0079, +0.0883, +0.1599, -0.1192, +0.3185, +0.0724, -0.1714, -0.1568, +0.1129, +0.5232, +0.2673, +0.0950, +0.2312, -0.2412, -0.4621, -0.9121, +0.0927, -0.2441, -0.0055, -0.3084, +0.0480, +0.2937, -0.5931, -0.1304, -0.1331, -0.0718, -0.4675, -0.2199, -0.4012, -0.7162, -0.0440, +0.3202, +0.0727, -0.0885, +0.2881, -0.2546, +0.2202, -0.0740, +0.0747, +0.3164, +0.1560, +0.1748, -0.1047, +0.0710, -0.1201, -0.0498, +0.1716, +0.2840, -0.2102, +0.1068, +0.0459, +0.1061, -1.3161, -0.0708, -0.6666, -0.0305, +0.0622, -0.3030, +0.0992, -0.4008, +0.1789, +0.0664, +0.1021, -0.1184, +0.2772, +0.2421, -0.6209, -0.4482, -0.6124, -0.0749, -0.0634, +0.4178, -0.0745, -0.5763, +0.3940, -0.2924, -0.4282, -0.2118, -0.5264, -0.8030, +0.1691],
-[ -0.0243, +0.1186, +0.1214, -0.7917, -0.0578, +0.0656, +0.1574, -0.4321, -0.8055, -0.0509, +0.2256, +0.1686, -0.0946, -0.1584, +0.1417, +0.1943, -1.2738, +0.0080, -0.1580, -0.5160, +0.2872, +0.0854, +0.1843, -0.0101, -0.0975, -0.1252, -0.3296, -1.1518, -0.1937, -0.0913, +0.1553, -0.3593, +0.7464, -0.2383, -0.8537, +0.0278, -0.0484, +0.1455, +0.0117, -0.0073, -0.5213, +0.0542, -0.3462, -0.4633, +0.1424, -0.0178, -0.0359, -0.8284, -0.5606, -0.0482, +0.3423, +0.2033, +0.3398, -0.2188, +0.0563, +0.4824, -0.7406, -0.2805, +0.2481, +0.0907, +0.1630, -0.2325, -0.1028, -0.0367, +0.1283, +0.1714, -0.4324, +0.3293, -0.4413, -0.3222, +0.0196, +0.4370, +0.2912, +0.1991, +0.0462, +0.3073, -0.5100, -0.0354, +0.0971, -0.6773, +0.1030, -1.0156, -0.3781, -0.3812, +0.5229, -0.1198, +0.1014, +0.3792, -0.0822, -0.5402, +0.3907, -0.4183, +0.2017, -0.2403, +0.1254, +0.1106, -0.2351, -1.0903, +0.0545, -0.6915, -0.4463, +0.2522, +0.0548, +0.0415, +0.1845, -1.2566, +0.3470, -0.1079, -0.1252, +0.3779, +0.2574, -0.1457, +0.6287, +0.2764, +0.0868, -0.3796, +0.1852, +0.2793, -0.1176, +0.0419, -0.3765, +0.2774, -2.0774, +0.1867, -0.3176, -0.0142, +0.1466, -0.0167],
-[ -0.2577, -0.3209, -0.2173, -0.9016, +0.1397, -0.0210, +0.0456, +0.3509, -0.3827, -0.4699, +0.0811, +0.1087, +0.3465, -0.3480, -0.0577, -0.1263, +0.1601, +0.1168, -0.3422, -0.1298, -0.8658, -0.3096, +0.0007, -0.2192, +0.1675, -0.2581, +0.0042, -0.3348, +0.2278, -0.3934, -0.1930, +0.1503, -0.1282, -0.0508, -0.1116, +0.0845, -0.1293, -0.4505, -0.3138, +0.2516, -0.8298, +0.2572, -0.2498, +0.0418, -0.4383, +0.1897, -0.0101, -0.0634, +0.4161, -0.1021, +0.0685, +0.0620, -0.0885, +0.0695, -0.3611, +0.2575, +0.0583, -0.3698, -0.0590, -0.0599, -0.0708, -1.1328, -1.4975, -0.4391, -0.0188, +0.2601, -0.3437, +0.0091, +0.1288, -0.1438, -0.7818, -0.5881, +0.1493, +0.1140, -0.2837, +0.0317, -0.3420, -0.2077, -0.0265, +0.2358, -0.0638, +0.2327, +0.2399, +0.0046, +0.3208, -0.2417, +0.1361, +0.1809, -0.1479, -0.2120, -0.0466, -0.4996, +0.0346, +0.0137, +0.1121, +0.0929, -0.0005, -0.2860, -0.8237, -0.1306, +0.3829, -0.0539, -0.4165, -0.1393, +0.0856, +0.1007, -0.2190, +0.5631, -1.2789, -0.0171, -0.3736, -0.0174, +0.0349, -0.4041, -0.0510, +0.1716, -0.6770, -0.0002, -0.3129, -0.7005, -0.9493, +0.0616, -0.2887, +0.0076, +0.2085, -0.6462, +0.1981, +0.1615],
-[ +0.3304, +0.1152, -0.6717, +0.1143, +0.2115, +0.0698, -0.1820, +0.1726, -0.0369, +0.0439, +0.1313, -0.1625, -0.0757, +0.0836, +0.0388, +0.1446, +0.0832, +0.0089, -0.4948, -0.0825, -0.3839, -0.4609, +0.1577, -0.0576, +0.0792, -0.0768, +0.1828, +0.3302, -0.1742, -0.3798, +0.0916, +0.1784, +0.0494, +0.0835, +0.0700, +0.1665, +0.3586, -0.6019, +0.2448, +0.6077, +0.1405, -0.1039, -0.0866, -0.0915, -0.0754, +0.2220, -0.5158, -0.5315, +0.2973, -0.0670, +0.0497, +0.2268, +0.1621, +0.0508, +0.0365, +0.3368, +0.3022, +0.3330, +0.2109, -0.3269, -0.3239, -0.2013, +0.2996, +0.1457, -0.2253, -0.3094, +0.1806, +0.1514, +0.2331, +0.0763, -0.1444, -0.1580, +0.3315, -0.5235, +0.2613, +0.1944, +0.1859, +0.3933, +0.4284, -0.2695, +0.1532, -0.0814, -0.6060, -0.1824, -0.2279, -0.3816, -0.9168, -0.2387, +0.0473, +0.0513, -0.0929, -0.2477, +0.0768, +0.4879, -0.5346, -0.4995, -0.2313, +0.0707, -0.0713, -0.1675, +0.2942, +0.0147, +0.2039, +0.3673, -0.0179, -0.4249, +0.0179, -0.4301, -0.2318, -0.0834, -0.3560, +0.1333, -0.0454, -0.3471, +0.2927, +0.2090, +0.1567, -0.2355, +0.0565, -0.2313, -0.0992, -0.4685, +0.0392, +0.0334, -0.4125, -0.0562, +0.1348, -0.0555],
-[ +0.2765, +0.2651, -0.1661, +0.0773, -0.1170, -0.0005, +0.1935, +0.2157, -0.0871, -0.0412, +0.2278, +0.0088, +0.5312, +0.1020, +0.4036, +0.1912, +0.1202, -0.2561, +0.0533, -0.3085, -0.3528, -0.2470, +0.8043, -0.1908, +0.3315, -0.0677, -0.2639, -0.7734, -0.0086, -0.8340, +0.1080, +0.3147, -0.0394, -0.1705, -0.6031, +0.5434, -0.0039, -0.0621, +0.1619, +0.6574, -0.3513, +0.4419, -0.0093, -0.3592, -0.3253, +0.2011, +0.3291, +0.4329, -0.2797, -0.0186, -0.6435, +0.2140, +0.0672, -0.3524, +0.1114, +0.0474, -0.7333, -0.2670, +0.1535, -0.8170, +0.3432, -0.4108, -0.1007, +0.1650, -0.0829, -0.4034, -0.3486, -0.0583, +0.2539, -0.0878, -0.9101, -0.2531, +0.2064, -0.3594, -0.1831, +0.2126, +0.4375, -0.0240, +0.1841, -0.3827, -0.3310, -0.3788, +0.0986, -0.7037, -0.1839, +0.2655, +0.0209, -0.1485, +0.3097, +0.1903, -0.0578, +0.1213, +0.0722, +0.3004, +0.4606, +0.0119, -0.0622, +0.0207, -0.6240, -0.2635, +0.3157, +0.1758, -0.3678, +0.3457, -0.3850, -0.4129, -0.5109, +0.3018, -0.2841, -0.7261, +0.1670, -0.2980, +0.0840, -0.0656, +0.2121, -0.0174, -0.1468, -0.6263, +0.2111, -0.8132, +0.1847, -0.1166, -0.1332, -0.1358, -0.1872, -0.5252, +0.0908, -0.3466],
-[ -0.3072, +0.0593, -0.2193, +0.4342, -0.0824, -0.0014, -0.1008, -0.2842, +0.0379, +0.2284, +0.0750, +0.1432, -0.2198, -0.2522, -0.3912, +0.0649, -0.1187, +0.2494, -0.0734, +0.1627, -0.2980, -0.2779, +0.3082, -0.2920, +0.5340, -0.1274, -0.2058, +0.0024, +0.0237, +0.3097, -0.2613, +0.0268, +0.0602, -0.0818, +0.0302, -0.7059, +0.1893, +0.1382, -0.3246, -0.9833, -1.0995, +0.0738, +0.2231, -0.2223, -0.2500, +0.3808, +0.2266, -0.4070, +0.1142, -0.6488, -0.1621, +0.2094, -0.2307, -0.4893, +0.0355, +0.0290, -0.1048, -1.1536, -0.5460, -0.1715, -0.0416, +0.5042, -0.3416, -0.1424, -0.0845, -0.0123, +0.2568, +0.1480, -0.8059, -0.6547, +0.1523, -0.1598, -0.1313, -0.3420, +0.0431, +0.2401, -0.1837, +0.1552, +0.1038, +0.1037, -0.2919, +0.0035, +0.0380, -0.1548, -0.1816, -0.4945, +0.2192, +0.2169, +0.4100, -0.6803, -0.2764, +0.3512, +0.0954, -0.2026, +0.2252, -0.2983, +0.2042, -0.5496, +0.0732, -0.0592, -0.1785, -0.2568, +0.1295, -0.1812, -0.1574, -0.1005, -0.1900, -0.2671, -0.2191, -0.1296, +0.3192, -0.0245, +0.1966, +0.3232, -0.1156, +0.3218, +0.3045, +0.1002, -0.3261, +0.3375, -0.1016, +0.1813, -0.5060, -0.0189, -0.0428, +0.0821, -0.1383, -0.0483],
-[ -0.0485, -0.0761, +0.2687, -0.3376, -0.0789, -0.3058, -0.1430, -0.6755, +0.2649, +0.7666, -0.2482, -0.4595, -0.0853, -0.3108, -0.1604, -0.1217, -0.4340, +0.2198, +0.0220, -0.3623, +0.6541, -0.2147, -0.1381, -0.3438, -0.1808, -0.1435, +0.2867, -0.9132, -0.2100, -0.6305, -0.3223, +0.0752, -0.0067, +0.0911, -0.0818, -0.3216, -0.1769, +0.1011, -0.2282, +0.1190, -0.1974, -0.0207, -0.3438, -0.0572, -0.2476, -0.2491, -0.1069, -0.4519, +0.1434, +0.2403, -0.3082, +0.0892, +0.0322, +0.0599, +0.0814, -0.3499, +0.0373, -1.0612, +0.0223, +0.1832, +0.0886, +0.0553, -0.0571, +0.2441, -0.3607, -0.1565, -0.2459, -0.0615, -0.7580, +0.2557, -0.9257, +0.0689, -0.0736, -0.2414, +0.1422, +0.2079, -0.4424, -0.3469, -0.0933, +0.3856, -0.0750, -0.1159, +0.4371, +0.1831, +0.1788, +0.0338, -0.0747, -0.4103, +0.3391, -1.0040, +0.4627, +0.1272, +0.2411, -1.0926, -0.2224, -0.1995, +0.1803, -0.0627, -0.6347, -0.1275, +0.2026, -0.0792, -0.0308, +0.1798, -0.0517, +0.2374, -0.4876, +0.0377, -0.4819, -0.0827, -0.2996, -0.4329, +0.3787, -0.1345, +0.1394, +0.3466, +0.1525, +0.3288, -0.0679, -0.6395, +0.0492, +0.2418, -0.2533, +0.2143, -0.6310, -0.7643, +0.3824, -0.5283],
-[ -0.2216, -0.2724, -0.3635, -0.5285, +0.2326, -0.0175, -0.1538, +0.0782, +0.6778, -0.3808, -0.1319, +0.1996, -0.1311, -0.3252, +0.4766, -0.1242, +0.5385, -0.1809, -0.0201, -0.1445, -0.2975, -0.3141, -0.0635, -0.1437, -0.1520, +0.2272, -0.1175, -0.6078, -0.0450, +0.0698, -0.0833, -0.0208, -0.9297, -0.7583, -0.8347, -0.2802, -0.1081, -0.2378, +0.0218, -0.3091, -0.3305, +0.0505, -0.1155, -0.9380, +0.0521, +0.4455, +0.2421, +0.2943, -1.0620, -0.1135, +0.1517, +0.2703, +0.1553, +0.1838, -0.0901, +0.4649, +0.0869, +0.0020, -0.3046, -0.1267, +0.2966, -0.0340, +0.0251, -0.0225, -0.4745, +0.1096, +0.4214, +0.0260, -0.9900, +0.1529, +0.0409, +0.0435, +0.4192, +0.1484, +0.2290, +0.3483, +0.0416, +0.0547, +0.2778, +0.0500, +0.1722, -0.2871, +0.1912, -0.1819, +0.0170, -0.1954, +0.1159, +0.1133, +0.0251, -0.5399, +0.1444, +0.2560, +0.2234, +0.0129, +0.1838, -0.0347, +0.1374, -0.3880, +0.4386, -0.5715, -0.0648, -0.1808, -0.1905, +0.1060, +0.0285, +0.0654, +0.1420, -0.3763, -0.3592, +0.1827, +0.0626, -0.0212, -0.1470, -0.0439, +0.3878, -0.5607, -0.0129, +0.0216, +0.0846, +0.2230, -0.8648, +0.0159, +0.3718, -0.0508, -0.5289, -0.7366, -0.0457, +0.4186],
-[ -0.0214, -0.0530, +0.0137, -0.2432, -0.0927, -0.2797, +0.0852, -0.4463, -0.0110, +0.2777, -0.1540, +0.1232, +0.1111, +0.0501, -0.0242, +0.3283, +0.1690, +0.7622, -0.3503, -0.2473, +0.0353, -0.3887, -0.4612, -0.1503, +0.0814, +0.3865, -0.1694, +0.0120, +0.4389, -0.0711, +0.1713, +0.3489, +0.0682, -0.2548, -0.2882, -0.0319, +0.3242, -0.4394, +0.3936, +0.0420, +0.2637, -0.4346, -0.2826, -0.1212, -0.2662, +0.0626, +0.1920, +0.1084, -0.1428, -0.1077, +0.4388, -0.4603, +0.0879, -0.1445, +0.0940, +0.1186, -0.0631, -0.5513, +0.2869, +0.0772, +0.3672, -0.6910, -0.0244, +0.2878, +0.2721, +0.0819, -0.2527, -0.0537, -0.1003, +0.3021, +0.1214, -0.0519, -0.1527, -0.1574, -0.0269, -0.1360, +0.1854, +0.4206, -0.0306, -0.2780, -0.0115, -0.1752, -0.3788, -0.2699, +0.1797, +0.1841, +0.1184, -0.1995, -0.2032, -0.0399, +0.0875, -0.5725, +0.4417, +0.2053, +0.0468, +0.4927, +0.1521, -0.1696, +0.0752, -0.3104, +0.5265, +0.1238, -0.2677, +0.0530, +0.2844, +0.1389, -0.0011, +0.1489, -0.0156, +0.0328, -0.8756, -0.1634, +0.3669, -0.4764, +0.2505, +0.4518, -0.2778, -0.0361, -0.2592, +0.2754, -0.9665, +0.0985, -0.0931, -0.1472, -0.0249, +0.1736, -0.0344, +0.4884],
-[ +0.0076, -0.0792, +0.4573, +0.2103, -0.3263, +0.5124, -0.1254, -0.3027, +0.4467, +0.1534, -0.0088, +0.0828, +0.1483, -0.0149, +0.3330, -0.1840, -0.8589, +0.1954, +0.1535, +0.2053, -0.1536, -0.3341, +0.2597, -0.6422, +0.0675, -0.2398, +0.3120, -0.7673, +0.1112, -0.3301, +0.0317, +0.0886, +0.0414, -0.2466, -0.1473, -0.7178, +0.4703, -0.4728, +0.1195, +0.4448, -0.3061, -0.6861, -0.3048, -0.2956, +0.3244, +0.4717, -0.4695, +0.5288, -0.6678, -0.0470, -0.0538, -0.1436, -0.9947, -1.1587, +0.0508, -0.2462, +1.0473, +0.2293, +0.4339, +0.3946, -0.2774, +0.0805, +0.1161, +0.6042, +0.4060, -0.2910, -0.5440, +0.1522, -0.3688, -0.9751, -0.8646, -0.4894, -0.3640, -0.3734, +0.2146, +0.2350, +0.1571, +0.2132, -0.0705, +0.0330, +0.1605, -0.0053, -0.1780, -0.9285, +0.0206, -0.5987, -0.2628, +0.3601, +0.1762, +0.2956, -0.0877, +0.1974, -0.0082, +0.5044, +0.2951, -0.1490, -0.5688, -0.4528, -0.4916, +0.2803, +0.0985, +0.0523, -0.2049, -0.0192, +0.2865, -1.0200, -0.1378, +0.1502, +0.4630, -0.1785, -0.2855, -0.5179, -0.2046, +0.2921, +0.0592, +0.0598, -0.5597, +0.0560, +0.5616, -0.0732, -0.0935, -0.0076, -0.0293, -0.0054, -0.5336, -0.0486, -0.0284, -0.7210],
-[ +0.0138, +0.1312, -0.5257, -0.4086, +0.0728, +0.1993, +0.1312, +0.0431, +0.0887, -0.0362, -0.2398, -0.2054, -0.0455, -0.0584, -0.2373, +0.2380, +0.2169, +0.0082, +0.2734, -0.1091, -0.4689, +0.2916, -0.1617, -0.1124, -0.1273, +0.0680, -0.0110, +0.0820, +0.0190, -0.2237, -0.2111, +0.0737, +0.1487, +0.1199, +0.3229, -0.1435, -0.1576, +0.2985, -0.4750, +0.2688, -0.4223, +0.3317, +0.1938, -0.0482, +0.2846, -0.1528, -0.1198, -0.3543, -0.1499, +0.1163, +0.2298, +0.0175, +0.2827, +0.1979, -0.1932, +0.3102, -0.0683, +0.1764, -0.0746, +0.0251, +0.2647, -0.3658, -0.4789, +0.3222, +0.1481, +0.0715, +0.1229, +0.2837, -0.3743, -0.1212, -1.3068, +0.1790, +0.3244, -0.2563, -0.2422, +0.2098, -0.2671, +0.3374, -0.1205, -0.7220, +0.4286, +0.3452, +0.1179, +0.4031, -0.3413, -0.6037, +0.2143, -0.2744, +0.2182, +0.4431, -1.0548, +0.1050, -0.0165, -0.2962, -0.2426, -0.1212, -0.1963, +0.2281, -0.6649, +0.0373, +0.0941, +0.1760, +0.1101, +0.0707, -0.6022, -0.0103, -0.3880, -0.4686, +0.4758, -0.5176, +0.1639, -0.0607, -0.6359, -0.2935, -0.1718, -0.2972, -0.3843, -0.0077, -0.7114, -0.0130, -0.2512, -0.2410, -0.2260, +0.2555, -0.2789, +0.1600, +0.1542, -0.1273],
-[ -0.2428, +0.3061, +0.2298, -0.4761, -0.3310, +0.1217, -0.4854, -0.0608, +0.0785, +0.0976, +0.0841, +0.0917, +0.3270, -0.5238, +0.0938, -0.4166, -0.1472, -0.0707, +0.0508, -0.2121, -0.2691, -0.3868, +0.3209, +0.1520, -0.3473, +0.3797, +0.1491, -0.0827, +0.0303, -0.0662, -0.0583, -0.0114, -0.2137, -0.0716, -0.2505, +0.0234, +0.1942, -0.2429, -0.1812, +0.2127, -0.3146, -0.0560, -0.1975, -0.2884, +0.1577, -0.1066, +0.3612, -0.4182, +0.3614, +0.1490, +0.2338, -0.1749, +0.1586, -0.1450, -0.3109, +0.0085, +0.2919, -0.5191, -0.4061, +0.3164, -1.2844, -0.0685, -0.0588, +0.0751, -0.3219, +0.4100, -0.0801, -0.3325, +0.1215, +0.2556, -0.3045, -0.4596, -0.0324, +0.0205, -0.0232, +0.1530, +0.0951, -0.2800, +0.0506, -0.5846, -0.1273, -0.0996, +0.2067, +0.1167, +0.3611, -0.0991, -0.1651, -0.3704, -0.1254, -0.3887, -0.1392, +0.2495, -0.1188, -0.5125, -0.7474, +0.2729, -0.2425, -0.3024, +0.1678, -0.0371, -0.1116, -0.4206, -0.2825, -0.0830, +0.0164, +0.3703, -0.5570, -0.2507, -0.2276, +0.3190, -0.4609, -0.1061, +0.1248, -0.1382, +0.0740, +0.0562, +0.0275, +0.2151, -0.1987, -0.6144, -0.0418, +0.2406, -1.1566, +0.1270, -0.4743, +0.0390, -0.0635, -0.0234],
-[ +0.1849, +0.2056, -0.8912, +0.1386, -0.2061, +0.2078, +0.0089, -0.5197, -0.3154, -0.3073, -0.4449, +0.1493, +0.4017, -0.4632, +0.0683, -0.0695, -0.2991, -0.1667, -0.8045, -0.2511, -0.2451, +0.4418, +0.2032, +0.1380, -0.1905, -0.2897, +0.0508, -0.0452, -0.0836, +0.1389, +0.1278, -0.0631, +0.0659, -0.0119, -0.4652, +0.0809, -0.0130, +0.1559, -0.2362, -0.0178, +0.4270, +0.2486, -0.0051, -0.1884, -0.2139, -0.6266, -0.2996, -0.6199, -0.1317, +0.0074, +0.4751, +0.2395, +0.2592, +0.1341, -0.0190, -0.2331, +0.2688, -0.7262, +0.2291, -0.1426, -0.0483, -0.0462, -0.1390, +0.1052, -0.6746, +0.1354, -0.0905, +0.1046, -0.1011, +0.0623, -0.6305, -0.6835, -0.2048, +0.0765, +0.2925, -0.0006, +0.4725, -0.5182, -0.1838, +0.1910, -0.4000, +0.0748, -0.5708, -0.1253, -0.1979, +0.4603, +0.2264, -0.1244, -0.1174, +0.1527, -0.0043, -0.0938, -0.1171, -0.2813, +0.1696, -0.7883, +0.0192, +0.0551, -0.6117, +0.1119, -0.5844, -0.5764, -0.0239, +0.0728, -0.0364, -0.3200, -0.2571, +0.1682, -0.0850, -0.1715, -0.2180, +0.4132, +0.1072, +0.3502, +0.2404, +0.0948, +0.0001, +0.0032, +0.0910, -0.0538, +0.4683, -0.1478, -0.0923, +0.0925, +0.3624, -0.3939, -0.1887, -0.0461],
-[ -0.6513, -0.0528, -0.0799, +0.0180, -0.0639, +0.1353, +0.1291, -0.4689, -0.1285, +0.0403, -0.0495, -0.2101, -0.0562, +0.0413, +0.3756, +0.2829, -0.4205, +0.0386, -0.2373, +0.1858, -0.1519, -1.2870, +0.0758, -0.0572, -0.0928, +0.0717, +0.2179, -1.3161, +0.0086, -0.3917, -0.3191, -0.1952, -0.4163, +0.1665, +0.0394, +0.1485, -0.3066, -0.5259, +0.0706, -0.1073, -0.7096, -0.3626, -0.2640, -0.3450, -0.0300, -0.0195, -0.2554, +0.3610, -0.6629, -0.0244, +0.0810, +0.1760, -0.1691, -0.0746, -0.1397, +0.2106, -0.3880, -0.8769, -0.1162, -0.3865, +0.4369, +0.0547, -0.2496, +0.2524, +0.2667, -0.1418, +0.0266, -0.3762, -0.0858, +0.0070, +0.1271, +0.3415, +0.3415, +0.0483, +0.4017, -0.0354, -0.3031, +0.3032, +0.1559, -0.0946, +0.3062, -0.2216, +0.1691, -0.0621, +0.3155, +0.2635, +0.2077, +0.0959, +0.0565, +0.2541, +0.0393, +0.0420, +0.1090, -0.3292, -0.2852, -0.1791, -0.3682, +0.3089, -0.0278, +0.0165, -0.2482, -0.0125, +0.1965, -0.2145, +0.2043, -0.7790, -0.2388, +0.1049, -0.0955, -0.0739, -0.3513, -0.7518, -0.0023, -0.1168, +0.2432, +0.1824, -0.4548, -0.1216, +0.2842, +0.0144, +0.1611, +0.1462, +0.4332, -0.4961, +0.0503, -0.1672, -0.2520, +0.0050],
-[ -0.4374, +0.0677, +0.1759, -0.0717, -0.5386, +0.0776, -0.0142, -0.5765, -0.3650, +0.3188, -0.7733, -0.4377, -0.7963, -0.3026, -0.2102, -0.8911, -0.4924, +0.3700, -0.0042, -0.4664, -0.1002, -0.1016, -0.1787, +0.1152, -0.0962, -0.2385, -0.0872, -0.2961, -0.1030, +0.1671, -0.2583, -0.2238, -0.1293, -0.0782, -0.4061, -0.3127, +0.1150, +0.1069, +0.0334, +0.2424, -0.0779, +0.1749, +0.1685, +0.4895, -0.4784, -0.5112, +0.3653, -0.3491, -0.0358, -0.0161, -0.7627, -0.2534, -0.1499, -0.6884, +0.1699, +0.1398, +0.0126, -0.6539, -0.5635, +0.3513, +0.0543, +0.4240, -0.0515, -0.6213, -0.1297, +0.5964, +0.2096, +0.0586, -0.3029, +0.1138, -0.5396, -0.2229, -0.8885, -1.1727, +0.0485, -0.2309, +0.2224, +0.3499, -0.0101, +0.0408, +0.1950, +0.1235, -0.3856, +0.0873, -0.3156, -0.1496, -0.0588, -0.2328, +0.2851, +0.3854, +0.1741, +0.1355, +0.0666, -0.2230, +0.0363, +0.3607, -0.8664, +0.0231, -0.1652, -0.2408, -0.2333, +0.1644, -0.5628, +0.2266, -0.0874, -0.7965, +0.4027, +0.1313, -0.0736, +0.3931, +0.1241, -0.5326, -0.1481, -0.2934, +0.3501, -0.5848, -0.3682, -0.0025, -0.0314, +0.0481, +0.1469, -0.2880, -0.2509, +0.0841, -0.2406, -0.1403, -0.3320, -0.1264],
-[ +0.2835, -0.2385, +0.0157, -0.1775, -0.0661, +0.2835, -0.2914, -0.0802, +0.0005, -0.9043, +0.3188, -0.0884, +0.1066, -0.4199, -0.4391, -0.2280, -0.6856, +0.0331, -0.9060, +0.1107, +0.1094, +0.2466, -0.1458, +0.0564, -0.8896, -0.7002, -0.1500, +0.3055, -0.1778, -0.1791, +0.1248, +0.0839, +0.0610, +0.0625, -0.0862, -0.0261, -0.1398, -0.1335, -0.6727, +0.2547, -0.7196, +0.1070, +0.2992, +0.0814, +0.0297, +0.0174, -0.1268, -0.2557, -0.8446, -0.0955, -0.1967, -0.1212, +0.1532, -0.5281, -0.1994, +0.1381, +0.1805, -0.5466, +0.0128, -0.1981, +0.3126, +0.1236, -0.3552, -0.0086, -0.4803, -0.1862, +0.0102, +0.0481, -0.3328, +0.1807, -0.3255, -0.5793, +0.1044, +0.0913, +0.0427, -0.0351, -0.7696, -0.1137, -0.0585, -0.0956, +0.2934, +0.1989, +0.4311, -0.3571, +0.1281, +0.1825, -0.0877, +0.1746, +0.3465, -0.0489, -0.0920, -0.1478, -0.2537, +0.0394, -0.2832, +0.1150, +0.1023, +0.0576, +0.1433, +0.1745, +0.2718, +0.0142, +0.1164, -0.1714, +0.0859, -0.1570, -0.0102, +0.3979, -0.4980, -0.0764, -0.5556, -0.3163, +0.0547, -0.1635, +0.1372, +0.2434, -0.0717, +0.1115, +0.0103, +0.2736, +0.1025, +0.3237, +0.1072, -0.1598, +0.2211, -0.9020, -0.0138, -0.0541],
-[ +0.5913, -0.1232, +0.4854, -0.9341, -0.0232, -0.2916, -0.0394, -0.6606, +0.2191, +0.5984, -0.3938, -0.0504, -0.0565, -0.5473, -0.1880, +0.7157, -0.0056, -0.4979, -0.2422, +0.0283, -0.0454, -0.1495, +0.1372, -0.1654, -0.0747, +0.0656, +0.0167, +0.3254, +0.2891, -0.4931, +0.0534, -0.2193, +0.0124, +0.0179, -0.2722, +0.1878, +0.0150, +0.2374, -0.6084, -0.2652, -0.2618, +0.0132, -0.0302, +0.0346, -0.1478, -0.6839, +0.0778, -0.3381, +0.2921, -0.1248, +0.2446, +0.0116, -0.4571, -0.1960, +0.5189, -0.6623, +0.2867, -0.5312, +0.5299, -0.0400, -0.3333, +0.3019, +0.7214, -0.6399, +0.0920, +0.0674, -0.2953, -0.3731, -0.1957, +0.2722, +0.5687, +0.1900, -0.1495, +0.2474, +0.5458, -0.0210, +0.3382, +0.1387, +0.3749, -0.7159, -0.2116, +0.2044, +0.0299, -0.6997, -0.0607, -0.1249, +0.4435, +0.1194, -0.3956, -0.3680, +0.7815, -0.3192, -0.2005, +0.6671, +0.1049, +0.1786, -0.0453, +0.0361, +0.3828, +0.1632, -0.2219, +0.0587, -0.0778, +0.2726, -0.1161, -0.8251, -0.9922, -0.1238, -0.2244, -0.0043, -0.8359, -0.4257, +0.3097, -0.0342, -0.6175, +0.1667, +0.2046, -0.4767, -0.5294, +0.3274, +0.6918, -0.2039, +0.0763, -0.1972, +0.2738, -0.1745, +0.3617, -0.1313],
-[ +0.3985, -0.7089, -0.0332, +0.0505, +0.0036, -0.0961, -0.0241, +0.2885, -0.2104, +0.0825, +0.2986, +0.1737, -0.1259, -0.6318, -0.5804, -0.4030, -0.5987, -0.4087, +0.0740, -0.4228, +0.0196, -0.0847, -0.1110, +0.1669, +0.2755, -0.6475, +0.1167, -0.0541, +0.1044, -0.0361, -0.1183, +0.1291, -0.0599, +0.1331, -0.2997, +0.2303, +0.1575, +0.3870, -0.1515, -0.4865, -0.6648, +0.1327, +0.1144, +0.0974, +0.0034, -0.2743, +0.0202, -0.1749, -0.1239, -0.3202, -0.3870, +0.0799, -0.1327, +0.0868, +0.3767, +0.1424, +0.1184, +0.4465, -0.1336, -0.0741, -0.3882, +0.1285, -0.3939, -0.7510, -0.6497, -0.2128, -0.4897, -0.1906, +0.2443, -0.0178, +0.2300, +0.1188, -0.1663, -0.2625, +0.1943, -0.1735, +0.1914, -0.3450, -0.7589, -0.1376, -0.2713, -0.5135, +0.1341, -0.1255, +0.1950, +0.0079, +0.1064, +0.1392, -0.1342, -0.5934, +0.2223, -0.7193, -0.3631, -0.0109, -0.6700, -0.0695, +0.3342, -0.3029, -0.4486, -0.3059, -0.1220, +0.0722, +0.1273, +0.0583, -0.4831, +0.1510, -0.1138, +0.0517, -0.1325, -0.2582, +0.2351, -0.1619, -0.0685, +0.0409, +0.1921, -0.5289, -0.8433, -0.3236, +0.1013, -0.0917, -0.4555, +0.2112, +0.5211, +0.0347, -0.0369, -0.0381, +0.1335, +0.0780],
-[ +0.3391, -0.1031, +0.5497, -0.0912, -0.0822, +0.0400, +0.0104, -0.2520, -0.2326, -0.1946, +0.1817, +0.1504, -0.1373, -0.3782, +0.2782, -0.0811, -0.1670, -0.0752, -0.0038, +0.0659, -0.1489, +0.0530, -0.1602, +0.2660, +0.3501, -0.3531, +0.0742, +0.4502, -0.1074, +0.3760, +0.3817, +0.3847, -0.0346, -0.2125, -0.3708, +0.1074, -0.5406, +0.6945, +0.0836, +0.5442, -0.0731, +0.1704, -0.2789, -0.2147, -0.1203, -0.4953, -0.2338, -0.6956, -0.2753, -0.2008, +0.3548, +0.2988, -0.0777, -0.1839, +0.2720, -0.3387, -0.0846, +0.2037, +0.1424, +0.1685, -0.0319, -0.2133, +0.2418, -0.2023, +0.0885, -0.2266, -0.0139, +0.1143, +0.2558, +0.1364, -0.0488, -0.3719, +0.1516, +0.0701, -0.0487, -0.1628, +0.6667, -0.0374, -0.0616, -0.6835, +0.3366, +0.3745, +0.3795, -0.3324, +0.0391, +0.1536, +0.4374, +0.3632, -0.1966, -0.3302, +0.0733, +0.2078, +0.1054, -0.1593, -0.4613, -0.0141, -0.1862, +0.3851, -0.3174, +0.1968, -0.2634, +0.0754, +0.0973, +0.4310, +0.0077, +0.1042, +0.5596, +0.1151, -0.0996, +0.2052, +0.0175, -0.1184, -0.0746, -0.0426, +0.1649, -0.1099, -0.1221, -0.8761, +0.1507, +0.0753, -0.1373, +0.0390, +0.3692, +0.0726, +0.1944, -0.3016, -0.0347, -0.0190],
-[ +0.1592, -0.9045, -0.3388, +0.2854, -0.3764, -0.2765, -0.2451, +0.2391, -1.0949, +0.0841, +0.3115, -0.3353, -1.3785, +0.1600, +0.3432, +0.2445, +0.1564, +0.0087, +0.3491, -0.5923, -0.2462, -0.4761, -0.4795, +0.1626, -0.1966, -0.2813, -0.1815, -0.1901, -0.4001, +0.0344, -0.1321, +0.0140, -0.3800, +0.1196, -0.1599, -0.2739, +0.0795, -0.2032, +0.3463, +0.0708, +0.2574, -0.0073, -0.2222, -0.2274, -0.1679, +0.0262, +0.3934, -0.0947, +0.3593, -0.0873, -0.4258, -0.1662, -0.2950, +0.0077, -0.0881, -0.3166, -0.4573, -0.0139, +0.1009, +0.1217, +0.3329, +0.2159, +0.2382, +0.0680, +0.2457, +0.0094, -0.1908, +0.4279, -0.4443, +0.0266, +0.3519, +0.1389, -0.9522, -0.1226, +0.1761, +0.0645, -0.3624, -0.0373, -0.6709, -0.6824, +0.0779, +0.4334, -0.1997, +0.2059, -0.2751, +0.4227, +0.1345, +0.3756, -0.6810, +0.1684, +0.0572, +0.0989, -0.7624, -0.0815, +0.0952, -0.1433, -0.1627, -0.0365, -0.4531, -0.3340, -0.3930, +0.0047, -0.7260, -0.7704, -0.1741, -0.6385, -0.2428, -0.2376, -0.2202, +0.3776, +0.3622, +0.3179, -0.5478, -0.0946, -0.4054, -0.3539, +0.1668, -0.3799, -0.6982, +0.2685, -0.1232, -0.1367, +0.1098, -0.0299, +0.2043, +0.4321, +0.6063, -0.1830],
-[ +0.0292, -0.0010, +0.2158, -0.4331, -0.0310, +0.0424, +0.3919, -0.7883, +0.2159, +0.1283, +0.1814, -0.1074, +0.2870, +0.3619, -0.0246, +0.1734, -0.2848, +0.0568, +0.2306, +0.1180, +0.3157, -0.5900, -0.2666, -0.6148, -0.2705, +0.4858, +0.0142, -0.2339, +0.3535, +0.3406, +0.0438, -0.1729, +0.1806, +0.1529, -0.3753, +0.1985, -0.6612, -0.0589, +0.2622, +0.3362, -0.3548, +0.0882, +0.0478, -0.0368, +0.1482, +0.2514, +0.1228, -0.1455, -0.1251, +0.0611, +0.0816, +0.0377, -0.1065, +0.0500, -0.3750, -0.2686, -1.3232, -0.3649, -0.5384, -0.3742, +0.1670, -0.3885, -0.0707, +0.4238, -0.0005, +0.3778, -0.9734, +0.3905, +0.6022, -0.0947, -0.7236, -0.1353, +0.0807, -0.8187, -0.0729, -0.3487, -0.1654, +0.2132, +0.0264, +0.1123, -0.0456, +0.1316, -0.7286, +0.2312, -0.2189, -0.0716, -0.3669, -1.2613, +0.1973, -0.5447, +0.1262, -0.4810, +0.3795, -0.6663, +0.3199, +0.0797, +0.0648, -0.7192, +0.3327, -0.3189, -0.0497, -0.3963, -0.2406, -0.2792, +0.0374, +0.1829, +0.1853, -0.0994, -0.7060, -0.1172, -0.0547, -0.2612, -0.9416, -0.3015, -0.0489, +0.0872, +0.2002, -0.5830, +0.0093, -0.2521, -0.3983, -0.5610, -0.1444, -0.0213, -0.1840, +0.5584, +0.1573, -0.0839],
-[ -0.0054, -0.1552, +0.0445, +0.5473, +0.3489, +0.0942, +0.1283, +0.1088, +0.2221, +0.0951, -0.2887, -0.3084, +0.0476, -0.6876, -0.1634, -0.0490, +0.0768, +0.1582, -0.3275, -0.2437, -0.1178, -0.0054, -0.2570, +0.1724, +0.0588, -0.8220, +0.3945, +0.3071, +0.0125, +0.0827, +0.2293, +0.1611, -0.0184, +0.3169, +0.3854, -0.1290, +0.3770, +0.0940, +0.0282, +0.1175, -0.1819, +0.0814, -0.3593, +0.4649, +0.4170, -0.3505, -1.3469, +0.1904, +0.0756, -0.4528, -0.1058, +0.0501, +0.1074, +0.0082, +0.0061, -0.3440, -0.0304, -0.1088, -0.0586, +0.0032, -0.0331, -0.0033, +0.0723, -0.3142, -0.1265, -0.0172, +0.1410, -0.0386, -0.2496, +0.1728, +0.2118, +0.3957, +0.1726, +0.1006, -0.3493, -0.1489, -0.3966, -0.2837, -0.0478, -0.0989, +0.1569, +0.0148, -0.0214, -0.0335, -0.0149, +0.4945, -0.5369, -0.0122, -0.0322, +0.2602, +0.2476, -0.1682, -0.4900, +0.1432, +0.0293, -0.3913, -0.0559, +0.1990, +0.1417, -0.4177, +0.3085, -0.2313, +0.0765, -0.3012, +0.1796, -0.5680, +0.3003, +0.1191, -0.1923, -0.1704, -0.2999, -0.4388, -0.7674, -0.0022, +0.1210, +0.1297, -0.2887, +0.1796, +0.3751, +0.2259, -0.0375, -0.0734, +0.3011, +0.1191, -0.0989, +0.0234, +0.4871, +0.0155],
-[ -0.2794, +0.4030, -0.8714, +0.1589, +0.3095, -0.2938, -0.5479, -0.1597, -0.1159, -0.3491, +0.4800, +0.0262, +0.3959, -0.6992, -0.7997, -0.1646, +0.2888, -0.8217, +0.1957, +0.2923, +0.0236, +0.2229, +0.0514, +0.1859, -0.2631, -1.0410, +0.0539, -0.3402, -0.0101, -0.2683, +0.3238, +0.0962, -1.0021, -0.0456, -0.9495, +0.3728, -0.0316, -0.0075, +0.2809, +0.3721, -0.1940, +0.0839, -0.5128, +0.3385, -0.0146, +0.0474, -0.7893, -0.0244, -0.4119, -0.1384, -0.3560, -0.5578, +0.0636, -0.5752, -0.2949, +0.5623, +0.1826, -0.2331, -0.2763, +0.1912, -0.1321, +0.0604, +0.1944, -0.1728, -0.3342, +0.0470, -0.0843, +0.3187, -0.0226, +0.0507, -0.2920, -0.9700, -0.0704, -0.3181, -0.1028, -0.3946, -0.3361, +0.3495, +0.2483, +0.2804, -0.0085, -0.2937, -0.2936, -0.0616, -0.0207, -0.4355, +0.1786, +0.2164, +0.1249, +0.3248, +0.2681, -0.1227, +0.2755, +0.2102, -0.8579, -0.1426, -0.0127, +0.0146, +0.3679, +0.1330, +0.2826, +0.1176, -0.0155, +0.4931, +0.1725, +0.0041, -0.0312, +0.1938, +0.5592, -0.0589, +0.0588, -0.0504, +0.1824, +0.1543, +0.2127, -0.1573, +0.0825, -0.1487, +0.0773, -1.0069, +0.3602, +0.1695, -0.1658, -0.4918, -0.2411, -0.0045, +0.1308, -0.0919],
-[ -0.0144, -0.1173, -0.0091, -0.0784, +0.3286, +0.4062, -0.4460, +0.0764, -0.0014, -0.2451, -0.3954, +0.1172, +0.1226, -0.0482, -0.0108, -0.5943, +0.5661, +0.1431, -0.0304, +0.0496, -0.6318, +0.0808, -0.1243, +0.2488, -0.3727, +0.1838, -0.1293, -0.5253, -0.2261, -0.0610, -0.0719, -0.9734, +0.0533, -0.2570, +0.1856, +0.1661, -0.0942, -0.4841, +0.3055, -0.3630, -0.3041, +0.3149, +0.0270, -0.2742, -0.3865, -1.0538, -0.2327, +0.1288, -0.3333, -0.0792, -0.1043, -0.0144, -0.4203, -0.2229, -0.1949, -0.1688, +0.0234, +0.4592, -0.2843, +0.1205, -0.1586, -0.1057, -0.4400, +0.2341, -0.0925, -0.0170, +0.6462, -0.0736, +0.2749, +0.4940, +0.0412, +0.1284, -0.1656, +0.1447, +0.2860, +0.1238, +0.2212, +0.1228, -0.2901, +0.2669, +0.2428, +0.4930, +0.3968, -1.0630, -0.3707, -0.4179, -0.0529, +0.1792, +0.0515, -0.0135, -0.3825, +0.0324, -0.3215, +0.0142, -0.6385, -0.3276, -0.2980, -0.3898, -0.3575, +0.0054, +0.0518, +0.1864, +0.1134, -0.0957, +0.1494, -0.0553, -0.4238, +0.0880, -0.0626, -0.4486, -0.7110, +0.0714, -0.0491, +0.1992, -0.4954, -0.2394, -0.1724, +0.1084, -0.3245, -1.6636, +0.2524, -0.6147, +0.0663, +0.3333, -0.1083, -0.7804, -0.1384, -0.2598],
-[ -0.2018, -0.5408, +0.0414, +0.1091, +0.3718, +0.2390, +0.4673, -0.2912, +0.0094, -0.0723, -0.3211, -0.1889, -1.4788, +0.3892, +0.1359, -0.1354, -0.0398, -1.3709, -0.2299, +0.2701, -1.3452, -0.3284, -0.1971, -0.7869, +0.1948, +0.2171, -0.2420, +0.3016, +0.4040, +0.6372, +0.0466, -0.6071, +0.3696, -0.0766, +0.1127, +0.3249, +0.1572, +0.1858, +0.1178, +0.1339, +0.0237, -0.0347, -0.0048, -0.1617, -0.7564, -0.1252, -0.0638, -0.1959, -0.4785, -0.1408, -0.3030, +0.2420, -0.3357, -0.0812, -0.1504, +0.1962, +0.1617, +0.0325, -0.2494, -0.1924, +0.2825, -1.0908, -0.5430, -0.2254, -0.0517, -0.2560, -0.2175, -0.2357, -0.2966, -0.1681, +0.2224, -0.1229, -0.9143, -0.3390, +0.1872, +0.0530, -0.0697, -0.6127, -0.3514, +0.0880, -0.2166, -0.2539, +0.0688, +0.1428, +0.2118, +0.1108, -0.0943, +0.1286, -0.3968, +0.1960, -0.0700, +0.5808, +0.0374, -0.5084, -0.3881, +0.0575, +0.2369, +0.5628, -0.2804, +0.4851, +0.1104, +0.0284, -1.1431, +0.1047, -0.3442, +0.1048, -0.0653, +0.1550, +0.0134, -0.2567, +0.4448, +0.0309, +0.1873, +0.2369, +0.0031, -0.3404, +0.3019, +0.1128, -0.1842, +0.0481, -0.0884, +0.3235, -1.0687, -0.1321, +0.2978, -0.2362, +0.0378, +0.1971],
-[ +0.2535, -0.2242, -0.0908, +0.5499, -0.2328, -0.3475, +0.2398, -0.1673, +0.1231, -0.6901, +0.0918, -0.0608, +0.0751, +0.2779, -0.3674, -0.0832, +0.1389, +0.0036, -0.0265, -0.0870, -0.0760, -0.3173, +0.0605, +0.2014, -0.3164, -0.0104, -0.0169, -0.3861, -0.2773, +0.0635, +0.0945, -0.5024, +0.1406, +0.0821, -0.0719, -0.1437, -0.3810, +0.2135, -1.1224, -0.0387, +0.1928, +0.1379, +0.0183, -0.0645, -0.0482, +0.1046, -0.2203, +0.0935, +0.2519, -0.2642, +0.1156, -0.3227, -0.1677, -0.2038, +0.0520, +0.0623, -0.1027, +0.0175, -0.0584, +0.0420, +0.1626, -0.8398, -0.0657, -1.0170, +0.0191, -0.9715, +0.0380, -0.1604, -0.6074, -0.0295, -0.2755, +0.1088, -0.1964, +0.2977, -0.3666, -0.3127, +0.2279, +0.0716, -0.5187, +0.1724, +0.1011, +0.0378, -0.5323, +0.0495, -0.5084, +0.0564, +0.0451, +0.1388, +0.0659, -0.0164, +0.1866, -0.4834, +0.0857, +0.0201, +0.1044, -0.0152, +0.1856, +0.4617, +0.0526, -0.0806, -0.1098, +0.0640, -0.1741, -0.1642, -0.1463, -0.2830, +0.0557, -0.3862, +0.4099, -0.3520, -0.0970, +0.2255, +0.0056, +0.2791, -0.3706, +0.2901, -1.1393, +0.2312, -0.0597, +0.1108, -0.1686, -0.3515, -0.0123, +0.6058, +0.0172, +0.1834, +0.1619, +0.0642],
-[ +0.1424, +0.2771, -0.4119, -0.4453, -0.0806, -0.0313, +0.0615, +0.0926, -0.0154, +0.1544, +0.0413, -0.0090, +0.0009, +0.1263, -0.5136, +0.1391, +0.1423, -0.2059, +0.3629, +0.0897, -0.2172, -0.0581, -0.4607, -0.6676, +0.2999, +0.1044, -0.0923, +0.0546, +0.1458, -0.0486, +0.0829, -0.4731, +0.0825, -0.4984, -0.2204, -0.0278, +0.1608, +0.3046, +0.0612, +0.0308, -0.1741, -0.1062, -0.1894, +0.3414, +0.3394, +0.2683, -0.5036, -0.4462, +0.1405, -0.0271, -0.1875, +0.3876, -0.0901, +0.1749, +0.2442, -0.6949, -0.3359, -0.3871, -0.1453, -0.6950, -0.1424, +0.1110, -0.0955, +0.1216, +0.3672, -0.1412, -0.1766, +0.0060, -0.1309, +0.0924, -0.0070, -0.0084, -0.7878, +0.0983, -0.2382, +0.3212, -0.0379, -0.0494, -0.4345, -0.3754, +0.1283, +0.1056, +0.1202, +0.2826, -0.2463, +0.2949, -0.3612, -0.0565, -0.1518, +0.1379, -0.4485, -0.4255, -0.0535, -0.8579, +0.3174, -0.0837, -0.0182, +0.0520, -0.1110, +0.1957, +0.4089, +0.0444, +0.1904, +0.0056, +0.1465, +0.2565, -0.5486, -0.6667, -0.0006, -0.8126, -0.1335, -1.0578, +0.1406, -0.3655, +0.1303, -0.0280, +0.3007, +0.2532, -0.0795, +0.0004, -0.1005, +0.3299, +0.0909, -0.3170, +0.1544, +0.3338, +0.0422, +0.0507],
-[ +0.4021, -0.5260, +0.0290, -0.7127, +0.3292, +0.3961, -0.4303, -0.1401, +0.1137, +0.1113, -0.2227, -0.2856, +0.1078, -0.5298, -0.2920, -0.3745, -0.7590, +0.1277, -0.5133, -0.5365, -0.0345, +0.3073, +0.0114, +0.5255, +0.2158, +0.2393, +0.2765, +0.0396, +0.1927, -0.1368, +0.0504, -0.1286, +0.2574, -0.3011, +0.0240, +0.1241, +0.0423, -0.2273, -0.0235, +0.0078, -0.6403, -0.3858, -0.5220, -0.6192, +0.4249, -0.5309, -0.1737, +0.1826, -0.1282, +0.5431, -0.0770, -0.3576, +0.1624, +0.0156, -0.4015, -0.5880, -0.4772, +0.1299, +0.1412, +0.3017, -0.3183, +0.2800, +0.1079, -0.3318, -0.3915, -0.0236, -0.2534, -0.0653, +0.0220, -0.5014, -0.0448, +0.4895, -0.5066, +0.0322, -0.4296, +0.5146, +0.0200, -0.5356, -0.0013, +0.0327, -0.3246, -0.2293, -0.2541, -0.4495, -0.5473, +0.2847, -0.1901, -0.2312, -0.1694, -0.6842, -0.1511, -0.1708, +0.1053, -0.5946, -0.3606, -0.2067, -0.1559, +0.0507, -0.2181, -0.0979, -0.1372, -0.1785, +0.0791, -0.2753, -0.1703, +0.0233, +0.2168, +0.4180, -0.4231, +0.0265, -0.0540, +0.1337, -0.4377, -0.2039, -0.2325, +0.1548, -0.3411, -0.4092, -0.7270, +0.5202, +0.1287, +0.2782, -0.1197, +0.1253, -0.0600, -0.5236, -0.6407, -0.1578],
-[ +0.2248, -0.0462, -0.8284, +0.3114, +0.1852, +0.1834, +0.2051, +0.0036, +0.3927, +0.0424, +0.3012, +0.3949, -0.1332, -1.5290, +0.1408, +0.1054, -0.7331, -0.1059, -0.2528, -0.3250, -0.0382, -0.2839, +0.2565, -0.1068, -0.9446, +0.1441, -0.3193, -0.2635, +0.0176, +0.0265, -0.0176, -0.2029, -0.0225, +0.1164, -0.1823, -0.3814, +0.0164, +0.1373, -0.3667, -0.7848, -0.0255, -0.0129, +0.1221, +0.1512, +0.1171, +0.1466, +0.5229, -0.6438, -0.0683, +0.3447, -0.0477, +0.3481, +0.0824, -0.2259, -0.0708, -0.1149, -0.0211, -1.2025, -0.1185, +0.0719, -0.1111, -0.1185, +0.2291, -0.6489, -0.0429, -0.1608, -0.9844, -0.2071, +0.3207, -0.7894, -0.4253, -0.2946, -0.1613, +0.0676, -0.2046, +0.0975, -0.1958, +0.1665, -0.0771, -0.4754, -0.7693, +0.2628, +0.2711, +0.0761, +0.0111, -0.2896, -0.1529, -0.2488, +0.4496, +0.1245, -0.4776, -0.0319, -0.0583, -0.0840, +0.1204, +0.2630, -0.0326, +0.1000, -0.2014, +0.1737, -0.3519, +0.0156, +0.1333, +0.6454, +0.0150, +0.1053, -0.0615, +0.1535, -0.6005, -0.6815, +0.3927, -0.0731, +0.2823, +0.1357, -0.1806, -0.1308, -1.2679, +0.2003, +0.2598, -0.3577, -0.1103, -0.1210, +0.3821, +0.0155, +0.1079, +0.0055, +0.1147, -0.2482],
-[ -0.1591, -0.0014, +0.1338, -0.7125, -0.7493, -0.1707, +0.3043, +0.1481, +0.1947, -0.5341, -0.3419, +0.2912, +0.2841, +0.0855, +0.0824, -0.3565, +0.0561, +0.0377, +0.2687, -0.2008, +0.4876, +0.1415, -0.7958, -0.1996, -0.4545, -0.0042, -0.3079, -0.1734, -0.2051, -0.0527, -0.1679, -0.2587, +0.3030, -0.8262, -0.0625, -0.4694, +0.2859, -0.0385, -0.3980, -0.5660, -0.5973, +0.3560, -0.0174, -0.1013, +0.0510, +0.1240, +0.3538, -0.0418, +0.4386, +0.2131, -0.0653, +0.1108, +0.1378, -0.0472, +0.2413, -0.2423, +0.0077, -0.8678, -0.8777, -0.1584, -0.9594, -0.4108, +0.1470, -0.6456, -0.0121, -0.3689, +0.1646, -0.9434, -0.4325, -0.2030, -0.0612, +0.0111, -0.1285, +0.1007, +0.0899, +0.0277, -0.0589, -0.0392, +0.1973, +0.0096, -0.2397, +0.4534, -0.1920, +0.1441, +0.0410, +0.3059, -0.5382, -0.3187, +0.2552, -0.0264, +0.1063, -0.2650, +0.1642, -0.0897, -1.0989, -0.3342, -0.7970, -0.3262, +0.1747, +0.4497, +0.0286, +0.0872, -0.0096, +0.1537, -0.0268, -0.1654, -0.2807, +0.0615, -0.5338, +0.2320, -0.1725, +0.0327, -0.4462, -0.2303, -0.0239, +0.2228, -0.0059, +0.0378, +0.1797, -0.5790, -0.3018, +0.0120, +0.2499, -0.0770, -0.7413, +0.1908, -0.6291, -0.0909],
-[ -0.1240, -0.4172, -1.2085, -0.3691, +0.0492, -0.1166, +0.1979, -0.2357, +0.1683, +0.5632, +0.2264, +0.3212, -0.3016, -0.1201, +0.2582, -0.1198, +0.0025, +0.1921, -0.2394, +0.4200, +0.6327, -0.4111, -0.3970, -0.0531, -0.3382, +0.1123, +0.1504, -0.3475, +0.1592, +0.1284, +0.2017, -0.2621, -0.3080, -0.0995, +0.1393, -0.1166, +0.0436, -0.2743, -1.1490, +0.0053, +0.1106, +0.0826, -0.0937, -0.0162, -0.2341, +0.0701, -0.2890, -0.1967, -0.3510, +0.2121, -0.0558, +0.1720, -0.0741, -0.0036, +0.2633, -0.3739, +0.0536, -0.1093, -1.3638, -0.0535, -0.1404, -0.1913, -0.1090, +0.0445, -0.2999, +0.3621, -0.2209, -0.3109, -0.0994, -0.0474, +0.2710, +0.0227, +0.0429, -0.0851, -0.1066, -0.0245, -0.1123, +0.1840, -0.8776, -0.0159, -0.1842, +0.1612, +0.6969, -0.5558, -0.5212, +0.2787, -0.1248, +0.1391, +0.1134, +0.1405, -0.5579, +0.2416, +0.0664, +0.1687, -0.1130, -0.1811, -0.0078, -1.1484, +0.3887, -0.3861, +0.1172, +0.3303, +0.3138, +0.1004, +0.2782, -0.3874, -0.2019, -0.6500, -0.0303, -0.6276, -0.2639, -1.1029, +0.1096, +0.2257, -0.3056, -0.4345, -0.0964, +0.0984, -0.1954, +0.2322, -0.5411, +0.0700, -0.3115, +0.3259, +0.0910, +0.1975, -0.2759, +0.0448],
-[ -0.3904, -0.0199, -0.3537, -0.4832, -0.1628, +0.0043, -0.0414, +0.1218, -0.2269, +0.2141, +0.3481, +0.0906, +0.0224, +0.2132, +0.3279, +0.5876, -0.3077, -0.4872, -0.6630, -0.4332, +0.2724, -0.3827, +0.1056, +0.2548, -0.5510, +0.4017, -0.1022, -0.4635, -0.1546, -0.3860, -0.2522, -0.7110, -0.9669, +0.2434, +0.2342, +0.3793, +0.1495, +0.6897, -0.1169, +0.2553, +0.0812, -0.0038, -0.2082, -0.6254, -0.2263, +0.3667, +0.0377, -0.0467, +0.0525, -0.4292, +0.3255, +0.1481, -0.3301, +0.1646, -0.0131, +0.3723, +0.0310, +0.1258, +0.2263, +0.3037, -0.5007, -0.8377, -0.4179, -0.1642, -0.3209, +0.0559, +0.5227, +0.2157, -0.3959, -0.2160, +0.1486, +0.2303, +0.1043, +0.0733, +0.3248, -0.0592, +0.3219, -0.2249, -0.0967, +0.1890, -0.1448, -0.4372, +0.4339, -0.4763, +0.1388, -0.1501, -0.5580, -0.4443, +0.0384, +0.1303, -0.4852, -0.2745, +0.2143, +0.5117, -0.1081, -0.0613, +0.0808, -0.1280, -0.0541, +0.3160, +0.0524, +0.0024, -0.1632, +0.1957, -0.2029, -0.0273, -0.6920, +0.1693, -0.3618, -0.6140, -0.1295, +0.1724, -0.2306, +0.1818, +0.3156, +0.6412, +0.1616, -0.5177, -0.0959, -0.1618, -0.0358, -0.3144, -0.2045, +0.0474, -0.5212, +0.1608, -0.3414, +0.1889],
-[ -0.1657, +0.0451, -0.3340, +0.3003, -0.0376, +0.2246, +0.3963, -0.6580, +0.4921, +0.0738, -0.8389, -0.0540, +0.4077, +0.2517, +0.1214, -0.0437, +0.2799, +0.1646, -0.1190, -0.0437, -0.0101, -0.4510, -0.1197, +0.4256, +0.4241, +0.2016, -0.2480, -0.2848, +0.0910, -0.3252, +0.0920, +0.1780, +0.1210, -0.2491, +0.4193, +0.0180, -0.2447, +0.1820, +0.4304, -0.6427, -0.0964, -0.4044, -0.1593, +0.3301, -0.1972, +0.1570, +0.1535, +0.2956, +0.0852, +0.5078, -0.2621, +0.0667, +0.3003, +0.1874, -0.4642, +0.0619, -0.1780, -0.0325, +0.0594, -0.0962, +0.0029, -0.0338, -0.6791, +0.0143, +0.2036, -0.6389, -0.3388, -0.3286, +0.2323, -0.3636, +0.0878, -0.1679, +0.3731, -0.6431, -0.0756, -0.0599, -0.0401, +0.3496, -0.3530, +0.0650, +0.1341, -0.2022, -0.6015, -0.3657, +0.1225, -0.1339, -0.0863, -0.2255, -0.0403, -0.1262, -0.0083, +0.3607, +0.4136, +0.4825, +0.2525, -0.1267, +0.2066, -0.0973, +0.1031, -0.0115, -0.2364, +0.2755, +0.0984, -0.4746, -0.1369, -0.0256, +0.1211, -0.1850, +0.1281, +0.0125, -0.4228, -0.1674, +0.0763, +0.1332, -0.1609, +0.2957, -0.0578, -0.1904, +0.2217, +0.4961, -0.1120, -0.0485, +0.0111, -0.3721, -0.2940, -0.2656, -0.0420, -0.0380],
-[ -0.0861, +0.1449, -0.6769, +0.0344, -0.2920, +0.1292, -0.2751, +0.1184, +0.3807, -0.3596, -0.7922, +0.0296, +0.6053, -0.8649, -0.6145, -0.9584, -0.1484, -0.2938, +0.5678, -0.1980, +0.9455, +0.1873, -0.4021, -0.0092, +0.1739, +0.0755, -0.2697, -0.5705, -0.1806, -0.4981, -0.9201, -0.2681, -0.5527, -0.5562, -0.2761, -0.1184, +0.0279, +0.0548, +0.2510, +0.1212, +0.2111, -0.2896, +0.0753, -0.1386, -0.3318, +0.4249, -0.4348, -0.6503, -0.9838, -0.0485, +0.1144, +0.7076, -0.1162, -0.0505, +0.1097, +0.1913, +0.1892, -0.0247, +0.0125, -0.2954, -0.0785, -0.7718, -0.6086, -0.0690, +0.5044, +0.0031, +0.0960, +0.2154, +0.3533, +0.5952, -0.1162, +0.5624, -0.2424, +0.0859, -0.2930, -0.1793, +0.7442, +0.0831, -0.1739, +0.2988, -0.7403, +0.6559, -0.8099, -0.1913, +0.1954, -0.3384, +0.0240, +0.2432, -0.3941, +0.2698, -0.2234, +0.1533, -0.0102, +0.0815, +0.3778, +0.1553, +0.2522, +0.2298, +0.1750, +0.3060, -0.3154, -0.9199, +0.1745, +0.4966, -0.1204, +0.0371, -0.9282, -0.1539, +0.2182, -0.2074, -0.5206, +0.4416, -0.6532, -0.0871, -0.1050, -0.0336, +0.0717, -0.0583, +0.0276, -0.7181, +0.2044, +0.2626, -0.1477, -0.1966, +0.5259, -0.2208, +0.1887, -0.3999],
-[ +0.3951, -0.1828, -0.5690, -0.4359, +0.1588, -0.0299, -0.0165, +0.1315, +0.1514, +0.0204, -0.0711, +0.4348, +0.1533, -0.5613, +0.1055, +0.1061, +0.0002, +0.0874, +0.1442, +0.1372, -0.2141, -0.2999, +0.1639, +0.0992, -0.1852, -0.2600, +0.0525, +0.4053, -0.2276, +0.1156, -0.1959, -0.2561, +0.1651, +0.2641, +0.0408, -0.2071, -0.3731, -0.1776, +0.2279, +0.2284, -0.0525, -0.2135, +0.2042, +0.1038, +0.0338, +0.0044, -0.1703, -0.2930, +0.3392, +0.3723, +0.3568, +0.1010, -0.6759, +0.1756, -0.0830, -0.0264, -0.3639, +0.2400, +0.1893, -0.7797, -0.2049, +0.6765, -0.9135, +0.1923, -0.4428, -0.2858, +0.1698, -0.0717, -0.0732, -0.1378, +0.1252, -0.3311, +0.3699, +0.2626, -0.1844, +0.2205, +0.1067, +0.2054, +0.1633, -0.0336, +0.1384, +0.2030, -0.4712, +0.1841, +0.1662, -0.4934, +0.2673, +0.1616, -0.1415, +0.1551, +0.1830, -0.7949, -0.1026, -0.0908, -0.2148, -0.0862, -0.3247, +0.2256, +0.4064, +0.0255, -0.2503, -0.1194, +0.0556, +0.2649, -0.1426, -0.3441, -0.4780, -0.0587, +0.1581, +0.0628, -0.9718, +0.4334, +0.0918, +0.0179, -0.2611, -0.2913, +0.0065, -0.3420, +0.1218, +0.0496, +0.4038, -0.2304, +0.3929, +0.2798, +0.0511, -0.0994, -0.1512, +0.0164],
-[ -0.6535, -0.3824, +0.4637, +0.5439, +0.0985, +0.2432, -0.1147, -0.4929, -0.4969, -0.3765, +0.3427, -0.1913, +0.1222, +0.5814, -0.0775, -0.0383, -1.3698, -0.0067, +0.1913, -1.1719, -0.2135, -0.6633, +0.1711, -0.2446, -0.9635, +0.1336, +0.2132, +0.6358, -0.1220, -0.0156, +0.4911, +0.6260, -0.4446, +0.2189, -0.4621, -0.6081, +0.2439, +0.0313, -0.3464, +0.2112, -0.2890, -0.0802, -0.5375, +0.0254, +0.6150, -1.0068, +0.3383, +0.0250, +0.0761, -0.0716, -0.1940, +0.0720, -1.4718, -0.4669, +0.2584, -0.3336, -0.1380, -0.7112, +0.1706, -0.2030, -0.3693, +0.5311, -0.3647, +0.3416, -0.6086, +0.5480, -0.5410, -0.3621, -0.0866, -0.2212, -0.0025, -0.6617, +0.0389, +0.3139, +0.3728, +0.2861, +0.5063, +0.0971, -0.8710, +0.0632, +0.0308, +0.9254, -0.0867, +0.0167, +0.2415, -0.0486, -0.3985, +0.0814, +0.3215, -0.5556, -0.5459, -0.5135, -0.7426, -0.1787, +0.1893, +0.1558, +0.3495, -0.1245, -0.3737, -0.4077, -0.0901, -0.0731, -0.3761, -0.0108, +0.0373, -0.4581, -0.4615, -0.7974, +0.0734, -0.2704, -0.7788, -1.6055, -0.0438, -0.0669, -0.5751, -0.1561, +0.2110, -0.4103, +0.1436, -1.0879, -1.3066, -0.4354, -0.8070, -0.1949, +0.1103, -0.1615, -0.6326, -0.1823],
-[ -0.2145, +0.0256, -0.1075, -0.8793, -0.6322, +0.3680, -0.5028, +0.6511, +0.1314, -0.2389, -0.4655, -0.4032, -0.5368, +0.1693, +0.2421, +0.1469, +0.1714, -0.0657, +0.1218, +0.2696, -0.5204, -0.0782, -0.1420, -0.1775, +0.2941, -0.5320, -0.0746, +0.1977, +0.3242, -0.4141, +0.1552, +0.1736, +0.4251, +0.3324, -0.3292, +0.1409, -0.3070, -0.4303, +0.1468, +0.0513, -0.4863, +0.2182, -0.4064, +0.1852, -0.4060, -0.1219, -0.8666, -0.8484, -0.4552, +0.0625, +0.2701, -0.2608, +0.1336, +0.3453, -0.1685, -0.8681, +0.0575, -0.0430, +0.4210, +0.4562, -0.2986, -0.5420, +0.2249, -0.0550, -0.8807, -0.3987, +0.1510, +0.0237, +0.2368, -0.1508, -0.2971, -0.4406, -0.1031, -0.8893, -0.0671, -0.0399, +0.3169, +0.6297, +0.0355, -1.3984, +0.0138, -0.0887, -1.0362, -0.6752, +0.1021, +0.2615, +0.2444, -0.1559, -0.3158, +0.0953, +0.3399, -0.0697, +0.0909, +0.3761, +0.1800, -0.2838, -0.6784, +0.1379, -0.5262, -0.0328, -0.0282, -0.1017, -0.1234, +0.1816, -0.0022, -0.1195, +0.3849, -0.5240, -0.2758, -0.5856, +0.1173, +0.4278, -0.2713, -0.2139, +0.3127, -0.4888, -0.5226, -0.1098, +0.1856, +0.1307, +0.3204, +0.1158, -0.2220, -0.1268, -0.0441, +0.3987, -0.0886, +0.0944],
-[ +0.4614, -0.0341, -0.3127, -0.3417, +0.1270, -0.2438, +0.1256, +0.2616, +0.1769, +0.2554, +0.0401, +0.4384, -0.3171, +0.1049, -0.6874, -0.8721, -0.2163, -0.0291, +0.2594, +0.0246, +0.0724, +0.2490, +0.0425, +0.0459, +0.2011, -0.5738, -0.1479, -0.3346, -0.0266, +0.2086, -0.0040, +0.0719, -0.2202, -0.2643, -0.2547, +0.1521, -0.3104, -0.2468, -0.1023, -0.3194, +0.2488, -0.0491, +0.3947, +0.1225, -0.2908, +0.1780, -0.0005, +0.1691, -0.2036, -0.2187, -0.1570, +0.1058, -0.2051, -0.3514, -0.1599, +0.2463, +0.1237, -0.0981, +0.2591, +0.4577, -0.3913, -0.0632, +0.2139, -0.1243, -0.2953, -0.2283, -0.6659, -0.1692, -0.1968, -0.0003, +0.0315, -0.0684, +0.1006, +0.1359, +0.1536, -0.3270, -0.0839, -0.2444, -0.3855, -0.4013, +0.1105, -0.0854, +0.2298, +0.0779, -0.1536, -0.1694, +0.1131, +0.1775, -0.6872, +0.5421, -0.0455, +0.3147, +0.0818, -0.1207, +0.3427, +0.1563, +0.1190, -1.2023, -0.7227, -0.3360, +0.2061, -0.2620, +0.2675, -0.3546, +0.1095, +0.3345, -0.7043, -0.0666, -0.7135, +0.1534, -0.5890, +0.0591, -0.3491, -0.2425, +0.2764, +0.3161, -0.6132, +0.1511, -0.3858, -0.2196, -0.0678, -0.0624, -0.3383, +0.0621, -0.0103, -0.0182, +0.0191, +0.0176],
-[ +0.3280, -0.6080, +0.1045, +0.0185, -0.3494, +0.1962, -1.1529, -0.1475, -0.2069, -0.0661, -0.1141, +0.0642, -0.3862, +0.2403, +0.1153, +0.1199, +0.2059, -0.4460, -0.1596, +0.1914, +0.4296, -0.2750, -0.0871, -0.1282, -0.1870, -0.0862, -0.1798, -0.2860, -0.8532, +0.0651, +0.2535, -0.5395, -0.3260, +0.1887, -0.1736, +0.0770, -0.0835, +0.2064, +0.0084, +0.1442, +0.2413, +0.0272, +0.3630, +0.1719, -0.2559, -0.3920, -0.4000, +0.0806, +0.0958, -0.1785, -0.1645, -0.1561, -0.0642, +0.0036, -0.2139, -0.1258, +0.8286, +0.1008, -0.0724, -0.4328, -0.3329, +0.1013, -0.2245, -0.1468, -0.7493, -0.0072, -0.1338, -0.2106, -0.2979, +0.0908, +0.0397, -0.1220, +0.2189, +0.3704, -0.0164, -0.2005, +0.1434, -0.5151, +0.0326, -0.1560, -0.3458, -0.1486, +0.2803, +0.0808, +0.2556, -0.1591, -0.0879, +0.2555, +0.0905, +0.3518, -0.3664, -1.1826, -0.2343, +0.1236, -0.2352, -0.1818, +0.1976, +0.3657, +0.1101, -0.0302, +0.1046, +0.3013, -0.4328, +0.5137, +0.3280, -0.3893, -0.4061, +0.2101, -0.1510, +0.1469, -0.0312, -0.1720, +0.1547, +0.2162, +0.0479, -0.2715, -0.1427, -0.2122, +0.0937, +0.3623, +0.5012, -0.3414, +0.3632, +0.0504, +0.1106, +0.1535, -0.3803, +0.0121],
-[ -0.4640, -0.1327, -0.0716, +0.0056, +0.2762, -1.1126, +0.0626, -1.0688, +0.2330, -0.2329, +0.5559, -0.1453, -0.5149, +0.0023, +0.1085, -0.4709, -0.5074, +0.0952, +0.1463, +0.2491, -0.0619, +0.0158, -0.0328, -0.5344, +0.1023, -0.0300, -0.2085, +0.1359, +0.0592, -0.2524, -0.1559, -0.0085, +0.0068, -0.0124, +0.3539, +0.2308, +0.0371, -0.1474, +0.0236, -0.5550, +0.0501, +0.1425, -0.5211, -0.4661, -1.4098, +0.0612, +0.2326, -0.0758, -0.0272, -0.0956, +0.0071, -0.4600, -0.2366, -0.0167, -0.5775, -0.5638, -0.0820, -0.4716, -0.5335, -0.2214, -0.3552, +0.2573, -0.2350, +0.4470, -0.7306, +0.4852, -0.2049, -0.3014, -0.2232, +0.3578, +0.1289, -0.2788, -0.4551, -0.3855, -0.4936, -0.1730, +0.0164, -0.1968, -0.1534, -0.3116, +0.0401, -0.2093, -0.0669, -0.1232, +0.6732, +0.0041, -0.1624, +0.1671, -0.3598, -0.2023, -0.7892, +0.3155, -0.1869, -0.3023, -0.4224, +0.4675, -0.1488, -0.6090, -0.7404, -0.2382, +0.2172, -0.7886, -0.5513, -0.1992, -0.7805, -0.1544, -0.0783, -0.2322, +0.2890, +0.0905, -0.0698, +0.4080, +0.3539, +0.0809, +0.4526, +0.4208, -0.0471, -0.2460, -0.6651, +0.1086, -0.4729, -0.5561, -0.4785, -0.4709, -0.1186, -0.6847, +0.0113, -0.2090],
-[ +0.1128, +0.2196, +0.0491, +0.0871, -0.0427, -0.1228, -0.1325, -0.0775, +0.0799, -0.4258, -0.4283, +0.0695, -0.4842, -0.7364, -0.3856, -0.5542, +0.1488, -0.0655, +0.1610, +0.2014, -0.0839, -0.0175, -0.1677, -0.4381, -0.3510, -0.3124, -0.1308, -1.4672, +0.0946, -0.4583, -0.6771, -0.2482, +0.0564, -0.0899, -0.3302, +0.3769, -0.2056, +0.1952, -0.7006, -0.0171, +0.0339, -0.7665, -0.2355, -0.4328, +0.4867, -0.9649, -0.7657, -0.2226, -0.0585, -0.0788, -0.1219, +0.2336, +0.0329, -0.1373, -0.0480, -0.4672, +0.1248, -0.3234, -0.0123, -0.0402, -0.7285, +0.1463, -0.2133, -0.3333, -0.3750, -0.3789, +0.2528, +0.2849, -0.2088, -0.1508, -0.0521, -0.2693, -0.0864, -0.2134, -0.0674, -0.0502, +0.0965, +0.1491, -0.0258, -0.8792, +0.0514, +0.2205, +0.1569, +0.1199, +0.0771, -0.2032, -0.1334, +0.1342, +0.4965, -0.3000, +0.4028, -0.4422, +0.3067, -0.2638, +0.0714, +0.0542, -0.0185, +0.0883, -0.4793, +0.0931, -0.1196, +0.2565, +0.1506, -0.2275, -0.0765, -0.0661, +0.0736, +0.5985, -1.2571, -0.4318, +0.0778, -1.4763, +0.0302, -0.0896, +0.0087, -0.1240, -0.1418, -0.4563, -0.2404, -0.2635, +0.0763, -0.3100, -0.1861, -0.0644, -0.0371, -0.0219, +0.3791, -0.3473],
-[ +0.4353, -0.0027, -0.1405, -0.4122, -0.3522, +0.0526, -0.1707, -0.0385, -0.1975, +0.2925, -0.4776, -0.0418, +0.0446, +0.2244, +0.1293, +0.3907, -0.9109, -0.0468, +0.0137, -0.0460, +0.4094, +0.0427, +0.2939, -0.1557, +0.0021, -0.1208, -0.1217, +0.4177, -0.3536, +0.0166, -0.1902, -0.2393, +0.0345, +0.0799, -0.7020, -0.1663, -0.5196, +0.1123, +0.2173, -0.3454, -0.1350, -0.2988, -0.4965, -0.3230, +0.1591, -0.0365, +0.1462, -0.2123, -0.0619, -0.1740, +0.0770, -0.2098, -0.0199, +0.0795, -0.3884, +0.1162, -0.2321, -0.4210, -0.6708, +0.0618, +0.0358, -0.1079, +0.2677, +0.1349, +0.2558, -0.1510, -0.2075, -0.0258, -0.2588, +0.0050, -0.1894, -0.1519, -0.1532, -0.3941, -0.0508, +0.1084, +0.1652, -0.1217, -0.1805, -0.5194, -0.2663, -1.1767, -0.1488, -0.1212, +0.0229, +0.3766, -0.5909, +0.2650, +0.2342, -0.2097, +0.2822, +0.5491, +0.3619, +0.0758, +0.2908, +0.3512, +0.2550, +0.0763, -0.7615, -0.0578, +0.1206, +0.2908, -0.2384, +0.0054, -0.1382, -0.1125, -0.0447, -0.2442, +0.1242, -0.0534, +0.0024, +0.1971, -0.1923, -0.0621, -0.3769, +0.1903, +0.1829, -0.1082, -0.1367, -0.0554, -0.7187, -0.4493, +0.2949, +0.0883, -0.3279, +0.2849, +0.1060, +0.3663],
-[ -0.6415, -0.3939, -0.5202, -0.1639, -0.4648, -0.1451, +0.4356, -0.6945, +0.3483, -0.5865, -0.3782, -0.0060, -0.0677, +0.1958, -0.2324, -0.1777, +0.0295, +0.5604, +0.0249, -0.2261, -0.2063, -0.0416, -0.0950, -0.2548, +0.0042, -0.3812, +0.2529, +0.0167, +0.0483, +0.3357, +0.1415, +0.0178, -0.1509, -0.0159, -0.2740, +0.0397, -0.0819, +0.1141, -0.3993, +0.0913, -0.2224, -0.7560, -0.2634, +0.3233, +0.0027, +0.3794, +0.2278, +0.6810, -0.7867, -0.0823, -0.0451, -0.3029, -0.0513, -0.4509, +0.4310, +0.1516, -0.4726, -0.1546, -0.3385, +0.1362, +0.3105, +0.0986, -0.7286, -0.1418, +0.0951, +0.1071, -0.1305, -0.0904, -0.9688, -0.3975, +0.0978, +0.4764, -0.2437, +0.1659, +0.3128, +0.1478, +0.2060, -0.8387, +0.0795, -0.3924, +0.3558, -0.5638, -0.5464, +0.3735, -0.3795, +0.3854, -0.2423, +0.0661, -0.3528, -0.1318, -0.2049, -0.5105, +0.5074, +0.0987, +0.4461, -0.8709, -0.2308, +0.5754, -0.1341, -0.9593, -0.0423, +0.0077, -0.0788, +0.0913, -1.0023, -0.2929, -0.7491, +0.1581, -0.1464, +0.2154, +0.2309, -0.2193, -0.2466, -0.5195, +0.1740, -1.0865, +0.0758, -0.3392, +0.1485, -0.0161, -0.6096, +0.0713, -0.1700, -0.1644, -0.3517, -0.1076, -0.6289, -0.0868],
-[ -0.0279, -0.1180, -0.2685, -0.4734, +0.4130, +0.2278, +0.2734, -0.1383, -0.1294, -0.2393, -0.2655, -0.2045, +0.1723, -0.1902, -0.0720, -0.1001, +0.0693, -0.2959, +0.4904, -0.4231, -0.6569, -0.5207, +0.0924, -0.2339, +0.1349, -0.0989, +0.2269, -0.5261, +0.0686, +0.2270, -0.1708, -0.7268, +0.0170, -0.8337, +0.1631, -0.1823, -0.1832, +0.4833, +0.2301, +0.2152, -0.1013, +0.1557, +0.1638, -0.1074, +0.0427, -0.0506, -0.2892, -0.2381, +0.2450, +0.2302, -0.3176, +0.0832, +0.1322, -0.4486, +0.4323, -0.5670, +0.0120, +0.1856, -0.0379, +0.1852, -0.0068, -0.4816, -0.5400, -0.5379, -0.1145, -0.6362, -0.2237, +0.0393, -0.2324, -0.1508, -0.5168, +0.1399, -0.8280, +0.0271, +0.0271, -0.1355, +0.3420, +0.0033, -0.0524, -0.0132, -0.0686, -0.2197, -0.2397, +0.4131, +0.3879, +0.1894, -0.0590, -0.2728, +0.2001, -0.5037, -1.1579, -0.1231, +0.1030, +0.3018, -0.1117, +0.2328, -1.1153, +0.2872, -0.8792, +0.1519, -0.0997, +0.3196, -0.4409, +0.3572, -0.1474, +0.0191, -0.4200, -0.3569, +0.0807, -0.5480, -0.5429, +0.1992, -0.0004, -0.7959, -0.6011, +0.0583, +0.1194, -0.1493, +0.1473, -0.6284, -0.2466, -0.5721, -0.0804, -0.0444, +0.2544, +0.0155, -0.0306, -0.3982],
-[ +0.5828, -0.1462, -0.2782, +0.0690, -0.1789, -0.1596, +0.0840, -0.4970, -0.2908, -0.3823, -0.8830, -0.0833, -0.4294, +0.3447, +0.4591, -0.1768, -0.4054, -0.2783, +0.0228, +0.2754, -0.3646, +0.3944, -0.0349, -0.1119, +0.0405, -0.7938, -0.1085, -0.1693, +0.3024, -0.5234, +0.1899, +0.1598, -0.0956, -0.0660, +0.8926, +0.0428, -0.1308, -0.9002, -0.1008, +0.0826, -0.0661, +0.2094, -0.2457, +0.0941, -0.1031, +0.0496, -0.6188, +0.3200, +0.3472, -0.1994, +0.0598, -0.6498, -0.3135, +0.1850, -0.3448, -0.5044, -0.0509, -0.9147, +0.2559, +0.0753, +0.0753, +0.0294, -0.3612, -0.0921, -1.4746, +0.4441, +0.3017, +0.1874, -0.4263, +0.4468, +0.2712, +0.0128, -0.0261, +0.3705, -0.4319, -0.0988, -0.0705, -0.4702, +0.1396, -0.3963, +0.0893, -0.2172, -1.2196, -0.6357, -0.1207, +0.1123, -0.2076, -0.1591, -0.1512, -0.0582, -0.3533, -0.5694, -0.2883, +0.2884, -0.0825, +0.0193, -0.2499, -0.5041, +0.2356, -0.0106, +0.0655, +0.1411, +0.1246, -0.5655, +0.0270, -0.5696, +0.1255, -0.0826, -0.0638, -0.5297, -0.9973, +0.2699, -0.2058, -0.0949, -0.3804, -0.1981, +0.0273, -0.1266, +0.0663, +0.2089, +0.1680, -0.1503, -0.1509, +0.1122, -0.7540, +0.2932, -0.8315, -0.3090],
-[ +0.1706, +0.0610, -0.5838, -0.0865, -0.0213, -0.2678, +0.0303, +0.3113, -0.3995, +0.3783, -0.5923, +0.1832, +0.1734, +0.0254, -0.3922, +0.3137, -0.3262, +0.0790, -0.0224, +0.0657, -0.0827, -0.9136, +0.1583, -0.0134, +0.0211, -0.0033, +0.0590, +0.0649, +0.0960, -0.3352, +0.0149, -0.8295, +0.2650, +0.2434, -0.0466, +0.1953, -0.3053, -0.4421, +0.0103, -0.0617, -0.4838, -0.0559, +0.1233, +0.0918, -0.3375, +0.0673, +0.1396, -0.4121, +0.0399, +0.1877, -0.9721, +0.0536, -0.4329, -0.0968, -0.0310, -0.0441, -0.1357, -0.2994, -0.1415, +0.3444, +0.0769, -0.1848, -0.8968, +0.2653, +0.1815, -0.0268, +0.4176, -0.0595, +0.1591, -0.1656, -0.0402, +0.0691, -0.7454, -0.3123, -0.4003, +0.0267, -0.0143, +0.2760, +0.2060, -0.7292, -0.2153, +0.2515, -0.2929, +0.0335, +0.0227, -0.4146, -0.1046, -0.0436, -0.3568, -0.0046, -0.1406, -0.0310, +0.3112, -0.5021, -0.0665, +0.2722, -0.2953, -0.1284, +0.4788, +0.0499, -0.1760, -0.5210, -0.4396, -0.0102, -0.1382, +0.1617, -0.1325, -0.6286, -0.2559, +0.2053, +0.0603, +0.1821, +0.0275, -0.4626, +0.0678, -0.1890, -0.0034, -0.2487, +0.1380, -0.1140, -0.0490, -0.0591, +0.2868, +0.2875, -0.2210, +0.1894, +0.1656, -0.2314],
-[ +0.1326, +0.1445, -0.4052, -0.2978, +0.5537, +0.1333, +0.3951, -0.2189, -0.2499, +0.1027, -0.1314, -0.2956, -0.4292, +0.1320, -0.5522, -0.3736, -0.1077, -0.3843, -0.6754, -0.2406, +0.2837, -0.7301, -0.1675, -0.2725, +0.0578, -0.6014, +0.2112, -0.0551, -0.0484, -0.3406, -0.0537, -0.5426, -1.5375, +0.2983, +0.3546, +0.1420, -0.0795, -0.4401, -0.4079, -0.3726, +0.3343, -0.2322, -0.2032, +0.2038, -0.1928, -0.3805, +0.0599, +0.0578, +0.4813, +0.2921, -0.1916, -0.0337, -0.2057, +0.1114, +0.0827, +0.1672, -0.0961, -0.0529, -0.2337, +0.0616, +0.1257, -0.8919, +0.1716, -0.1828, -0.3268, -0.1773, -0.3308, -0.8293, -0.8749, -0.4553, -0.2627, -0.1717, +0.0148, +0.1005, -0.0882, +0.0134, -0.3633, -0.1698, -0.3961, -0.0632, -0.8008, +0.0911, -0.5091, +0.0745, +0.0184, -0.5566, +0.0934, -0.1507, -0.3232, +0.1291, -0.9442, +0.3393, +0.1318, -0.0475, -0.6027, -0.4318, +0.0814, +0.0791, -0.4565, -0.6858, -0.5338, -0.5991, +0.3650, +0.1171, -0.2716, -0.1989, -0.6467, +0.3248, -0.0296, +0.1573, -0.8836, -0.1377, -0.1053, -0.0780, -0.2601, -0.2829, -0.2949, -0.0864, -0.0371, -0.1057, +0.2542, -0.0073, +0.0424, +0.2498, +0.0555, +0.4797, -0.3376, -0.4506],
-[ -0.0255, -0.1650, -0.2974, +0.0178, +0.0392, -0.0186, +0.1872, +0.0655, -0.1296, +0.2720, -0.1809, +0.3607, -0.2829, -0.7414, -0.0197, +0.4503, +0.1493, -0.0222, -0.6118, -0.1622, +0.4015, -0.0279, +0.0294, -0.2557, +0.0963, +0.1893, +0.0614, -0.4798, +0.0077, -0.0389, +0.2097, +0.0587, -0.0738, +0.2764, +0.4512, +0.3174, -0.1535, -0.2276, -0.7275, -0.3815, -0.7228, +0.0201, +0.1117, -0.0261, -0.2577, +0.0478, -0.1840, +0.3085, -0.1759, -0.0425, -0.4142, +0.0371, -0.0894, +0.4119, +0.0659, -0.2694, +0.1903, -0.8607, -0.6496, -0.0941, +0.2064, -0.0151, +0.5710, +0.5431, +0.1864, -0.0135, -0.0710, -0.4110, -0.2441, -0.5753, -0.4009, +0.2134, +0.2212, +0.2904, -0.2814, -0.3143, -0.5441, +0.1319, -0.1148, -0.2074, +0.0995, -0.0569, -0.2905, -0.0324, -0.4356, -0.3295, +0.1332, +0.0101, -0.1996, +0.3176, -0.6325, +0.3636, -0.2449, -0.1157, +0.0073, -0.3086, -0.2715, -0.0547, -0.2606, -0.1449, +0.2044, -0.0712, +0.2225, -0.2971, +0.1239, -0.0524, -0.1557, -0.4880, +0.3417, -0.2688, +0.2402, -0.7468, +0.1165, +0.0455, +0.0083, +0.0263, +0.1152, +0.4319, -0.2114, +0.2163, -0.0243, +0.4918, +0.1440, +0.5037, -0.2096, -0.1679, +0.1048, -0.0869],
-[ +0.1235, +0.3844, -0.2685, -0.0345, +0.0650, +0.3062, -0.1378, -0.2978, -0.2188, -0.0771, +0.2667, +0.0304, -0.0427, +0.5494, -0.1444, -0.2129, +0.5117, -0.6419, +0.0324, -0.0905, -0.1562, -0.4267, -0.0232, -0.5619, -0.5693, -0.5975, -0.4708, +0.0807, -0.2655, -0.4244, -0.0705, -0.2516, -0.2843, -0.6295, -0.4559, -0.1688, +0.0422, +0.6803, -0.4978, -0.2812, +0.0619, -0.4478, +0.0157, -0.4996, -0.3075, -0.3749, +0.1362, +0.0591, -0.1556, -0.4341, +0.6123, -0.0788, +0.7977, -0.3591, -0.9098, -0.1948, -0.2681, -0.2196, +0.5037, +0.5002, -0.2051, -0.4643, +0.0398, -0.5385, -0.1953, +0.0785, -0.6677, -0.1378, -0.9210, -0.4328, -0.2015, -0.4793, -0.1423, +0.0203, +0.1207, -0.7935, -0.0970, +0.0853, -0.6163, -0.0491, +0.4021, +0.1865, +0.4280, -0.0037, -0.4592, -0.2485, +0.1351, -0.2844, -0.6598, +0.3015, +0.2235, -0.9861, -0.3646, +0.3393, -0.3452, +0.3539, -0.5701, -0.4908, +0.5699, -0.4017, -0.1102, -0.2180, +0.1905, +0.4240, -0.2312, -0.2970, -0.4595, +0.2174, +0.1782, +0.0243, -0.0901, +0.4517, -0.0867, +0.3470, -0.2287, -0.2463, -0.1592, -0.3746, -0.0036, -0.3122, +0.1140, -0.4486, -0.8497, -0.1085, +0.9101, +0.2038, -0.2062, -0.0823],
-[ +0.2463, +0.5707, -0.4433, +0.2201, -0.0199, -0.6071, +0.2050, +0.0493, -0.2200, -0.4677, +0.0629, +0.0493, -0.0842, +0.1211, -0.3605, -0.0976, -0.7993, +0.0483, -0.1064, +0.2877, -0.6253, -0.2183, -0.3741, +0.0682, -0.0970, +0.5666, -0.0419, -0.8218, +0.1176, -1.4321, +0.0578, -0.1302, +0.1870, +0.3711, -0.5058, +0.3670, -0.1283, -0.1262, +0.0613, -0.2924, -0.4785, -0.1313, +0.1151, -0.1354, +0.3046, +0.1120, +0.0943, -0.5687, -0.6528, -0.1993, -0.8543, -0.3318, +0.1341, -0.1301, +0.2574, +0.0046, -0.1438, -0.0989, +0.0297, -0.1477, -0.0582, -0.2912, +0.1454, +0.2671, -0.4703, -1.3141, -0.1180, +0.1261, +0.0528, +0.1643, -0.4553, -0.0406, -0.4539, +0.0511, +0.1268, +0.2252, -0.0132, +0.0196, +0.7711, -0.0122, +0.1204, -0.5035, -0.0164, -0.0501, +0.4662, -0.2951, -0.1318, -0.1211, -0.2753, -0.0345, +0.0149, -0.3875, -0.1881, -0.1405, +0.1532, +0.1554, -0.0673, -0.2962, +0.1869, +0.2242, -0.5578, -0.0057, -0.3872, +0.1012, +0.1592, -0.5527, -0.1771, +0.2545, +0.1549, -0.0110, -0.5167, +0.1115, -0.0596, -0.5712, +0.3191, -0.3316, -0.0618, -0.7255, -0.0035, -0.5352, -0.0360, +0.0610, -0.6326, -0.2177, -0.5042, -0.5355, -0.1681, -0.1498],
-[ +0.1926, -0.0685, +0.3304, -0.3787, +0.0300, -0.2676, +0.0136, -0.3297, -0.1434, +0.2152, +0.1500, -0.0552, -0.3526, -0.0323, +0.2272, -0.1979, -0.4169, -0.3634, -0.8873, -0.1784, +0.0721, -0.5226, +0.1625, -0.5973, -0.2882, -0.2884, -0.0342, -0.7191, -0.1038, +0.2307, -0.3793, -0.2169, -0.4917, +0.1231, -0.2788, -0.0933, +0.0867, +0.1352, -1.5252, +0.3475, -0.2924, -0.6522, -0.2583, -0.2580, +0.0162, -0.1497, -0.2728, -0.0223, -0.2669, +0.1925, +0.3857, -0.3332, +0.1178, -0.5367, +0.0528, -0.0169, -0.5829, -1.0664, -0.5824, -0.1038, +0.1126, -0.7621, -0.4332, -0.0314, -0.1815, +0.1829, -0.6382, +0.1326, +0.0845, -0.4755, -0.2206, -0.3449, +0.0764, -0.0900, -0.5230, -0.0539, -0.4122, -0.7988, -0.1538, +0.2325, +0.1030, -0.1607, +0.0113, -0.1478, +0.2353, +0.1148, -0.0807, -0.1881, -0.4861, -0.2848, +0.2721, -0.7730, -0.4613, +0.6028, +0.2487, -0.1225, -0.2896, -0.2808, -0.1185, -0.7210, +0.0897, +0.1085, +0.3445, -0.1611, -0.0695, +0.2044, -0.1024, -0.2478, -0.0785, +0.3137, +0.5408, -0.3994, -0.4764, -0.2766, +0.2133, +0.1204, -0.9959, +0.3333, +0.1227, +0.2426, -0.4202, -0.3578, -0.1248, -0.1090, -0.2104, -0.3860, +0.2306, -0.0728],
-[ -0.3248, +0.0159, -0.0667, -0.0756, -0.0663, +0.3394, -0.2182, -0.2663, -0.1528, +0.1880, -0.5628, +0.2296, -0.0234, -0.0294, -0.2945, +0.1946, -0.3773, -0.0458, -0.3226, -0.4340, -0.0176, +0.3101, +0.1491, +0.3488, +0.3136, +0.1758, +0.3119, +0.4763, +0.1465, -0.0397, -0.3957, -0.3768, +0.1163, -0.4517, +0.3269, -0.0506, +0.2071, -0.3858, +0.4534, -0.2441, +0.5120, -0.5391, -0.2332, -0.6894, -0.0485, -0.2305, -0.0612, +0.1359, +0.0151, -0.3765, +0.3468, -0.3807, +0.5106, -0.2714, -0.7264, -0.8902, -0.3425, -0.1253, -1.0046, +0.2819, +0.0902, +0.2295, +0.2070, -0.6132, -0.0471, +0.1733, -1.1173, -0.4534, +0.5652, -0.0742, +0.1592, -0.1147, -1.0578, -0.7389, +0.1167, -0.3078, -0.0317, -0.1373, -1.1162, -0.1009, -0.4260, -0.0209, -0.6846, -0.2091, +0.4688, +0.1684, +0.5514, -0.1581, -0.4061, -0.2237, +0.1754, -0.4694, +0.0851, -0.6308, -0.2750, -0.3957, -0.5867, +0.2913, -0.4755, -0.2140, -0.3601, +0.3739, -1.1790, -0.0693, -0.2330, -0.5800, -0.1498, -0.5219, -0.1689, +0.1537, -0.1052, +0.6002, +0.0727, -0.2849, -0.4114, -0.0390, -0.0276, -0.2993, -0.0610, -0.1966, -0.0580, +0.2800, -0.0033, +0.4452, +0.2182, -0.9645, +0.0513, +0.0884],
-[ -0.3226, +0.1336, +0.6645, -0.4503, -0.1672, -0.0602, -0.5145, -0.2136, -0.2340, +0.2906, -0.0673, -0.1477, +0.2186, +0.1079, +0.0486, +0.2164, -0.5336, -0.1297, -0.0875, +0.2970, -0.3045, +0.4400, +0.5784, -0.4019, -0.3110, -0.9414, -0.3346, +0.2523, -0.0274, -0.4475, -0.2102, +0.0897, +0.0419, +0.0503, +0.1835, -0.0535, +0.0689, +0.0691, -0.1349, -0.6753, +0.3090, -0.5637, +0.0200, +0.3919, -0.2876, -0.3861, +0.2904, +0.2580, +0.1847, -0.4541, +0.2357, -0.0827, -0.9218, -0.0946, -0.1218, -0.1566, -0.0611, -0.1368, -0.1764, -0.5379, -0.0988, +0.0806, -0.4375, -0.0130, -0.1357, -0.0778, -0.7153, +0.0455, -0.4599, -0.4328, +0.1127, -0.3466, +0.2376, -0.0922, -0.4810, +0.3056, -0.7828, +0.0528, -0.1335, +0.5371, -0.2253, +0.1008, -0.3593, -0.4297, -0.0838, -0.2490, -0.2259, -0.1838, -0.0699, -0.2224, -0.2921, -0.1630, +0.0722, -0.1825, -0.8208, -0.1545, +0.6346, +0.0748, +0.0044, -0.4955, -0.1173, +0.2172, -0.0944, -0.7999, -0.5529, -0.1711, +0.1271, +0.0247, -0.5756, -0.4206, -0.3636, -0.4627, +0.2299, +0.0614, -1.0937, -0.5468, +0.0510, -0.7410, -0.8884, +0.3174, -0.4159, -0.4072, -0.8816, -0.1527, -0.1486, +0.3125, -0.2283, +0.2177],
-[ +0.0039, +0.0103, -0.1755, -0.7996, -0.0968, +0.0277, +0.1732, -0.3424, -1.4968, -0.1753, -0.0114, +0.2941, +0.1342, +0.2813, -1.7341, -0.5349, +0.0842, +0.3819, -0.5440, +0.0967, +0.0900, -1.4831, +0.3267, -0.0945, +0.1357, -0.3697, -0.1469, -0.4575, +0.1818, -0.6642, -0.0056, -0.1976, +0.0797, -0.1708, +0.1934, +0.2915, -0.1422, -0.0404, -0.2522, +0.0745, -0.5222, +0.1857, -0.1054, -0.4258, -0.1111, -0.3788, -0.0603, -0.3986, -0.5091, -0.0344, +0.3817, +0.2383, -0.1576, +0.2485, +0.3856, +0.0202, +0.0191, -0.5266, -0.1806, -0.1136, +0.1925, -0.5746, -0.9777, -0.3512, -0.0246, +0.0901, -0.5217, -0.0677, +0.0909, +0.2601, +0.9345, -0.3394, -0.0119, -0.0092, -0.4497, +0.3786, +0.0784, +0.0421, +0.0792, -0.3989, -0.0075, -0.0954, +0.1185, -0.1363, +0.0989, -0.1078, +0.1155, -0.0391, -0.1252, -0.2695, -0.0459, -0.2948, -0.3355, -0.5704, -0.0559, -0.2500, +0.4076, +0.0663, +0.2311, -0.0617, -0.0548, -0.0475, +0.4303, -0.0794, -0.2073, -0.7073, -0.0176, -0.0955, -0.0993, -0.5084, +0.0248, -0.0866, -0.8128, +0.0065, -0.0581, +0.3117, +0.0263, -0.1558, -0.0008, +0.2365, -1.1693, +0.4167, -0.1065, +0.4104, -0.2010, +0.0968, +0.0552, -0.0371],
-[ +0.2534, -0.0501, -0.2594, +0.1478, -0.7236, +0.2802, +0.0805, -0.1607, +0.2090, +0.1263, +0.1884, -0.1083, -0.4125, -0.3225, +0.1190, -0.2326, -0.2595, -0.2029, -0.3719, +0.0625, -0.1373, +0.2389, +0.3014, +0.0892, +0.3054, -0.2101, +0.0070, +0.1154, -0.0347, -0.1208, +0.0531, +0.1513, +0.2507, -0.0510, -0.1456, +0.0580, +0.0154, +0.1996, -0.0832, +0.1442, +0.0221, -0.0928, +0.0884, +0.1552, +0.0532, -0.7460, -0.2394, +0.0967, +0.1723, -0.2659, +0.2287, -0.0556, +0.2908, +0.4469, -0.1458, +0.1577, -0.2041, -0.0583, +0.3994, +0.5170, -0.7670, +0.3433, -0.0383, -0.0670, -0.3647, -0.1440, -0.2584, +0.4074, +0.3214, -0.1794, +0.3010, -0.2413, +0.0558, -0.5349, -0.5052, +0.0807, +0.0558, -0.4087, +0.1186, -0.3845, +0.1390, +0.0359, +0.2994, -0.2928, -0.0573, -0.1539, -0.2161, -0.0756, -0.1941, -0.3361, -0.4123, +0.1537, -0.0709, +0.2274, -0.5642, -0.2887, -0.4241, +0.3842, +0.3369, +0.1526, +0.1065, -0.2747, -0.1502, +0.0964, -0.0100, -0.0807, -0.6731, -0.7413, -0.1946, -0.4019, -0.3018, +0.0907, -0.0809, -0.3277, +0.2652, +0.0611, +0.0838, -0.1097, -0.6041, +0.1028, +0.1933, -0.2961, -0.0032, +0.0196, +0.0418, -0.0965, +0.3258, +0.0426],
-[ -0.6308, -0.0501, -0.0838, -0.1519, +0.3868, +0.0165, -0.0647, +0.2359, -0.7684, +0.2470, -0.1684, +0.0552, -0.0439, -0.5137, -0.0342, -0.1471, -0.2033, +0.0010, +0.5120, +0.2452, -0.3707, -0.4031, +0.1284, -0.0031, +0.2168, -0.2880, -0.1485, -0.0316, +0.1138, -0.0230, -0.3823, -0.2558, +0.2216, -0.8283, +0.1104, +0.2202, +0.1233, -0.5009, -0.3594, -1.0594, +0.1320, -0.1490, +0.0831, +0.6580, -0.2022, -0.3214, -0.0493, -0.4918, -0.1414, -0.3596, -1.2959, +0.0334, -0.0096, -0.0637, +0.1090, +0.2714, +0.2888, -0.4400, -0.9489, +0.0081, -0.0942, +0.1463, -0.1739, -0.6975, +0.2816, -0.8516, -0.3003, +0.1234, +0.3339, -0.1227, -0.2146, -0.7996, -0.2116, -0.0534, -0.3831, +0.1300, -0.6559, -0.2496, -0.3875, -0.6497, -0.4172, +0.1083, +0.3429, +0.1460, -0.6197, +0.0890, +0.4016, -0.0499, +0.0776, -0.1099, +0.4072, +0.1516, -1.1238, +0.1015, +0.0881, +0.2689, +0.4516, -0.1882, +0.1791, +0.7761, +0.2232, +0.0939, -0.3682, -0.1288, +0.0489, -0.2183, -0.2398, +0.0578, -0.5142, -0.1569, +0.2860, +0.3591, +0.3800, -0.3455, +0.1576, +0.2144, -0.8416, -0.0603, +0.1336, +0.2087, -0.6990, -0.1888, +0.5619, -0.2315, +0.1561, +0.1132, -0.7656, -0.3181],
-[ -0.1286, +0.1858, -0.2411, +0.0090, -0.3402, -0.2936, +0.1051, +0.1919, -0.2531, +0.4690, -0.6679, +0.3317, +0.2073, -1.1532, -0.7191, +0.0884, -0.0799, +0.2003, -0.1593, -0.1969, -0.2554, -0.2080, -0.2559, +0.3545, -0.8480, +0.4528, -0.2133, -0.4219, -0.4413, +0.1131, -0.0602, -0.1928, +0.0279, +0.1352, -0.2555, +0.2333, -0.2460, +0.0057, -0.8220, -0.0760, +0.0504, -0.9094, -0.6114, +0.1768, +0.0091, -0.0628, -0.1880, -0.2029, +0.2462, +0.1165, +0.2070, -0.1164, -0.1690, +0.1759, -0.1980, -0.2017, -0.2359, -0.5043, -0.7476, -0.3844, -0.1492, -0.5376, +0.2582, +0.3424, -0.1346, -0.1681, -0.4327, +0.0905, -0.2482, +0.1685, +0.3307, +0.1385, -0.2317, +0.2284, -0.6566, +0.2268, -0.1018, -0.2626, -0.0549, -0.3204, -0.1904, -0.0743, -0.8110, +0.2222, -0.0741, -0.0935, +0.1553, +0.1289, -0.1035, -0.0720, +0.4058, -0.3011, +0.0458, +0.2255, -0.6481, +0.0250, +0.1870, +0.1039, +0.1931, +0.1419, -0.7905, +0.0222, +0.2000, -0.1245, +0.2453, -0.4877, +0.2176, +0.2230, -0.5876, -0.0292, +0.0748, -0.3372, -0.0874, +0.0585, +0.4317, -0.0294, +0.3862, +0.3095, -0.2184, -0.5214, +0.3847, +0.0584, +0.3308, +0.0771, -0.0182, +0.1068, +0.0827, -0.3393],
-[ -0.0223, +0.2438, -0.0411, -0.3990, +0.4767, -0.4751, +0.2604, +0.2775, +0.0951, +0.3999, -0.0248, -0.0078, -0.0592, -0.4420, +0.0711, +0.2006, -0.0424, +0.4881, -0.0616, -0.3197, -0.2655, -0.3899, +0.2844, -0.0932, -0.3590, +0.0607, +0.1592, -0.0413, +0.2932, +0.0039, +0.3933, +0.3092, -0.4648, +0.3378, -0.1120, +0.0148, +0.2869, +0.0393, -0.3506, +0.2658, +0.1252, +0.1600, -0.2529, -0.1268, +0.3310, -0.0902, +0.2594, -0.1768, -0.0035, -0.4478, +0.1509, -0.0057, +0.1382, -0.0739, -0.0245, -0.1634, -0.1252, +0.0223, -0.5591, -0.0023, -0.0707, -0.2333, -0.3290, -0.0214, +0.0871, -0.0567, -0.3501, -0.0693, -0.1038, -0.4635, +0.0217, -0.3380, +0.2432, +0.1398, -0.2903, +0.0658, +0.0269, +0.0889, +0.2137, -0.1885, -0.0677, +0.2808, +0.0891, +0.0853, +0.1616, +0.3423, +0.2141, +0.0873, +0.0890, +0.0168, +0.0364, +0.0070, -0.3678, +0.1200, +0.1389, +0.1118, +0.2462, +0.0112, +0.0536, -0.3833, +0.1149, -0.3142, +0.3757, -0.2268, +0.5505, -0.4528, +0.1183, -0.4295, -0.2305, -0.2820, +0.2610, -0.5187, -0.3496, -0.0884, +0.1280, -0.1898, +0.2082, +0.2891, -0.1266, +0.0223, -0.2194, +0.0958, +0.3503, +0.1008, -0.0299, +0.1613, +0.1108, +0.2884],
-[ -0.2112, +0.2139, +0.2353, -1.3735, +0.3379, -0.3306, -0.5791, +0.2142, +0.1661, -0.2046, -0.4202, -0.5208, -0.4747, -0.3524, -0.1866, +0.2010, +0.3635, -0.3221, -0.3282, +0.1993, -0.1151, -0.4721, +0.0627, -0.2138, -0.3382, +0.2179, +0.1286, +0.0916, -0.2135, +0.1114, +0.1641, -0.7235, +0.0271, -0.3165, -0.4372, -0.0611, +0.0824, -0.1537, +0.3468, -0.3766, -0.0373, +0.0722, +0.0230, -0.7669, -0.7521, +0.4481, +0.1352, -0.0385, -0.0233, -0.3938, -0.1916, +0.1151, +0.2809, -0.0007, -0.0378, +0.0906, +0.2414, -0.9108, -0.2856, -0.1401, -0.6404, -0.7260, -0.2588, +0.1096, -0.1461, +0.0196, -0.9551, -0.5937, -0.0863, -0.1227, -0.9528, -0.1206, -0.0116, -0.3274, +0.3520, +0.0632, -0.1109, -0.3264, -0.8242, +0.2668, -0.0588, -0.2727, -1.1266, -0.9705, +0.2631, -0.2931, -0.7791, -0.9120, +0.2401, +0.0197, -0.0931, -0.5968, +0.5901, +0.1350, +0.0918, -0.5455, -0.6439, +0.4476, +0.2893, -0.5928, +0.0521, -0.3101, -0.0489, +0.0052, -0.3169, -0.4701, -0.6680, -0.0638, +0.1298, -0.4204, -0.0254, +0.1195, -0.0933, -0.1896, +0.0503, -0.7819, +0.1228, +0.0729, -0.0561, -0.0014, -0.0664, +0.2052, -0.7386, +0.4056, -0.0660, -0.9663, -0.2771, -0.5232],
-[ -0.1246, -0.2805, -0.3576, +0.2033, +0.1179, +0.0137, -0.6560, -0.2292, -0.5633, -0.0186, -0.2827, +0.1622, +0.1316, -0.4703, -0.7199, +0.2989, +0.1364, -0.1050, +0.4184, -0.0721, -0.1984, -0.8043, +0.1757, +0.1660, +0.1198, -0.6675, -0.1686, -0.0080, -0.0535, -0.2755, -0.0087, -0.0772, -0.1946, -0.1625, +0.2803, -0.4290, +0.3188, -0.5116, +0.3810, -0.4627, -0.3474, -0.0296, -0.0126, -0.5452, -0.1713, +0.0726, +0.1517, -0.3349, +0.2804, -0.4211, -0.3698, -0.0776, +0.5157, -0.0116, -0.1578, -0.2274, -0.5434, -0.7078, -0.1557, +0.1799, -1.7247, +0.0598, -0.2763, -0.2002, -0.1513, +0.0315, +0.1172, -0.5970, -0.4829, -0.1757, -0.6510, -0.2016, +0.0722, -0.2784, +0.2477, -0.1084, +0.3574, +0.2216, -0.2019, -0.0929, -0.2401, -0.0009, +0.0100, +0.3262, +0.1323, -0.3393, +0.0441, +0.0237, -0.1123, -0.3906, +0.1925, +0.2541, +0.0079, -0.3655, +0.1809, +0.0290, -0.2198, +0.2628, -0.1835, +0.1061, +0.2996, +0.5976, -0.0171, -0.0882, +0.0488, +0.0209, -0.4426, -0.1461, -0.7127, +0.0345, -0.0908, -0.0087, -0.6902, +0.0474, +0.3433, +0.2376, +0.0280, +0.1350, -0.6906, -0.1005, -0.3456, -0.4074, -0.3707, -0.4556, +0.1230, +0.1421, -0.1536, +0.4549],
-[ +0.4253, -0.1862, -0.2521, +0.0973, +0.2793, -0.0849, -0.1390, +0.2692, +0.2426, +0.1690, -0.0772, -0.0276, +0.1998, +0.0185, -0.1736, -0.0510, -0.1957, +0.2297, +0.2222, -0.0429, -0.1558, -0.9350, +0.1733, +0.2294, +0.2759, -0.1063, -0.6416, -0.2152, +0.0899, -0.4758, -0.0466, +0.0209, +0.0777, -0.6026, +0.1939, -0.1837, +0.1779, +0.1248, -0.1254, -0.2091, -0.1979, +0.4873, +0.1698, +0.0795, -0.1283, +0.0153, -0.4910, +0.3692, -0.0166, +0.0893, -0.3555, -1.2133, -0.3912, -0.3162, +0.1056, +0.3104, -0.0164, +0.4362, -0.1710, -0.5106, -0.0164, +0.3129, -0.7867, +0.1497, +0.0967, -0.0521, +0.1755, -0.1235, +0.1731, +0.2002, +0.2755, -0.0072, +0.2876, +0.2190, +0.0101, +0.1913, -0.3036, +0.3041, +0.2350, +0.3212, +0.1128, +0.1641, -0.5767, +0.1855, +0.0141, +0.2336, -0.1784, -0.2715, +0.0631, -0.1110, +0.2796, +0.1881, +0.2210, +0.4339, +0.1268, -0.1757, +0.1511, +0.0015, -0.0059, +0.0019, +0.2075, +0.1971, +0.1113, +0.0985, +0.0434, -0.2494, +0.2593, +0.0467, -0.5946, -0.2618, -0.1521, -0.2028, +0.2417, -0.6486, -0.1829, +0.0708, -0.1101, +0.1115, +0.0227, +0.1591, -0.4037, -0.0098, +0.0621, -0.4142, -0.1739, +0.4112, +0.3607, -0.5380],
-[ +0.1177, -0.0829, -0.2037, -0.2156, +0.1920, +0.1360, -0.1985, -0.0925, -0.5613, -0.2878, -0.1383, -0.1178, +0.2660, -0.2264, -0.3758, +0.0474, +0.0023, +0.1017, -0.4475, -0.0988, +0.2955, -0.4085, -0.2192, +0.1311, -0.3999, -0.3496, -0.1175, -0.4424, -0.4607, -0.0673, -0.1690, -0.2330, -0.3726, -0.0566, -0.3821, +0.0028, +0.1176, +0.1637, -0.3063, -0.2605, +0.4228, +0.5291, +0.0629, +0.5256, -0.3477, +0.4640, +0.0645, -0.5641, -0.2468, +0.2339, +0.1751, +0.0718, +0.3500, -0.4988, -0.1264, -0.0177, +0.1769, -0.0400, -0.2931, -0.0032, +0.3511, +0.2182, -0.4131, -0.6258, -0.2432, -0.0031, -0.4084, -0.1694, -0.1345, -0.0997, -0.2085, -0.1604, +0.3349, +0.2521, +0.1971, -0.1442, +0.2636, -0.1359, -0.0244, -0.5738, +0.1898, -0.0964, +0.3351, +0.1642, +0.1135, -0.3388, -0.1054, -0.0207, +0.0978, +0.0311, +0.0011, -0.0103, -0.3878, -0.1310, +0.1785, +0.0105, +0.0070, -0.2280, +0.1466, +0.1476, -0.0045, -0.4846, +0.3915, -0.2372, -0.0766, -0.4503, -0.1964, +0.1785, +0.1047, +0.8291, +0.1383, +0.1750, +0.2304, +0.1486, +0.1168, -0.0636, +0.0268, -0.0029, +0.1824, -0.4461, +0.2138, +0.0789, +0.2332, +0.3060, -0.2309, -0.1640, -0.2015, +0.0814],
-[ -0.2089, +0.1014, -0.0579, +0.3885, -0.0160, +0.3301, -0.4470, +0.4714, -0.1930, -0.4235, -0.0122, -0.5872, +0.3336, +0.0962, +0.1576, +0.0089, +0.0542, -0.1455, -0.1269, +0.1636, -0.1596, -0.1467, -0.0751, -0.3372, -0.0210, -0.3890, +0.2495, -0.5069, +0.2558, +0.2504, -0.0504, -0.1370, -0.1636, +0.1638, -0.4274, -0.4883, +0.1807, -0.3299, -0.2602, -0.1714, +0.3408, +0.1558, +0.3440, -0.2063, +0.3495, -0.0942, -0.1896, +0.1604, +0.2981, +0.0938, +0.3079, -0.0422, +0.2457, -0.0888, -0.1330, +0.3858, +0.1828, +0.2261, +0.0589, +0.0212, +0.2386, -0.2637, -0.1125, -0.6084, -0.1772, +0.1757, -0.0477, -0.4429, -0.5084, -0.0512, -0.0579, +0.2526, +0.2676, -0.3652, +0.0563, +0.1303, +0.1980, -0.1137, -0.1055, +0.1332, +0.2540, -0.0726, -0.2244, +0.1358, +0.1327, -0.5314, -0.5776, +0.0586, +0.4645, -0.5067, +0.2115, -0.8910, -0.0485, -0.2118, +0.0909, +0.4667, +0.1512, -0.4808, +0.0252, -0.1659, +0.2356, -0.1116, +0.0382, +0.0931, +0.1761, +0.0300, -0.3396, -0.1821, +0.1245, -0.1004, -0.1907, +0.1104, -0.0528, -0.1555, -0.0645, +0.0562, -0.2227, +0.3703, -0.2504, -0.1985, -0.2180, -0.1775, +0.2405, -0.0889, +0.1268, +0.3380, -0.3181, +0.3610],
-[ -0.1952, -0.0578, -1.1057, +0.5134, -0.1378, +0.2639, -0.1665, -0.3419, -0.1661, +0.1025, -0.0394, -0.0055, -0.3502, +0.3829, +0.0351, -0.8268, -0.4556, +0.1120, -0.0705, +0.2972, -0.4725, +0.0838, +0.3422, -0.5389, -0.2642, -0.2428, -0.4464, -0.1878, +0.3799, +0.0833, -0.3188, +0.1659, -0.5127, -0.1637, -0.5105, -0.3803, +0.1553, +0.1436, -0.2048, -0.0348, +0.1922, -0.2446, -0.6350, -0.6326, +0.3759, -0.8518, -0.2066, -0.3527, -0.9225, +0.5922, +0.1130, -0.6997, +0.0371, +0.1281, +0.0358, -0.3420, +0.0422, -0.1585, +0.0060, -0.2306, +0.0093, +0.3616, +0.1565, -0.4825, -0.2306, -0.6262, +0.0261, +0.1737, -0.8466, +0.1037, +0.1481, -0.1724, -0.0477, -0.2328, -0.7668, +0.0539, -0.0205, -0.1615, +0.1709, +0.1200, +0.0062, -0.1006, -0.0631, -0.6605, +0.3073, +0.0534, -0.1759, -0.0048, +0.3530, -0.0488, -0.3439, +0.6192, -1.0127, -0.4404, -0.1655, +0.2329, +0.1701, -0.0102, -0.6998, -0.5205, -0.3661, -0.3588, -0.0991, -0.0539, -0.1724, -0.0598, +0.0298, -0.5078, -0.2480, +0.2300, -0.0248, -0.8744, +0.1165, -0.3571, -0.2669, -0.3494, +0.1781, +0.3223, -0.0251, +0.1327, +0.5895, +0.4107, -0.1365, -0.4952, -0.2869, +0.1122, +0.2460, +0.4473],
-[ +0.1338, -0.0063, -0.2522, -0.1941, +0.2738, -0.2233, -0.2280, +0.2611, -0.0943, -0.3515, -0.0844, +0.2064, -0.0363, -0.3102, -0.3898, +0.0770, +0.2784, -0.1512, -0.1478, -0.0007, -0.1822, -0.2255, -0.5550, +0.2976, +0.2547, +0.0151, +0.0828, -0.0848, -0.2138, -0.0103, -0.8352, +0.1319, -0.2303, -0.2299, -0.0563, -0.3885, +0.0342, -0.4977, -1.2963, +0.2561, -1.1328, +0.0012, +0.2306, -0.5411, -0.3006, +0.0676, -1.9030, -0.3075, -0.0979, +0.0896, -0.0580, -0.0038, +0.1381, +0.0090, +0.1478, -0.3079, +0.2841, -0.1863, -0.6163, -0.1751, -0.5646, +0.4300, +0.0704, -0.0387, -0.2823, +0.2259, -0.0953, -0.2159, -0.2969, -0.3502, -0.3141, -0.1517, +0.0782, +0.0999, +0.5229, -0.1531, -0.2047, -0.1471, +0.2247, -0.2625, +0.0019, -0.1073, -0.0022, -0.4420, +0.0517, -0.0580, -0.6427, -0.2424, +0.1411, -0.0678, -0.1120, -0.8540, -0.2692, +0.2238, -0.2368, -0.9063, +0.2976, +0.0414, +0.1095, +0.2244, +0.0210, -0.1006, -0.2540, -0.1564, -0.0956, -0.1224, -0.5763, +0.2323, -0.1224, +0.2074, -0.5607, -0.5861, -0.0902, +0.1296, +0.1034, -0.2310, -0.2814, -0.1924, +0.1452, -0.5430, -0.0619, -0.4562, +0.2069, +0.2684, -0.2071, -0.7354, -0.2258, -0.1395],
-[ -0.1963, -0.0107, -0.0423, +0.0007, +0.3431, +0.3000, -0.2971, +0.3827, -0.2744, -0.6258, -0.7529, -0.2262, -0.0908, +0.7792, -1.4345, -0.7595, -0.0323, -0.4281, -0.0325, +0.0773, -0.4141, +0.1006, +0.5800, +0.4668, +0.3735, -0.3455, -0.2889, -0.2550, +0.2045, -0.2958, -0.0868, -0.0470, -0.2008, +0.1274, +0.0259, +0.1598, -0.2579, -0.5582, -0.0712, +0.2501, -0.4543, +0.1671, -0.0398, -0.3789, -0.6567, +0.3653, -0.5175, -0.0741, -0.1428, -0.9625, -0.1969, +0.3227, -0.7710, -0.2489, +0.0553, +0.1062, +0.2338, -0.8710, -0.2630, +0.1344, +0.2044, -0.1054, -0.3221, -0.7012, -0.1819, -0.1221, -0.0658, -0.0748, -0.3830, +0.3178, +0.6506, -0.3111, -0.4665, +0.2741, -0.2561, +0.2261, -0.4738, -0.0788, +0.0114, -0.5013, -0.6076, -0.4491, -0.4184, +0.6562, +0.3299, -0.1993, +0.3129, -0.6395, -0.0735, -0.5297, +0.0319, +0.4652, +0.6208, +0.0026, -0.1381, -0.5193, +0.0792, +0.5061, -0.5610, +0.5022, -0.1293, -0.0424, -0.2379, -0.2926, -0.4384, -0.4252, -0.6475, +0.4550, -0.1399, -0.3108, -0.6347, +0.2680, +0.6766, +0.5618, +0.0904, -0.0573, -0.3292, +0.1988, -0.2317, +0.3934, -0.3043, -0.1623, -0.4827, -0.1761, -0.1059, +0.0525, -0.0313, -0.1475],
-[ -0.0720, -0.0474, -0.0168, +0.1428, -0.1180, -0.3548, +0.4974, -0.7262, -0.2118, +0.1000, -0.0795, -0.2894, -0.0655, -0.0423, -0.1659, +0.1347, +0.0860, -0.2163, -0.5078, -0.2881, +0.1382, -0.4808, +0.0168, +0.3667, -0.3162, -0.3973, -0.1601, -0.2069, -0.1248, +0.2609, +0.0856, +0.0030, +0.1974, +0.3896, +0.0707, -0.1730, -0.1112, +0.2419, -0.1894, -0.1437, +0.0670, -0.2615, -0.3430, +0.1329, -0.0827, -0.8066, -0.0254, +0.1680, +0.2338, -0.9633, +0.1481, -0.1104, +0.1121, +0.2071, +0.2378, +0.1063, -0.1278, -0.1192, +0.2428, +0.2460, -0.0064, +0.0025, +0.4307, +0.4768, -0.8693, +0.2835, -0.2696, +0.0314, -0.0276, -0.1222, +0.2166, +0.2363, -0.2178, +0.3113, -0.8229, -0.2482, -0.4106, +0.1824, -0.0883, +0.0695, -1.2673, -0.3113, +0.1158, +0.2840, +0.1894, -0.7726, +0.3572, +0.0157, +0.0035, -0.2735, +0.2097, -0.6630, +0.0192, +0.0644, -0.1819, -0.0937, -0.2322, +0.3941, -0.1772, +0.0560, +0.0390, -0.4749, +0.0099, -0.3858, -0.1375, -0.0988, -0.6115, -0.1879, -0.1092, +0.0315, +0.2415, -0.2787, -0.0006, -0.0118, +0.2440, -0.0432, -0.1334, -0.1346, -0.4602, +0.1854, +0.1047, -0.0036, -0.2341, -0.1576, +0.0653, +0.1567, +0.1526, +0.1044],
-[ +0.1769, -0.1034, -0.1948, -0.1274, -0.1648, +0.5893, -0.0946, -0.2004, -0.2721, -0.3387, +0.3898, -0.3109, +0.1371, +0.1680, -0.7257, +0.1351, -0.6586, +0.2851, +0.1728, +0.1130, -0.0131, -0.4239, +0.1692, +0.1324, -0.3443, +0.2481, +0.1447, -0.3541, +0.1374, +0.0410, -0.1387, +0.1571, +0.1503, -0.0262, -0.0774, -0.1869, -0.0378, +0.2104, +0.0172, -0.1452, -0.4186, +0.2158, +0.2101, +0.2539, +0.3134, -0.0346, -0.0244, -0.2532, -0.1317, -0.0540, +0.0459, -0.1373, +0.1366, -0.0571, +0.1385, +0.1867, -0.1449, -0.1944, +0.3466, +0.0981, -0.1643, +0.0219, -0.0246, -0.3430, +0.0084, -0.6418, +0.1014, +0.0666, +0.2488, -0.2650, -0.1532, -0.2495, +0.0428, -0.4240, -0.2821, -0.0754, +0.2721, +0.4462, -0.8370, -0.0485, +0.1678, -0.2672, +0.3932, -0.1626, +0.1755, -0.5960, -0.0072, +0.6288, +0.0466, -0.0260, -1.0479, -0.5837, -0.1394, +0.0547, +0.1121, -0.6113, -0.5292, -0.6037, -0.2560, +0.2865, -0.2272, -0.2464, +0.1547, -0.0282, -0.8408, +0.3033, +0.1790, -0.1641, -0.3059, +0.1309, -0.3210, -0.0627, +0.2607, -0.0373, +0.0129, -0.2009, -0.3511, -0.1189, -0.2208, -0.0538, +0.0637, +0.1723, -0.5148, +0.2267, +0.1132, +0.0045, -0.1421, +0.1912],
-[ +0.0906, -0.1130, -0.2077, +0.1502, +0.3574, -0.4087, -0.1618, -0.1510, +0.2428, -0.3561, -0.3971, -0.2274, -0.1077, +0.2071, +0.5784, +0.3420, +0.2530, -0.1951, -0.1346, +0.2660, -0.0259, +0.0771, -0.0849, +0.3132, -0.0404, -0.1513, -0.0255, +0.1137, +0.3354, -0.1369, -0.1115, -0.1645, +0.1585, -0.2722, +0.4510, -0.0847, -0.0087, -0.1398, +0.0353, -0.0701, -0.4510, -0.8897, +0.0337, -0.0026, +0.1252, +0.0948, +0.2133, +0.2421, -0.2473, +0.2771, +0.3732, -0.0731, -0.4412, -0.0749, +0.1336, -0.0273, +0.1484, -0.3783, +0.1017, +0.0390, -0.5518, +0.0037, -0.6220, +0.2184, +0.3016, +0.0485, +0.1901, +0.2104, +0.1166, -0.1032, +0.3395, -0.0177, -0.3512, +0.1229, +0.0400, +0.2339, -0.5922, -0.4052, -0.5183, +0.4653, +0.1410, +0.2020, +0.1406, -0.1232, +0.2124, -0.1376, -0.2617, -0.0459, -0.4286, -0.7037, -0.0695, -0.5891, +0.0045, -0.1987, -0.3906, +0.1380, +0.0949, -0.3112, -0.2688, -0.1340, -0.2209, -0.3564, -0.1459, +0.3078, +0.0459, +0.2045, +0.1436, -0.1081, -0.6286, -0.3076, +0.1346, +0.1734, -0.0212, +0.2784, -0.2703, -0.5880, -0.1379, +0.0307, +0.4657, -0.2370, -0.6191, -0.0113, +0.2450, -0.0045, +0.1112, -0.0822, +0.3822, -0.0562],
-[ +0.1409, -0.0538, -0.1432, +0.1716, +0.1670, +0.1345, +0.3174, +0.0786, +0.3477, -0.5395, -0.3514, +0.2158, +0.0896, -0.1822, +0.2500, +0.4068, +0.3118, +0.3923, -1.1109, -0.2122, +0.0909, +0.1655, +0.1356, +0.4056, -0.3149, +0.1185, +0.1717, +0.0258, -0.1728, +0.2402, -0.0251, -0.0708, -0.0743, -0.1093, +0.5213, +0.0419, -0.1286, +0.1853, +0.4699, -0.5875, -0.2311, +0.4390, -0.3652, +0.2524, -0.0379, -0.1384, -0.1974, -0.3096, +0.0594, +0.0794, +0.0578, +0.1156, -0.9567, -0.3747, +0.2159, +0.1118, -0.0018, -0.4289, -0.0497, +0.5024, +0.0897, -0.5219, -0.4890, -0.1756, -0.1832, +0.1821, +0.3873, +0.0030, -0.7192, +0.0757, +0.4871, -0.8119, -0.0317, +0.3589, -0.1295, -0.0279, -0.1444, -0.8395, -0.3653, +0.1671, -0.0373, +0.0349, -0.0650, +0.2142, -0.1536, -0.2972, +0.0513, -0.2596, +0.1086, -0.5500, +0.5186, -0.1609, -0.2082, -0.9726, -0.0006, -0.2899, +0.1783, -0.1634, -0.5750, -0.0325, -0.2408, -0.0379, +0.1189, +0.0418, +0.3697, +0.2451, +0.1595, -0.2399, -0.1088, -0.1213, -0.4627, +0.2782, +0.0666, -0.0095, -0.4685, -0.5872, +0.1120, +0.1272, +0.0088, -0.4947, +0.3034, +0.0580, -0.2964, +0.0579, -0.1105, -0.1897, +0.0601, +0.0605],
-[ -0.0967, -0.8116, -0.1189, -0.5744, -0.3304, -0.6346, +0.1212, +0.2593, -0.0239, +0.2636, +0.0874, -0.4657, +0.1628, +0.6463, +0.2373, -0.6677, -0.1700, +0.1728, -0.3091, +0.2459, +0.3715, -0.7096, -0.0390, +0.4462, +0.6917, -0.5975, -0.0984, +0.5475, +0.4104, -0.1399, -0.1059, +0.0950, +0.1488, +0.1787, +0.3116, -0.1217, +0.1377, +0.1193, -0.4545, -0.5360, +0.6137, -0.1851, +0.2568, -0.1605, -0.0478, -0.8687, +0.4071, -0.1072, -0.1179, +0.2131, +0.0615, -0.2244, -0.2624, -0.0859, -0.0773, +0.0423, +0.0499, -0.3312, -0.1253, +0.0579, -0.0270, +0.1835, +0.1067, -0.3907, +0.2115, +0.0562, -0.1266, +0.0306, +0.1233, -0.0524, +0.0968, -0.5194, +0.2325, +0.3540, -0.4088, +0.0112, -0.2728, -0.4368, -0.3143, -0.1848, +0.0044, +0.1795, -0.1937, -0.4705, +0.1564, -0.4308, +0.2992, +0.1559, +0.1413, -0.5684, -0.5887, -0.4417, +0.1254, +0.6016, +0.3093, +0.2221, +0.2689, +0.2764, +0.2066, +0.3921, -0.0492, +0.5264, +0.1195, +0.0354, +0.0472, -0.7510, +0.4551, -0.3297, +0.2557, +0.0964, -0.2333, -0.0974, +0.0046, -0.1966, -0.1438, +0.2168, -0.0106, +0.0827, +0.1734, -0.1622, -0.7648, +0.0657, +0.4125, -0.0107, +0.5142, -0.1843, -0.0255, +0.0251],
-[ -0.4894, -0.3838, -0.0560, -0.0102, +0.2462, +0.2396, -0.1605, +0.6648, +0.0289, +0.3985, -0.3124, -0.1270, +0.0019, -0.0186, -1.0743, +0.6784, +0.1577, +0.2268, -0.0569, +0.2442, -0.1164, -1.2692, -0.6146, -0.5071, -0.0065, -0.1015, +0.0568, -0.0257, -0.1093, -0.1685, +0.5144, -0.0581, +0.5970, +0.3194, -0.3760, +0.2867, +0.3716, -0.2157, -0.1207, +0.3089, +0.5712, +0.2472, +0.0238, -0.7120, +0.0921, -0.5046, -0.4643, +0.3063, +0.0916, -0.7755, +0.0375, +0.1377, +0.4099, +0.1541, -0.0234, -0.2307, -0.2292, +0.1845, -0.3229, -0.0655, -0.0224, -0.3936, +0.1464, -0.2497, -1.0163, -0.0754, -0.2383, -0.1563, +0.0342, -0.2338, +0.3699, +0.0190, +0.3233, +0.0361, -0.3095, +0.1544, -0.2940, -0.0897, +0.2073, +0.4680, -0.3452, -0.1035, -0.1820, -0.5826, -0.4127, -0.5719, -0.2433, +0.1142, -0.1415, -0.4814, -0.1358, -0.0734, +0.4341, +0.2401, -0.4429, +0.3538, -0.2312, -0.2072, +0.0078, -0.2757, -0.2212, +0.0824, -0.0945, -0.2644, +0.0169, -0.6544, -0.0961, -0.2083, +0.4017, -0.6613, -0.2524, +0.2338, -1.7121, -1.9104, +0.2422, -0.0147, +0.3072, -0.3819, +0.3498, -0.4022, -0.4189, +0.4619, +0.1477, +0.3179, -0.2559, -0.0367, +0.1080, -0.3277],
-[ +0.0885, -0.4506, +0.4188, +0.2334, +0.2903, +0.0490, -0.0631, -0.0504, +0.2215, -0.1555, -0.0389, -0.1621, +0.0310, -0.4083, -0.3338, -0.2568, +0.0147, +0.1238, -0.5747, +0.0482, -0.2570, -0.2541, -0.0272, +0.2152, +0.0003, +0.3637, -0.2845, +0.0474, +0.1485, -0.3750, -0.4793, +0.4647, +0.0522, -0.6269, -0.1822, -0.0465, +0.1702, +0.2424, -0.1810, -0.1115, -0.5531, +0.0817, +0.0351, -0.0986, +0.0474, -0.4087, -0.0984, -0.2288, -0.0353, +0.0090, -0.1881, -0.1815, -0.0516, +0.1652, +0.3100, +0.2649, +0.2842, +0.3319, +0.4483, +0.2002, -0.1618, +0.1024, -0.1409, +0.3892, +0.2560, +0.1263, -0.0126, -0.0984, +0.3725, +0.1183, -0.2909, +0.1879, +0.1049, -0.1430, -0.1976, +0.2291, -0.2020, +0.1399, +0.0848, +0.0876, +0.2030, -0.0233, -0.3914, -0.0174, -0.0214, -0.0481, -0.2875, +0.0232, +0.0775, -0.6476, -0.2746, -0.3848, -0.0085, -0.5357, -0.5196, +0.1634, +0.1043, +0.0855, -0.0452, -0.0374, +0.1830, -0.2180, +0.1506, -0.1684, +0.0160, +0.0860, +0.4804, -0.0316, -0.3141, -0.1559, -0.4767, -0.1185, -0.1897, -0.0881, -0.1665, +0.0357, -0.3111, +0.0422, -0.1488, -0.1632, -0.7307, +0.0462, +0.0164, -0.0160, +0.0143, +0.3344, +0.3005, +0.2044],
-[ -0.1839, -0.1799, -0.5069, +0.3499, -0.0474, +0.3088, -0.3604, -0.3482, +0.0276, -0.4781, -0.1208, +0.1777, -0.2034, +0.0649, -0.2837, +0.0718, +0.1179, -0.5131, +0.0390, -0.2522, -0.0683, -0.0128, -0.1180, +0.3263, -0.4664, -0.2562, -0.1115, +0.2541, -0.1521, -0.2567, -0.2162, -0.8788, +0.1234, +0.0628, -0.4491, +0.0485, +0.1332, +0.4184, -0.1297, +0.2791, -0.3251, -0.3365, +0.1526, +0.2818, -0.1102, -0.2195, -0.3119, -0.0794, -0.0632, +0.0212, -0.5798, -0.3181, +0.1821, +0.5628, +0.2593, +0.0294, +0.1707, +0.3392, -0.4010, -0.3270, -0.0918, -0.1726, -0.1836, -0.9079, +0.1893, +0.2778, -0.0391, +0.0554, +0.1980, +0.2862, -0.4825, +0.1002, -0.8366, +0.1210, +0.0550, +0.1069, -0.3516, +0.1627, -0.3116, -0.0464, +0.0496, -0.1154, -1.9989, +0.0147, +0.1130, -0.1936, -0.1085, -0.1807, +0.2358, +0.3699, -0.1481, -0.1616, +0.1135, -0.7175, -0.0026, +0.2132, -0.1823, +0.1340, +0.1992, +0.0517, +0.0738, +0.0116, -0.4166, +0.0767, +0.1451, -0.4632, -0.4240, +0.2534, +0.0618, +0.1764, +0.1874, -0.1760, +0.3762, -0.0860, +0.2035, -0.8606, -0.1828, -0.1658, +0.0730, -0.1324, -0.6475, +0.1506, -1.5427, -0.1539, +0.3581, +0.1685, -0.0010, -0.4744],
-[ -0.0038, +0.2629, -0.0222, -0.4313, +0.2458, -0.0521, +0.2995, +0.1401, -0.1501, +0.2219, -0.0508, -0.6905, +0.2089, -0.1588, -0.1579, +0.3263, +0.1093, +0.1843, -1.6538, -0.1711, +0.0280, +0.0042, +0.1678, +0.3942, -0.1122, -0.7447, +0.1776, +0.0452, +0.0464, +0.1958, -0.5837, -0.2740, -0.8022, -0.0597, -0.1732, -0.3843, -0.1682, +0.4161, +0.5845, +0.0023, -0.0245, -0.0033, -0.0888, -0.0147, -0.0569, -0.7998, +0.1384, -0.1289, +0.3003, -0.0507, -0.4349, +0.5294, +0.0240, +0.1736, -0.1584, -0.1868, +0.2200, +0.0831, -0.6566, -0.1660, +0.1753, -0.0999, -0.5722, -0.1753, -0.4500, -0.0143, -0.2124, -0.0305, -0.8012, +0.2173, -0.1607, +0.3925, -0.3454, -0.6074, -0.1541, -0.4732, -1.1834, -0.0688, -0.0430, -0.5353, -0.1790, -0.4362, -0.2226, +0.0306, -0.0149, -1.2302, -0.6747, -0.3040, +0.1048, -0.6485, -0.4555, +0.0236, -1.1733, +0.5728, -0.1619, +0.1556, +0.1970, -0.2370, -1.8582, -1.0090, +0.0693, -0.1693, -0.1371, +0.3884, -0.1606, -0.2022, -0.2294, +0.5752, -0.0680, +0.2737, -0.1054, -0.5773, -1.0577, +0.0026, +0.1283, -0.2511, -0.0521, +0.1820, -0.6071, +0.1580, -0.1609, -0.1862, -0.1680, -0.1709, -0.1637, -0.2186, -0.2398, -0.2395],
-[ -0.1990, -0.1855, -0.5902, -0.1221, -0.8566, -0.1161, -0.2680, -0.2043, +0.0571, -0.2467, -0.5931, +0.0254, +0.2520, -0.0025, +0.3188, -0.2049, -0.1082, -0.2633, -0.3426, -0.3033, -0.4411, +0.2479, -0.4121, -0.2249, -0.2227, -0.3816, +0.1910, +0.2194, -0.0299, -0.0100, -0.2124, +0.4138, -0.2423, -0.0244, +0.1657, +0.0472, +0.0487, -0.3765, -0.1005, -0.1568, +0.3201, +0.4085, -0.1769, -0.6161, +0.1530, +0.0596, -0.1156, -0.8411, +0.1763, +0.0797, -0.6425, +0.3897, -0.2085, -0.1751, -0.0950, +0.1567, +0.0639, -0.1603, -0.3423, +0.1372, +0.2382, +0.1874, -0.0615, +0.0112, -0.1747, -0.6345, -0.5276, +0.1812, +0.4886, -0.0955, -0.1977, +0.0003, -0.1835, -1.0626, -0.3339, +0.1317, -0.2761, -0.2422, -0.6792, -0.0781, -0.3236, -0.1302, -0.3486, -0.7894, -0.6369, -0.4031, -0.1746, -0.1511, -0.2680, +0.0775, -0.5212, -0.1803, -0.4150, -0.3021, +0.4448, -0.4643, +0.3082, +0.5188, +0.3292, -0.1640, +0.2659, -0.0533, +0.0046, -0.2112, +0.0273, -0.3975, +0.1884, -0.2407, +0.5993, -0.0079, -0.1007, -0.3500, -0.7119, -0.2974, -0.2962, -0.1762, +0.0230, +0.2033, +0.1797, +0.0175, -0.3485, +0.2241, +0.1257, -0.1503, -0.3651, -0.4343, +0.0671, -0.2769],
-[ -0.2600, +0.3728, -0.1667, -0.2300, -0.1080, -0.4825, -0.1574, -0.2525, -0.1608, +0.3153, +0.3603, +0.1668, -0.1195, -0.0257, -0.1009, +0.2942, +0.1748, -0.3680, +0.4175, +0.1282, +0.2824, -0.8205, +0.3949, +0.0005, -0.0312, +0.2784, +0.1849, +0.0828, +0.1771, -0.6393, +0.0286, +0.2044, +0.5371, +0.1309, -0.1426, +0.0577, -0.3925, +0.1035, +0.2724, -0.4162, -0.2550, -0.0506, +0.1085, -0.0336, -0.3512, +0.1353, +0.2077, -0.2278, +0.1395, -0.0786, -0.3421, +0.5657, -0.5820, +0.1765, +0.0473, +0.0195, +0.0008, +0.0445, -0.0457, -0.0523, +0.2640, +0.1286, -0.0769, +0.1583, +0.0020, -1.1252, -0.3394, -0.2469, -0.2057, -0.0182, +0.0225, -0.4020, +0.0443, +0.3486, +0.3001, +0.1069, +0.2708, -0.3042, -0.0407, +0.1189, -0.1185, -0.6579, +0.1502, -0.0180, -0.1439, -1.4340, -0.0236, -0.1200, -0.3519, +0.2684, -0.9712, +0.4391, +0.2379, -0.0626, -0.3674, -0.0832, -0.1493, -0.5778, -0.0028, -0.3108, -0.3896, -0.5958, -0.0574, +0.0678, +0.3899, -0.3551, -0.6014, -0.6356, -0.0705, +0.1556, +0.2318, +0.1251, -0.0145, +0.0445, +0.1474, -0.0408, -0.5473, +0.0390, -0.0862, +0.3692, +0.0987, +0.0798, -0.2238, -0.0353, +0.0702, +0.1057, +0.1381, +0.0884],
-[ -0.1550, -0.6553, -0.0098, -0.0513, +0.4681, -0.4697, +0.3507, -0.6614, -0.1393, +0.2851, -0.2353, +0.1117, +0.3554, -0.4386, -0.3174, -0.8774, -0.7019, +0.2315, -0.2981, -0.2346, +0.5748, +0.3798, -0.0704, -0.0219, +0.2735, -0.1494, -0.1263, -1.4348, +0.3184, -0.1334, -0.0568, +0.1348, -0.5653, -1.3195, -0.4193, +0.0257, -0.6081, -0.2396, +0.5183, +0.0537, -0.4824, +0.1120, -0.1459, -0.6086, +0.2357, -0.4124, -0.1445, -0.6436, -0.1888, -0.2544, +0.3426, -0.6475, +0.2406, +0.4602, +0.1544, +0.1915, -0.8082, +0.3168, -0.2569, +0.0707, +0.1043, +0.0112, +0.5536, +0.2491, -0.4264, -0.4461, +0.4385, -0.2794, +0.0615, -0.1656, -0.3143, +0.1733, -0.5887, -0.1564, +0.0588, +0.2128, +0.4712, -0.0338, +0.2120, -0.0114, -0.2567, -0.4390, +0.1800, +0.1231, -0.0566, +0.0131, +0.3387, -0.1946, -0.0597, +0.6877, +0.3091, -0.3047, -0.0256, +0.3494, -0.5286, -0.1652, +0.4785, -0.6145, -0.5849, +0.3488, -0.2858, +0.0411, -0.0751, -0.0106, +0.0322, +0.1082, +0.1757, -1.0412, -0.1001, +0.1272, -0.2649, -0.2981, +0.0066, -0.6085, -0.2164, +0.3369, -0.4131, -0.3749, -0.1556, -0.2250, +0.3331, -0.7518, +0.5474, +0.2815, -0.1135, -0.0068, +0.0842, +0.1357],
-[ -0.2586, +0.1079, -0.0247, +0.2432, +0.2292, -0.1817, +0.0774, -0.5248, -0.7265, +0.0755, -0.2294, -0.1428, -0.3254, +0.0887, -0.2064, -0.2610, +0.4028, -0.3058, -0.6010, +0.1141, -0.3263, -0.0803, -0.0203, +0.0699, -0.0710, -0.6511, -0.1640, +0.4584, -0.2584, +0.2199, +0.3318, -0.4902, +0.0846, -0.0167, +0.2071, -0.3865, +0.0593, +0.4101, -0.1511, -0.4140, +0.1307, +0.0728, -0.1314, +0.2545, -0.1680, +0.1449, +0.2776, +0.1651, -0.1073, -0.0356, -0.2519, +0.6122, -0.0189, -0.6031, +0.2458, +0.2116, -0.3389, +0.1072, +0.1387, +0.2409, -0.2313, +0.1170, -0.0619, +0.1290, -0.4353, +0.0356, -0.2926, +0.0432, -0.7712, -0.3432, -0.0004, -0.2343, -0.0708, +0.0205, -0.0015, +0.1525, +0.0152, +0.0648, +0.3449, -0.4003, +0.0074, +0.1720, -0.0653, +0.1272, +0.2053, +0.1385, -0.0542, +0.1896, +0.3601, -1.3929, +0.1053, -0.1274, -0.0188, -0.0037, +0.3852, -0.4051, -0.4026, +0.0011, +0.1984, +0.4017, -0.2087, -0.1526, +0.0104, -0.3145, -0.1186, -0.2420, -0.8113, -0.1924, -0.0769, +0.0629, +0.0287, -0.0093, +0.1665, +0.4061, -0.1140, -0.1501, +0.4697, -0.1004, -0.0598, -0.9584, +0.1174, +0.1803, -0.4207, +0.2724, +0.1135, -0.3000, -0.1081, -0.2234],
-[ -0.0944, +0.2341, -0.1293, -0.3682, -0.2815, +0.3922, +0.1281, -0.0364, -0.3578, +0.3765, +0.0833, -0.2770, -0.3372, -0.1390, +0.2268, -0.0754, -0.7129, +0.1079, +0.4896, -0.2936, +0.5755, +0.0711, +0.0261, +0.3214, +0.1170, -0.3148, -0.3589, -0.3999, -0.0442, +0.1939, -0.0184, -0.5482, -0.0909, -0.1102, +0.3405, -0.2403, +0.0017, -0.0908, +0.1057, +0.0563, -0.4943, -0.2383, +0.2750, +0.1475, +0.4200, -0.7400, -0.0005, -0.7109, +0.2982, -0.0624, +0.0991, -0.7474, -0.3128, +0.0312, -0.1940, +0.0893, +0.1152, -0.2274, -0.3678, -1.4362, -0.1969, -0.6162, +0.4540, +0.2569, +0.3304, -0.1393, +0.2411, -0.5043, -0.4747, -0.4624, +0.2566, +0.2622, +0.3182, -0.1998, +0.2243, +0.1218, -0.3776, -0.1689, -0.3444, -1.2030, -0.3384, +0.0376, -0.9877, +0.4066, +0.2852, -0.1160, +0.1727, -0.6990, -0.0899, -0.1878, +0.4875, -0.7249, -0.2148, -0.2262, +0.2572, +0.5794, +0.1245, +0.0084, -0.0661, +0.0022, +0.0790, -0.2628, +0.0873, +0.1133, -1.4550, -0.0061, +0.4475, -0.0445, -0.1131, -0.1322, -0.1805, -0.4632, -0.4034, -0.0477, +0.0881, -1.3645, +0.7105, -0.8035, -0.0230, -0.2352, -0.6769, -0.0870, -0.1496, -0.7174, -0.3905, +0.5053, +0.1599, +0.0774],
-[ -0.0854, -0.3404, +0.0652, +0.0362, -0.0756, +0.0192, -0.1265, +0.3489, -0.3569, -0.8240, +0.0391, -0.0941, -0.1433, +0.3441, -0.1874, -0.2676, +0.5242, +0.2251, -0.2071, -0.1848, -0.2279, -1.2238, +0.2887, +0.0095, -0.1245, -0.3161, +0.0329, -0.0625, -0.2333, +0.3116, +0.0164, -0.3283, -0.4250, +0.1686, +0.2560, -0.5164, -0.2912, -0.3383, -0.1983, +0.1373, +0.2847, +0.4067, +0.1801, -0.1141, +0.0385, -0.4291, -0.2469, +0.0845, -0.0106, -0.4852, +0.2204, -0.3597, -0.3101, +0.0629, -0.1494, -0.0957, -0.2842, -0.2712, -0.1635, -0.3056, -0.0953, -0.7983, -0.2230, +0.1603, +0.1263, +0.0316, +0.1262, +0.0299, +0.2142, -0.1661, -0.1874, -0.2247, -0.1495, +0.4345, -0.0050, -0.0023, -1.0454, -0.1850, +0.0324, -0.1299, +0.0808, +0.2819, -0.3591, -0.0671, +0.3848, +0.0527, +0.0870, +0.2097, -0.7340, -0.0364, +0.1416, -0.7251, +0.3899, -0.0321, +0.2230, +0.2796, +0.3449, -0.1251, +0.1570, +0.2467, +0.0966, +0.1106, -0.0601, +0.2364, -0.1023, +0.1761, -0.3835, +0.3161, +0.1496, +0.0713, +0.3664, -0.1054, -0.8298, -0.0852, -0.6931, -0.3448, -0.0491, +0.0825, -0.1888, +0.0303, -0.1669, -0.2420, +0.1384, -0.1588, -0.0640, +0.0044, +0.0920, +0.5491],
-[ -0.2530, -0.0550, +0.1767, -0.0197, +0.0392, +0.1533, -0.1908, +0.2095, -0.4558, -0.3182, -0.1207, +0.1121, +0.1108, +0.0632, +0.0251, +0.0800, -0.1490, -0.5128, +0.3625, +0.2499, -0.2294, +0.1496, -0.0599, +0.3519, -1.1459, +0.4171, -0.4250, -0.8933, -0.3909, -0.2782, +0.1234, +0.1028, +0.1640, -0.3572, -0.8056, -0.0328, +0.0441, -0.2858, +0.4340, +0.3755, -0.1979, +0.2009, -0.4347, -0.0842, -0.6567, -0.5243, -0.0483, +0.1214, -0.2512, +0.3272, -1.3854, +0.1747, -0.4386, +0.1441, -0.3902, -0.4389, +0.0880, -1.0031, -1.5420, -0.2146, -0.2588, -0.7700, -0.1053, -0.4492, -1.1340, -0.3955, -0.0062, +0.1858, -0.4721, +0.5749, -0.7658, -0.4602, -0.0370, -0.1331, +0.1250, -0.4708, +0.0186, -0.0472, +0.6910, -0.1052, -1.0263, +0.3958, +0.1160, -0.0658, -0.0263, +0.1706, -0.1598, +0.3593, -0.7746, -0.1430, -0.2939, -0.5315, +0.1469, +0.0629, -0.2287, -0.0982, -0.9673, +0.3858, -0.1839, -0.3926, +0.1103, +0.5221, -0.2097, -0.0538, -0.3374, -0.2589, -0.1362, -0.8023, +0.5058, -0.1019, -0.1020, -0.2040, +0.2014, -0.2802, -0.0912, +0.0152, -0.6996, +0.2708, -0.5717, -0.3458, +0.1621, -0.1512, +0.2791, -0.0776, -0.1128, +0.0089, +0.1515, +0.5123],
-[ -0.4655, -0.0379, +0.0643, +0.1431, -0.0937, +0.1572, +0.2089, +0.0227, +0.4811, +0.2738, -0.4770, -0.0302, -0.2714, -0.0353, -0.4082, +0.4073, -0.2526, +0.0575, -0.2309, +0.4160, -0.2468, +0.2285, -1.0454, -0.3023, +0.0094, -0.0101, +0.3390, +0.0338, -0.0278, +0.1941, -0.0570, +0.2868, +0.0429, -0.8105, -0.0188, -0.1246, +0.0159, -0.4999, -0.2032, +0.0914, +0.6455, -0.1245, +0.0020, +0.0418, -0.6123, +0.0697, +0.1981, -0.4423, -0.1076, +0.2690, +0.1470, +0.3055, -0.1343, -0.0624, +0.2082, -0.1393, +0.0894, +0.2845, +0.2606, +0.3553, -0.0025, +0.4361, +0.6263, -0.0265, -0.0731, +0.2340, -0.1738, +0.1374, -0.0836, -0.0444, -0.7722, -0.3558, -0.3378, -0.5021, +0.1452, +0.1734, -0.0282, -0.3774, +0.1987, +0.1507, +0.0245, -0.0719, -0.0083, +0.2448, -0.1184, +0.1152, -0.6909, +0.1571, -0.6083, +0.0978, -0.2012, +0.3425, -0.0069, +0.2474, -0.5482, +0.0814, -0.1556, -0.1506, +0.1668, +0.2776, +0.3391, +0.2342, -0.2065, +0.0879, -0.6159, +0.2643, -0.2567, -0.2676, +0.2018, -0.4286, -0.4639, -0.4193, +0.1816, +0.2604, -0.0906, +0.0827, -0.0005, +0.2018, -0.3132, -0.3025, +0.1614, -0.1068, +0.0919, +0.2894, -0.3590, -0.3032, -0.4354, +0.0154],
-[ -0.0429, -0.3707, -0.3739, +0.3704, -0.0150, +0.2189, -0.4955, -0.7602, -0.6327, +0.1189, +0.3060, -0.5486, +0.1754, -0.5086, -0.4190, -0.6469, +0.0826, -0.0344, +0.1115, -0.4931, +0.2178, -0.6064, -0.0868, +0.2074, -0.1581, +0.4950, -0.4560, +0.1868, -0.2302, -1.1003, -0.9498, -0.3075, -0.1099, -0.7696, +0.2225, +0.3048, +0.0237, +0.1738, -0.1000, -0.0539, +0.2746, -0.6315, -0.7834, +0.5839, -0.7714, -0.1029, -0.3709, -0.2092, +0.5387, +0.0590, +0.3252, -0.1812, -0.0796, +0.0109, +0.1797, -0.1807, -0.6953, +0.0922, +0.2157, -0.0296, +0.0137, +0.0309, -0.0322, +0.1320, -1.3996, -0.5238, +0.0258, +0.1411, -0.3324, -0.0493, -0.8150, -0.2201, -0.6262, -0.1943, -0.2466, -0.3587, -0.5532, +0.3025, -0.9596, +0.2320, +0.0081, -0.3283, +0.0479, -0.5118, -0.1686, +0.5102, -0.2949, +0.2405, -0.0371, +0.3475, -0.2653, -0.1511, -0.3839, -0.0687, +0.0342, -0.5996, -0.4391, -0.5633, +0.3001, -0.8634, +0.0928, +0.1859, +0.1312, -1.4476, +0.4269, +0.6876, -0.3687, +0.0898, -0.2377, -0.3089, +0.2988, -0.4810, -0.0220, -0.2208, -0.3043, -0.2693, -0.5514, -0.1327, +0.0981, +0.1090, +0.0979, +0.0774, +0.1311, -0.0520, +0.5947, +0.1165, +0.0255, +0.0646],
-[ -0.4015, -0.7856, -0.0138, +0.2379, +0.4219, -0.0133, -0.1120, -0.0367, +0.1862, -0.5656, -0.0802, +0.3317, -0.1842, +0.0494, -0.0962, +0.1796, +0.3449, +0.3633, -0.5248, +0.3595, -0.6307, -0.1464, -0.2156, -0.1198, +0.6068, -2.0541, +0.0744, +0.1036, -0.4800, -0.9317, +0.3650, +0.0608, +0.2096, +0.0011, -0.1670, +0.2135, +0.5401, -0.6114, -1.1094, -0.1530, -1.1694, -0.0469, -0.0043, -0.3584, -0.0760, -0.4375, -0.3118, +0.2781, -0.8857, -0.1821, -0.2038, +0.5715, -0.3865, -0.4510, +0.4034, -0.0904, -0.0075, -0.1263, -0.3763, -0.6469, +0.0981, +0.2835, -1.0551, -0.2261, -0.1222, +0.0047, +0.5585, -0.3472, -0.2015, -0.7965, -0.1860, -0.5664, -0.2167, -0.2244, -0.2145, +0.3671, -0.6399, -0.0906, +0.2896, -0.0949, -0.7272, -0.1690, -0.8668, +0.1197, +0.2210, -0.1381, -0.0362, -0.2772, +0.3834, +0.4729, +0.1046, -0.8879, +0.2266, -0.0665, +0.2083, +0.1939, +0.3427, -0.0931, +0.0226, -0.2263, +0.1235, +0.4096, +0.0778, +0.4601, -0.1834, -0.1526, +0.3648, +0.2721, +0.1836, +0.1039, +0.1252, -0.0670, -0.4777, +0.4181, +0.0461, -1.0144, -0.2770, -0.2780, +0.4376, +0.2788, -0.7011, -0.3962, -0.4795, -0.2742, -0.9814, -0.0447, -0.0447, -0.4444],
-[ +0.3501, +0.3281, -0.1430, +0.3228, -0.0807, +0.2136, -0.0195, -0.1002, -0.2381, +0.4731, -0.0458, +0.0137, +0.2722, +0.0900, -0.0668, +0.0659, -0.3536, +0.1688, -0.2339, -0.1300, -0.2204, +0.1206, -0.0453, -0.2130, -0.0140, +0.0041, -0.2013, -1.2579, +0.0436, -0.2726, -0.2897, -0.5455, +0.1721, -0.4969, -0.3442, +0.2220, +0.0569, -0.1374, -0.4693, -0.5210, -0.7792, -0.1477, -0.1435, -0.1889, +0.1739, -0.1954, +0.1126, +0.1769, -0.0294, -0.2095, -0.4485, -0.1938, +0.3559, -0.1803, +0.1457, -0.3859, +0.2793, -0.7072, +0.2029, -0.0043, -0.1302, -0.4323, -0.1481, +0.0405, +0.1824, +0.2051, +0.2035, -0.2542, -0.0847, +0.0311, +0.0031, -0.1944, +0.0411, -0.1625, -0.2449, -0.0437, +0.1181, +0.1734, +0.1622, +0.2482, -1.3020, -0.2676, -0.1668, -0.4255, -0.3623, +0.0653, -0.2027, +0.2574, +0.3004, +0.0192, +0.0700, +0.2328, -1.2587, -0.2362, -0.3811, +0.0033, +0.3652, -0.2675, -0.1837, -0.1855, -0.0299, +0.1968, -0.2170, -0.0384, -0.2551, +0.0783, +0.0645, +0.0703, -0.0835, +0.1902, -0.4658, +0.5849, -0.0440, -0.6254, +0.4145, +0.0154, -0.0337, -0.2226, -0.0193, -0.3050, -0.2739, +0.0791, -0.0331, -0.2853, -0.3587, -0.0245, +0.3906, -0.1312],
-[ -0.3729, -0.3580, +0.1994, +0.3125, -0.1575, +0.0351, +0.1712, +0.0479, -0.5090, -0.1524, -0.0229, -0.3794, -0.2660, -0.2205, -0.3291, +0.5219, -0.3152, -0.3720, +0.0702, -0.4275, +0.0918, +0.0985, +0.2214, +0.2948, +0.0067, +0.1727, +0.3573, -0.0733, -0.3958, -0.5830, -0.0946, -0.2411, +0.1241, -0.5995, +0.1575, +0.2158, -0.5639, -0.1019, -0.1161, -0.0025, +0.3288, -0.3254, +0.0209, +0.2869, +0.0349, -0.0032, +0.2493, -0.1807, +0.2012, +0.0285, -0.9862, -0.3932, +0.0355, -0.6267, -0.2420, -1.1322, +0.3270, -0.4070, +0.0856, +0.1377, -0.4038, -0.2331, -0.0207, -0.5493, -0.2026, -0.7153, +0.1385, +0.1107, +0.0477, +0.0602, -0.3468, -0.0456, -0.3055, -0.5692, +0.0869, +0.0364, +0.2018, +0.0797, +0.2311, +0.4669, -0.2796, -0.5679, +0.0042, +0.0015, -0.0524, -0.2371, -0.3690, -0.3491, +0.1767, -0.2053, -0.2630, -0.6185, +0.0131, -0.2657, -0.5073, -0.2655, +0.0691, -0.0768, -0.4844, -0.6951, -0.3339, +0.3054, -0.8780, -0.0191, -0.6555, -0.3514, -0.3141, -0.3230, -0.0244, +0.0889, +0.1160, +0.3249, +0.2260, -0.1515, -0.2689, -0.3664, -0.1808, +0.0221, +0.5215, +0.0880, -0.1395, -0.5289, -0.7631, +0.0567, -0.4045, -0.2250, +0.0902, -0.3769],
-[ -0.5947, +0.2274, -0.9496, +0.3703, +0.0841, -0.1836, +0.0044, +0.0021, +0.1787, -0.0429, +0.1353, -0.4052, +0.0083, +0.1235, +0.6274, +0.2087, +0.3484, +0.1119, -0.1528, +0.0003, -0.3680, -0.5990, -0.5782, -0.0053, -0.0038, +0.2493, +0.0427, -0.1297, -0.0332, +0.0291, -0.1151, -0.0122, +0.2482, -0.1746, +0.6397, +0.1691, +0.0541, -0.1390, -0.0668, -0.1904, +0.2275, -0.0548, -0.3013, -0.3059, +0.0162, -0.3792, +0.2507, -1.5725, -0.0162, +0.4433, -0.2386, -0.3115, +0.2838, -0.2357, -0.2010, +0.3173, -0.0459, -0.0212, +0.3470, +0.1231, -0.2594, +0.0194, +0.0015, +0.5905, -0.0855, +0.0124, +0.3250, +0.0103, -0.2701, +0.0159, +0.1874, -0.0726, +0.1616, +0.0483, -0.2104, +0.0683, +0.0354, +0.0604, +0.0738, -0.6140, -0.1024, +0.1922, -0.6209, -0.4914, -0.1139, -0.3441, +0.2979, -0.0118, +0.0571, +0.2113, -0.4013, -0.2839, -0.2274, -0.1234, -0.2224, +0.5136, -0.5031, -0.2097, +0.1413, +0.4381, -0.5172, -0.2161, +0.1183, +0.1782, +0.0394, -0.9201, +0.1413, +0.1968, -0.8099, -0.2413, -0.0397, +0.0048, -0.9168, +0.0216, +0.2725, -0.6455, +0.0540, -0.1368, -0.8279, -0.2034, -0.1583, +0.2583, -0.4102, +0.2368, -0.1897, +0.0892, +0.2035, -0.6145],
-[ -0.4914, -0.0175, -0.1029, -1.1875, +0.0158, +0.1054, -0.4501, +0.1822, +0.1384, +0.0073, +0.1010, +0.2072, -0.0566, +0.0374, -0.5182, +0.2300, -0.0543, +0.0234, +0.0719, -0.3345, +0.1585, -0.2427, -0.3074, -0.5413, +0.0213, +0.2899, +0.1372, -0.2435, -0.1829, +0.5233, -0.1391, +0.0271, -0.0862, +0.1832, +0.7547, -0.0167, -0.1029, -0.4332, +0.3798, +0.0694, -0.6046, +0.2171, +0.0931, -0.4275, +0.0547, +0.1686, +0.0674, -0.3921, +0.5958, +0.2580, -0.7376, +0.4033, +0.3357, +0.5261, -0.2143, -0.2368, -0.1381, -0.7014, -0.2709, +0.3299, -0.6330, +0.0553, +0.1474, +0.5485, -0.4183, -0.5408, -0.4226, +0.1773, -0.0814, -0.0224, +0.1349, -0.1298, -0.7348, +0.1840, -0.1371, +0.2017, +0.0927, -0.2807, +0.1679, -0.3693, +0.1331, +0.1271, +0.0445, -0.1609, -0.3406, -0.5669, -0.1359, +0.3603, -0.2292, -0.1502, -0.2860, +0.3773, -0.0089, +0.2764, +0.4845, -0.1967, -0.8141, -0.0563, +0.1718, -0.0717, +0.4198, +0.0029, -0.3978, +0.2698, +0.0651, +0.2271, +0.1170, -0.3438, -0.2717, +0.6219, -0.0172, +0.2207, -0.5174, +0.1052, -0.2792, +0.1195, +0.3255, +0.2822, -0.1286, -0.6566, +0.0267, +0.3203, -0.5382, -0.0283, -0.9872, -1.0424, -1.0301, -0.0555],
-[ -0.0453, -0.2395, +0.2406, +0.0631, +0.0629, +0.0833, +0.1781, +0.3761, -0.2013, -0.5130, -0.5778, -0.0650, -0.1589, -0.3232, -0.3333, -0.8319, +0.2013, +0.2267, +0.2610, -0.5927, -0.0493, +0.2577, +0.4523, +0.1532, -0.6685, -0.0539, +0.2305, +0.2816, -0.1894, +0.1239, +0.0723, -0.3620, +0.0898, -0.0181, -0.0459, +0.1914, -0.6516, +0.1430, -0.5466, -0.3008, -0.0715, -0.6103, +0.0118, +0.0141, +0.1248, -0.1234, +0.0846, +0.2255, -0.5190, -0.2559, -0.1613, +0.4473, +0.1540, -0.5639, -0.8685, +0.1487, -0.2612, +0.3390, -0.4948, -0.0352, +0.0908, +0.1311, +0.0625, -0.1194, -0.2128, +0.0454, +0.2579, +0.3957, +0.5040, +0.1017, -0.3063, -0.4509, -0.2063, -0.2673, -0.3279, +0.0295, -0.1485, +0.2786, +0.1512, +0.1158, +0.1659, -0.1235, -0.8287, -0.2932, +0.0973, -0.0585, -0.3973, +0.2949, +0.2267, -0.1506, +0.2104, -0.1853, -0.4127, -0.8102, -0.1861, -0.2241, -0.0969, -0.1213, +0.2320, -0.8217, +0.0387, +0.1559, +0.0937, +0.0199, +0.2130, +0.5811, +0.1031, +0.0254, +0.1938, -0.1855, +0.2375, -0.6722, -0.1418, +0.6080, -0.6757, -0.2532, +0.0382, +0.2149, -0.2714, +0.3754, -0.2763, +0.0971, -0.3987, +0.5819, -0.0490, -0.6208, -0.0094, -0.0335],
-[ -0.0520, +0.1143, +0.3346, +0.3328, -0.7457, -0.4004, +0.4402, +0.1565, +0.2192, -0.7181, +0.4356, +0.0638, +0.1050, +0.3447, -0.9636, -0.2623, +0.5175, -0.0571, +0.0749, -0.2558, -0.1522, +0.1987, +0.3003, -0.0340, -0.1250, +0.1917, +0.0105, +0.1603, +0.3017, +0.1785, +0.3443, -1.5343, -0.1129, -0.3967, -0.0861, -0.1839, +0.3447, -0.0320, -0.1140, -0.7012, -0.5374, -0.1204, -0.1188, -0.9007, +0.1548, -0.1386, -0.0337, +0.6399, -0.4455, +0.0039, +0.2296, +0.0017, -0.3522, -0.4161, +0.1904, -0.4585, -0.0504, -0.4775, -0.1963, -0.0786, -0.0918, -0.0926, -0.4992, -0.4981, +0.1395, -0.0966, -0.1520, +0.1250, -0.3255, +0.1306, +0.1884, +0.2478, -0.1758, -0.0991, -0.3168, +0.2045, +0.1035, +0.1926, +0.1510, -0.9593, +0.2111, -0.5241, -0.6604, -0.0298, -0.4766, -0.1225, -0.2626, -0.2218, +0.3571, -0.8226, +0.0405, -0.8556, -0.8859, -0.3557, -0.7047, +0.2757, -0.0380, +0.1300, -0.2333, -0.4366, -0.6659, +0.1032, +0.0568, +0.0892, -0.5488, -0.5828, +0.2135, +0.5198, +0.2927, -0.1756, +0.4095, -0.5759, -0.5219, +0.0122, +0.1435, -0.3798, +0.1782, +0.0249, -0.7436, -0.4398, -1.0002, -0.4882, +0.3656, +0.4042, +0.3798, -0.3411, -0.0478, -0.4250],
-[ +0.0293, -0.1663, -0.3768, -0.2223, -0.0055, -0.3266, +0.1328, +0.2718, +0.3462, +0.0200, -0.5919, -0.0576, -0.5609, -0.3056, +0.0931, +0.3790, +0.0302, +0.0964, +0.0000, -0.1535, -0.2970, +0.7108, +0.7230, -0.1885, +0.3083, -0.2583, -0.1817, -0.2954, -0.4350, +0.2642, +0.0138, -0.2058, -0.5751, +0.2576, +0.2225, -0.3665, -0.9525, -0.1351, -0.3914, +0.0191, -0.0508, -0.6731, +0.1697, -0.3946, -0.0264, -0.0259, +0.0276, -0.5611, -0.4430, +0.2832, -0.6663, -0.0660, +0.2421, +0.0772, -0.0405, +0.2755, +0.0031, -0.6514, +0.0150, +0.3053, +0.4018, +0.5021, -0.2157, +0.1647, -0.8754, +0.1060, +0.1213, +0.0049, -0.5501, +0.3529, +0.3156, -0.1689, -0.3875, -0.1849, -0.1724, +0.1727, +0.1591, -0.0960, +0.1350, -0.5237, -0.3937, +0.0273, +0.3581, +0.1818, -0.2577, +0.4555, +0.3635, +0.4512, -0.2311, -0.1382, -0.8001, -0.4946, +0.0842, +0.3760, +0.1495, +0.6040, -0.4504, -0.4973, +0.0428, +0.0742, -0.1994, -0.0175, -0.0597, -0.2138, -0.3823, -0.1439, +0.1747, -0.8329, -0.2617, +0.2151, +0.1795, -0.4310, +0.0498, +0.0994, +0.5801, +0.2664, +0.2355, -0.6505, -0.2277, -0.4698, +0.4264, -0.0938, -0.3382, -0.3953, +0.0303, +0.4967, +0.1012, -0.1518],
-[ -0.2188, +0.1021, -0.2240, -0.4672, +0.1532, -0.3045, +0.1718, +0.1418, -0.5078, -0.3792, +0.0666, +0.0985, -0.3817, -0.1581, -0.3091, -0.4972, -0.4725, +0.1204, -0.6940, -0.1842, +0.0045, -0.9836, +0.1029, -0.1811, +0.0756, +0.0428, +0.0777, -0.3013, -0.4269, -0.0528, +0.0722, -0.0670, -0.7216, +0.1244, +0.2999, -0.0958, +0.0789, -0.1816, -0.4453, -0.6704, -0.0310, -0.2875, +0.3572, -0.0051, -0.4087, +0.0230, +0.3466, -0.1092, +0.3518, -0.3754, -0.1125, -0.1751, -0.1190, +0.0514, +0.2108, +0.0382, -0.2385, -1.1745, -0.6549, +0.1466, +0.1003, -0.1397, +0.1939, -0.1007, -0.5671, -0.2141, -0.3080, -0.3285, -0.5235, -0.5764, -0.3409, -0.5457, +0.1450, +0.2169, -0.0775, -0.3134, -0.2641, +0.0260, -0.1224, -0.2079, -1.1028, -0.0962, +0.3657, +0.2675, +0.2761, -0.1438, -0.0040, +0.3894, -0.1598, -0.9228, -0.4203, +0.3786, -0.6578, -0.2065, +0.4389, -0.6512, +0.1878, +0.1302, -0.1187, +0.0349, -0.2018, +0.2299, -0.1649, -0.5971, -0.0187, -1.1908, -0.2499, -0.4757, +0.0489, -0.0761, +0.6595, +0.0984, -0.2936, -0.1527, +0.3843, +0.4120, +0.2702, +0.0496, -0.1293, +0.6906, +0.2244, -0.1256, -0.4838, +0.6558, -0.0440, -0.2431, -0.5317, +0.1463],
-[ +0.1007, -0.2044, +0.0915, -0.1110, +0.2309, +0.0957, +0.0353, -0.2517, -0.1242, -0.1429, -0.3406, +0.0926, +0.0606, +0.0489, +0.0082, +0.1055, -1.3637, +0.2863, -0.8374, +0.0397, -0.0966, +0.1015, +0.0416, +0.2654, -0.1580, +0.0091, +0.2479, -0.1647, +0.0940, +0.1184, -0.1846, +0.2333, -0.1408, -0.0981, +0.1680, +0.0911, +0.4148, +0.2737, +0.0429, -0.3616, +0.0468, +0.2632, -0.2784, +0.4318, +0.0774, -0.4683, +0.0070, -0.0744, -0.0775, +0.0305, +0.0484, -0.1177, +0.0596, -0.1406, +0.0670, -0.0642, +0.2147, -0.3049, -0.0589, +0.2003, -0.0902, -0.1474, -0.3707, +0.1232, -0.3934, +0.1415, -0.2993, +0.0076, -0.1834, +0.0297, -0.1118, +0.1966, +0.1434, +0.0009, +0.0595, -0.2880, +0.0926, -0.3560, -0.5908, +0.2940, -0.0431, -0.0223, +0.4797, +0.1149, -0.0131, -0.0821, +0.0943, -0.2290, +0.1531, +0.2856, -0.3395, -0.1174, -0.5446, +0.0501, -0.0462, -0.1134, -0.1696, +0.0725, -0.0470, -0.0893, +0.0332, -0.0180, +0.5846, -0.2333, +0.1019, -0.0331, +0.0771, +0.2611, -0.1336, -0.1301, -0.9212, -0.3052, +0.0114, +0.0305, -0.2702, -0.1209, +0.2616, +0.4937, -0.0724, +0.2716, -0.0188, +0.2153, +0.3038, +0.1207, +0.1832, -0.1724, +0.2292, +0.2457],
-[ -0.1804, -0.6413, -0.0744, +0.1991, -0.0737, -0.2933, +0.1017, -0.1491, +0.4600, +0.2833, -0.2731, -0.1631, -0.5416, -0.4341, -0.2894, -0.1315, -0.2177, +0.0498, -0.0359, +0.4271, -0.1389, -0.0952, -0.0668, -0.2945, +0.0423, -0.4391, +0.1829, -0.0940, +0.2085, +0.4466, -0.0549, -0.4789, +0.1381, +0.3271, -0.1952, -0.5656, -0.4272, -0.6747, -0.1363, -0.4104, +0.3835, +0.1417, +0.3708, +0.0614, -1.0061, -0.3433, +0.5277, -0.0979, +0.2403, -0.3140, -0.1091, -0.0942, -0.7187, -0.1379, -0.0743, -0.0831, -0.0651, -1.4077, -0.2030, +0.4326, +0.1291, +0.0197, +0.0664, +0.0799, -0.0921, -0.1370, -0.4199, +0.2537, -0.1733, -0.5453, -0.3406, +0.2641, -0.2840, -0.2217, -0.1717, -0.2596, -0.6149, +0.2036, -0.1179, -0.4542, -0.2821, -0.0771, -0.3978, -0.0618, -0.0831, -0.2506, -0.1301, +0.0824, -0.5279, -0.0014, -0.0490, -0.5102, -0.3509, -0.0945, +0.3115, +0.4273, -0.6854, -0.7175, -0.3040, +0.1343, -0.3622, -0.2034, +0.4940, -0.5965, +0.0041, -0.6200, +0.0382, +0.2886, -0.6852, +0.1837, -0.1224, -0.3253, -0.2527, -0.8300, -0.0729, +0.0226, -0.4047, +0.1606, +0.2364, -0.4973, -0.6442, +0.1035, +0.3565, +0.0052, +0.3142, +0.3418, +0.0403, -0.5119],
-[ -0.1017, -0.0053, +0.0267, -1.0741, -0.1520, -0.1370, -0.3307, -0.0732, -0.4366, -0.7079, -0.2262, -0.2293, -0.1644, +0.1885, +0.6407, -0.2647, +0.0997, +0.1705, +0.3492, -0.1606, -0.0041, -1.6792, +0.0112, -0.0425, -0.4714, -0.0951, +0.1999, +0.1248, +0.2741, +0.2132, +0.3065, +0.2279, -0.1889, +0.0610, -0.3630, +0.1476, -0.0402, -0.1753, -0.7225, -0.0120, +0.0444, +0.1587, +0.1624, -0.3233, +0.0357, +0.1818, +0.2471, -0.5049, -0.9300, -0.1819, -0.0472, -0.1533, +0.2635, +0.2933, -0.1783, -0.2531, -0.1683, -0.0108, +0.0977, +0.2713, -0.0255, -0.2324, +0.1616, -0.3653, -0.1300, -0.0267, -0.0338, +0.1684, +0.0473, -0.0590, -0.1669, +0.0260, -0.2941, +0.1953, -0.7179, -0.1900, +0.1382, +0.3187, +0.1247, -0.5942, -0.5205, -0.0947, -0.0335, -0.0588, -0.0189, +0.3053, -0.0854, -0.3207, +0.1741, +0.0546, +0.0115, -0.2876, +0.1458, +0.3574, -0.2910, +0.0976, +0.1731, -0.0817, -0.0826, +0.2886, -0.1298, +0.2386, +0.2121, -0.1873, +0.3193, +0.3598, +0.3700, -0.4408, +0.0477, -0.2259, -0.8351, -0.3033, -0.1020, -0.3804, -0.0147, -0.0782, -0.0253, +0.2604, +0.0669, -0.0886, -0.2918, +0.0786, -0.0955, +0.1704, -0.2301, -1.1527, -0.0295, +0.4580],
-[ -0.6923, -0.0835, -0.2932, +0.1860, -0.0988, +0.0671, +0.0189, +0.2117, +0.1516, +0.1037, -0.1780, +0.5206, -0.2900, -0.4395, +0.0723, -0.1160, +0.1709, -0.1442, +0.3346, -0.7235, -0.4740, +0.0875, -0.0777, -0.1537, +0.4708, +0.3247, +0.1284, -0.2747, +0.4688, +0.1906, -0.5578, -0.2271, -0.6142, -0.2636, -0.1089, -0.4988, -0.1197, -0.1757, +0.0829, -0.0075, +0.2441, -0.6189, -0.1981, +0.1928, +0.1158, -0.3283, -0.5588, +0.0071, +0.6097, +0.3238, -0.3600, +0.4527, -0.0510, +0.7691, -0.5023, -0.2895, +0.2136, +0.1607, +0.3858, -0.0098, +0.3589, -0.1146, -0.0712, -0.0400, -0.1925, -0.4676, +0.2759, +0.1378, -0.4339, -0.5202, -0.4195, +0.0838, -0.2441, -0.3500, +0.0759, -1.0871, -0.1415, -0.2753, -1.1007, -0.0186, +0.1863, -0.5634, +0.0043, +0.1119, +0.2769, -0.1073, -0.2010, +0.4234, -1.3143, +0.3216, +0.1197, -0.0692, -0.4731, -0.6585, +0.1252, +0.1992, -0.2571, +0.1463, -1.2326, +0.1175, +0.0214, -0.3330, -0.2817, -0.4959, -0.0610, -0.0143, -0.7349, +0.2925, -0.2817, -0.2231, +0.1759, -0.9774, +0.2390, -0.1225, -0.9171, -0.1901, -0.7895, -0.4615, +0.0353, -0.5406, -0.4352, +0.3894, +0.1673, -0.5319, -0.4118, -0.2283, -0.5668, +0.2083],
-[ -0.2980, -0.3592, -0.0770, -0.3542, +0.1863, +0.2256, -0.1919, -0.1789, -0.4016, +0.1436, -0.2752, +0.0135, +0.2265, -0.3872, +0.0598, +0.0476, -0.2551, -0.1743, -0.7473, -0.2520, -0.2357, -0.3911, +0.0377, +0.1986, -0.0369, -0.3049, +0.1196, +0.2373, +0.1458, +0.2655, +0.1632, -0.1340, -0.2975, +0.4237, +0.2112, +0.4525, -0.0604, -0.0543, -0.4549, +0.0763, -0.6850, -0.4227, -0.7335, -0.1524, -0.2647, -0.1532, +0.3511, -0.2706, +0.1650, -0.4522, -0.0460, +0.6378, -0.1204, +0.0676, -0.0465, -0.0767, +0.2404, -0.8729, +0.2271, +0.4106, -0.1021, +0.0290, -0.5288, -0.1131, -0.3274, +0.0984, -0.4574, +0.5551, -0.1834, +0.0660, -0.1157, +0.1353, -0.2033, -0.3010, +0.5301, +0.0713, -0.2118, -0.1965, +0.0318, +0.5520, -1.3944, +0.3160, -0.5554, -0.3506, +0.0334, +0.1534, +0.1675, -0.2854, +0.1113, -0.2012, +0.3805, -0.0233, -0.2185, +0.1111, +0.0239, -0.4577, +0.1438, +0.1930, -0.1968, +0.1310, +0.6313, -0.3919, -0.4534, +0.2406, -0.5656, +0.1666, +0.0888, +0.0411, +0.0157, +0.3176, -0.1931, +0.2688, -0.3309, +0.0924, -0.0175, +0.3059, +0.0998, -0.1257, +0.2527, -0.5143, +0.0128, +0.0456, -0.3505, -0.3927, -0.0699, -0.4737, -0.5614, -0.4470],
-[ -0.4806, +0.3155, +0.0923, -0.0874, -0.3705, +0.0612, +0.2649, -0.5107, -0.7034, +0.1830, -0.2687, -0.0724, -0.0851, -1.4003, +0.0659, -0.5941, +0.1984, +0.1414, -0.1043, +0.0107, -0.6484, -0.0740, +0.2101, +0.0407, -0.2219, +0.0094, -0.1241, -0.3421, -0.0127, -0.1056, +0.2103, +0.2309, -0.2926, -0.7421, -0.5438, +0.0586, +0.0710, +0.3101, -0.6930, +0.0095, -0.5734, +0.1109, -0.3719, +0.1490, +0.1394, -1.1226, -0.0579, +0.3137, -0.1024, +0.3899, +0.0721, -0.4998, +0.0433, +0.3800, +0.2369, +0.2631, -0.4126, +0.4422, -0.0038, +0.1540, -0.2970, +0.2507, +0.0484, -0.0013, -0.1378, +0.3255, -0.6364, +0.1867, +0.3550, +0.1193, -0.1194, -0.5268, -0.0703, +0.0644, -0.1363, +0.0177, +0.0322, +0.2742, +0.0973, -0.1359, -1.5205, +0.3452, +0.1356, -0.0290, -0.1225, -0.5191, -0.1403, -0.1737, -0.3189, +0.1529, +0.1788, +0.5082, -0.2529, -0.1178, +0.1159, -0.2308, +0.0791, +0.0944, +0.2157, -0.1984, -0.6510, -0.2869, -0.0004, +0.2280, +0.0338, +0.1443, -0.5017, +0.3413, -0.0812, -0.3725, -0.0953, -0.1753, -0.6761, -0.7394, -0.2595, -0.5947, -0.1616, -0.1802, +0.1509, -0.3197, -0.0278, +0.2917, +0.2329, -0.0423, +0.1683, -0.2103, +0.1495, +0.0141],
-[ -0.0667, -0.0992, -0.1614, +0.0497, +0.1847, +0.0645, +0.1867, +0.1900, +0.0920, -0.4507, +0.0406, -0.5628, +0.1646, +0.0726, -0.0777, -0.0642, -0.7265, +0.1354, +0.2330, -0.3079, +0.1769, -0.1255, +0.2995, -0.1625, -0.6023, -0.1636, +0.2149, +0.0838, +0.1872, -0.0040, -0.2513, +0.1646, +0.4241, +0.3852, -0.2071, +0.2552, +0.5452, +0.2415, +0.1584, -0.3388, +0.0944, -0.0345, +0.1485, -0.2260, +0.1944, -0.3549, -0.0954, -0.3895, +0.0756, -0.1107, +0.3953, -0.2296, -0.6125, +0.2883, +0.5243, -0.1802, +0.1412, +0.0637, +0.2653, +0.1138, +0.0330, -0.8522, -0.4973, -0.1516, -0.1257, +0.0568, -0.1561, -0.9619, -0.3596, +0.0625, +0.0618, -0.3619, +0.0190, -0.0134, +0.0080, -0.1078, +0.5391, +0.0050, +0.0016, -0.2223, -0.0290, -0.2086, +0.1544, -0.4426, +0.2384, -1.1034, -0.0437, +0.1262, +0.2907, +0.1822, +0.2386, -0.3384, -0.0796, -0.0364, -0.2243, -0.3665, +0.2532, -0.0050, -0.5482, -0.1726, -0.0011, +0.2308, -0.1187, +0.4308, +0.3380, -0.5357, -0.3053, -0.1135, -0.4833, +0.2517, -0.3469, -0.1541, +0.2791, -0.6348, +0.3385, +0.0960, +0.0710, -0.0633, -0.0994, +0.3203, -0.7650, -0.3229, -0.2339, -0.1777, +0.1286, +0.3831, +0.2287, +0.2214],
-[ -0.2278, +0.0599, +0.1749, +0.0846, +0.2653, -0.2085, +0.2674, +0.0839, +0.1695, +0.0025, +0.1746, -0.6353, -1.5946, -0.0767, +0.1051, -1.0178, -0.4124, -0.8966, -0.4066, -0.4909, +0.1857, -0.3586, -0.0416, -0.0515, -0.5398, -0.4615, +0.0544, -0.2038, -0.6872, -0.1224, +0.1132, -0.0118, +0.5187, -0.3769, -0.3153, -0.6752, -0.0928, +0.5779, -0.3849, -0.2489, -0.2858, +0.0034, -1.1811, -0.5856, +0.0593, -0.7577, -0.4646, -0.0720, -0.0858, -0.6801, -0.3070, -0.2493, -0.3826, +0.1238, +0.0142, +0.1338, -0.2912, +0.1265, +0.1413, -0.0790, -0.4042, -0.1121, +0.0566, -0.5050, -0.1847, -0.0788, -0.7086, +0.4693, +0.0922, -0.5241, +0.0480, -0.6937, -0.3177, +0.3113, -0.2466, -0.0568, -0.3864, +0.0785, +0.1268, +0.3052, -0.4641, +0.0233, +0.3174, +0.4796, +0.2136, +0.2071, -0.3378, +0.1770, -0.3073, -0.4837, +0.0268, +0.3070, -0.7598, +0.1185, -0.9079, -0.0655, -0.8789, +0.1163, +0.0533, -0.4104, -1.1246, +0.3531, -0.2305, -0.0769, +0.2587, -0.2744, -0.1765, +0.1128, -0.3661, -0.2759, -0.3635, -0.0870, +0.2840, -0.1848, -0.7447, -0.1136, -0.5474, +0.1823, +0.3944, -0.8700, +0.2521, +0.2599, -0.1910, -0.1516, -0.0022, +0.1349, +0.0809, -0.0219],
-[ +0.1997, -0.1686, +0.1633, +0.3972, -0.2555, -0.4707, +0.0986, +0.2124, +0.2609, -0.0477, +0.0647, +0.2468, -0.4802, +0.2162, +0.1008, -0.3933, -0.7887, +0.1305, -0.3189, +0.1509, +0.1744, +0.0297, +0.1503, +0.3479, +0.4152, -0.0781, -0.1543, -0.3510, -0.4484, +0.2827, -0.3342, +0.2767, -0.1857, -0.0755, +0.0698, -0.0198, +0.3059, +0.1141, -0.1964, +0.0740, +0.1471, +0.0524, +0.3166, +0.4728, +0.2753, -0.2491, -0.3577, -0.0727, +0.1008, +0.2395, +0.1954, -0.2640, +0.1138, +0.2663, -0.0429, -0.1869, -0.1945, +0.2696, -0.0298, -0.4269, +0.1007, -0.0709, +0.1780, -0.0386, +0.1516, -0.2490, +0.0642, -0.1984, +0.1382, +0.2252, +0.2989, -0.0884, +0.5567, -0.1373, -0.0234, -0.1539, +0.2249, +0.0235, +0.0363, -0.0671, +0.5934, -0.3499, -0.4031, -0.0343, +0.0282, +0.2338, -0.1531, -0.0376, -0.3333, -0.0082, +0.3619, +0.0112, -0.2805, +0.1392, -0.2005, -0.4171, -0.0823, -0.1410, -0.0805, -0.1926, +0.4222, -0.0171, +0.5127, +0.2822, +0.2713, -0.5033, +0.1302, -0.1223, -0.2492, +0.0080, +0.3015, +0.2210, -0.1282, -0.2839, -0.2694, +0.0342, +0.0786, -0.0651, +0.4300, -0.3366, +0.1258, +0.0659, +0.1648, -0.3529, -0.1900, -0.0573, -0.1043, +0.3084],
-[ -0.3196, -0.3881, -0.2989, +0.0906, -0.1275, -0.0363, +0.1150, -0.0005, -0.3683, +0.2742, -0.0017, +0.0236, -0.4375, +0.2102, +0.3765, -0.4295, -0.1413, -0.1046, -0.4363, -0.2343, -1.3066, -1.2125, +0.2322, +0.0435, -0.2443, +0.2904, +0.3639, +0.0835, -0.0235, +0.1044, +0.0270, -0.2595, -0.1545, +0.4291, -0.6825, -0.1580, -0.3518, -0.4174, -0.3360, +0.1452, -0.3446, -0.0335, -0.2831, -0.0344, +0.0732, +0.0012, -0.7452, -0.2454, +0.0288, +0.0435, +0.2431, -0.1675, +0.3184, -0.0510, +0.2899, -0.5552, +0.0075, -0.7057, +0.0556, -0.1258, -0.9960, -0.9879, +0.2819, +0.0506, -0.4218, +0.0495, +0.1051, +0.0847, +0.1042, +0.1964, +0.0236, -0.4007, -0.2263, +0.1160, -0.4721, +0.0103, -0.1899, -0.0715, +0.2563, +0.4472, -0.0286, +0.0117, +0.1024, -0.0833, +0.2239, +0.0298, +0.0470, +0.0317, -0.2442, +0.1281, -0.1152, +0.2104, +0.1516, -0.3350, +0.1161, +0.0015, -0.2331, -0.1021, +0.1318, +0.0211, -0.0406, -0.3460, -0.0693, +0.3281, +0.2538, +0.0049, -1.5453, -0.5795, +0.1501, -0.0246, -0.1320, +0.1567, +0.1448, -0.5247, +0.0656, -0.1189, +0.2296, -0.2399, +0.1571, +0.1269, -0.2336, -0.2560, -0.2979, -0.0549, +0.2824, -0.0339, -0.4543, +0.0071],
-[ +0.2987, -0.2200, +0.0036, -0.7426, -0.0864, +0.0387, -0.2558, -0.3795, -0.2955, -0.2933, +0.2701, +0.1779, -0.0576, -0.4442, +0.1014, -0.1645, -0.1616, +0.0985, +0.4104, +0.5039, -0.1322, -0.2139, +0.2462, -0.3159, -0.2811, -0.2837, +0.4436, +0.3231, +0.1408, +0.1549, +0.1745, +0.1944, -0.2509, +0.4857, -0.9717, +0.0911, -0.1165, -0.1745, -0.2154, +0.5759, -0.3839, +0.4048, +0.1516, -0.1299, -0.2511, +0.1025, +0.0566, -0.2283, -0.3304, -0.2317, +0.4664, +0.1280, -0.2645, -0.3396, +0.2112, +0.1603, +0.3225, +0.3721, +0.3877, +0.2450, -0.0419, +0.0659, -0.3701, -0.7026, -0.3082, +0.0884, +0.1561, +0.3241, -0.1554, -0.3413, -0.1884, -0.9844, -0.5072, -0.0303, +0.1457, +0.3460, -0.5375, -0.2408, -0.1810, -0.5850, +0.0492, +0.1837, -0.1011, +0.4130, +0.0559, -0.0881, +0.3454, +0.2754, -0.7812, +0.1154, -0.3114, -0.2542, +0.0460, -0.0661, +0.1960, +0.1341, -0.1157, +0.1198, -0.2963, -0.3547, +0.3525, -0.3400, -0.1312, +0.0590, -0.0392, +0.4954, +0.0648, +0.3201, -0.2454, -0.2929, +0.0651, +0.5381, -0.3279, +0.2092, -0.1961, -0.1749, -0.5174, -0.1017, -0.1551, +0.1715, -0.0994, +0.1894, +0.0272, +0.2676, +0.1321, -0.0582, -0.1677, +0.2883],
-[ -0.0146, -0.0709, -0.0518, -0.0176, -0.2959, -0.1746, -0.0633, +0.6862, +0.2387, +0.0482, -0.2509, +0.1436, +0.1807, -0.3079, +0.0494, -0.3246, +0.3055, -0.0408, +0.0555, -0.3382, -0.0025, -0.6834, +0.3476, -0.0030, +0.1579, +0.0862, -0.1791, +0.2797, -0.1817, -0.5095, +0.1178, -0.0809, +0.0146, +0.0715, +0.2182, +0.1804, -0.0511, +0.2319, +0.3272, +0.1131, -0.8983, -0.2011, +0.1689, +0.1074, -0.2583, +0.1779, -0.3014, -0.6327, -0.6665, -0.1555, -0.4645, +0.3818, -0.1123, -0.0006, +0.0179, -0.2749, -0.2487, +0.2292, -0.4893, +0.0555, +0.0468, -0.6136, +0.5404, +0.0466, +0.4146, +0.1579, -0.2530, -0.1750, +0.1629, +0.3238, +0.5659, -0.0503, +0.0016, +0.2809, +0.2784, +0.1475, -0.6414, +0.0670, +0.2265, -0.1811, -0.3040, -0.0546, -0.2173, -0.2576, +0.0802, +0.2631, +0.0972, -0.4235, -0.2117, +0.1895, -0.0280, -0.5000, +0.0190, -0.4688, -0.1146, -0.1668, -0.3957, -0.4922, -0.4706, +0.0001, +0.0590, +0.2283, +0.2287, +0.1000, +0.0845, -0.0947, -0.0734, +0.0261, -0.6553, +0.0896, +0.2446, -0.0348, +0.0433, +0.4232, -0.0218, -0.3960, -0.5046, -0.2987, +0.0280, +0.1634, +0.2381, +0.3501, -0.3088, -0.1006, -0.1233, +0.2142, +0.2062, -0.1283],
-[ +0.4739, -0.1162, -0.1366, +0.3816, -0.0417, +0.1261, -0.2335, +0.3669, -0.2401, -0.9522, +0.2109, -0.0132, -0.1865, +0.4836, +0.1055, -0.2218, -0.1196, +0.0196, -0.0025, -0.1330, +0.2417, +0.1743, -0.1366, -0.0336, -0.6017, -0.1232, -0.0231, -0.5966, -0.2600, +0.2885, +0.1231, -0.4905, +0.1792, +0.3717, -0.3098, -0.1309, +0.0815, +0.2542, +0.4068, +0.0271, +0.5056, -0.1061, +0.0995, +0.1470, +0.0906, +0.0087, -0.0164, -0.0068, +0.1400, +0.0244, +0.1745, -0.5422, +0.1526, +0.2037, +0.3617, +0.0946, -0.0461, +0.3309, +0.1855, +0.1393, +0.1067, -0.1586, +0.4164, -0.3496, -0.0448, -0.1618, +0.1439, +0.1217, -0.1955, +0.1186, -0.4702, -0.0768, +0.1980, +0.0206, -0.1104, +0.1408, +0.2186, +0.2172, -0.0080, -0.5046, -0.2846, +0.2130, +0.3136, +0.1544, -0.1141, -0.2175, +0.1584, +0.3487, +0.0853, -0.3997, +0.1498, -0.7731, -0.3221, -0.1360, +0.1550, -0.3316, +0.2193, +0.1954, +0.1046, -0.4732, +0.0718, -0.0856, +0.1472, +0.1259, +0.4658, -0.9460, -0.3982, -0.2009, +0.0725, +0.0534, -0.1006, +0.1511, +0.1744, -0.0355, +0.0462, +0.0833, +0.1941, +0.2094, -0.0421, -0.3453, +0.0553, -0.3758, +0.4053, +0.1095, +0.3244, +0.2891, +0.0966, +0.1166],
-[ -0.0724, +0.1085, -0.4972, -0.0028, -0.0067, +0.0227, -0.0290, -0.2167, -0.6043, +0.0365, +0.4909, -0.1674, +0.2678, +0.0223, -0.3653, -0.0437, -0.1391, +0.0805, -0.1396, +0.2644, -0.1395, +0.0312, -0.3119, -0.0578, -0.3483, -0.0024, +0.0221, -0.0269, +0.0651, -0.4800, +0.3787, -0.7678, -0.2529, +0.1472, +0.2696, +0.0188, +0.0343, +0.1721, -0.2451, -0.1120, -0.2019, -0.2884, -0.6638, -0.1714, +0.2885, +0.2285, +0.0318, -0.3222, -0.3335, +0.2194, -0.3422, -0.4953, +0.2280, -0.5251, -0.1215, -0.6155, -0.1824, -0.5457, -0.2367, -0.3223, -0.0156, +0.1921, -0.3315, +0.0449, -0.4019, -0.2108, -0.1561, +0.4559, +0.0354, +0.1694, +0.1857, -0.1764, -0.1723, +0.2748, -0.4499, -0.2516, -0.2862, -0.7654, +0.1760, -0.3138, +0.1232, +0.1452, -0.4399, -0.4372, -0.5577, +0.4384, +0.1098, +0.2407, +0.3873, +0.2635, -0.4921, +0.0278, +0.0434, -1.1753, -0.5458, -0.7957, -0.5668, +0.1613, -0.4191, +0.1752, -0.0424, +0.0031, -0.1225, +0.3289, -0.2935, -0.1039, -0.1187, +0.0134, -0.1290, -0.0443, -0.4428, +0.1887, +0.3621, -0.5257, -0.1781, -0.4115, -0.2030, -0.0053, -0.3871, +0.1769, +0.0771, +0.1107, -0.5442, +0.1559, -0.2440, +0.0977, +0.0242, -0.3956],
-[ -0.0798, -0.1869, -0.4505, +0.2138, +0.1049, +0.3944, +0.1550, -0.0989, -0.2967, +0.0611, +0.3077, +0.1048, +0.0462, -0.2095, -0.1263, +0.3146, -0.2458, -0.2668, -0.2381, +0.0026, +0.1260, +0.4875, +0.0092, -0.0631, +0.1149, +0.0102, -0.2396, +0.0068, -0.0141, -0.3464, +0.1864, -0.2542, -0.2427, +0.2244, -0.8746, +0.2318, -0.0816, +0.0589, -0.9249, -0.0227, -0.4448, +0.0442, +0.2586, -0.0237, +0.0434, +0.3148, +0.1130, -0.1757, -0.2727, -0.0835, -0.8797, -0.1123, -0.2536, +0.0793, -0.0724, +0.0759, -0.8041, +0.0838, +0.0876, +0.2154, +0.0597, -0.4181, +0.5480, -0.0952, +0.3059, -0.1575, -0.0610, -0.1407, -0.1976, -0.1626, -0.5145, +0.4673, +0.1151, +0.2068, -0.0202, -0.5073, -0.2761, -0.0609, -0.0292, +0.2907, -0.0149, -0.2919, -0.0782, -0.0149, +0.2524, +0.0138, +0.5132, -0.0625, -0.0648, -0.1619, +0.0246, -0.4964, +0.4155, -0.1614, -0.0334, +0.2199, -0.4551, -1.1411, +0.4183, -0.5659, +0.4333, -0.1543, -0.3226, +0.1156, +0.2702, +0.1286, -0.1775, -0.1968, -0.0402, +0.4610, -1.0954, +0.0405, +0.2891, -0.0159, -0.1103, +0.1736, +0.0364, -0.3440, -0.4703, -0.0790, +0.2281, -0.0608, -0.0070, +0.1701, +0.2180, +0.2921, -0.1660, -0.0240],
-[ -0.1531, -0.0762, +0.2434, +0.2059, +0.0006, -0.0483, -0.0835, -0.1988, +0.1489, -0.3940, -0.0165, +0.2051, -0.3440, -0.4387, +0.1805, -0.0351, +0.0964, -0.2094, +0.0173, -0.1027, +0.0215, -0.5647, -0.2739, -0.1528, +0.4392, +0.0523, +0.1529, +0.0308, +0.0211, +0.1656, -0.0450, -0.1568, +0.0969, +0.1154, -0.3587, +0.2964, -0.0999, -0.3697, +0.1148, -0.0733, -0.5812, +0.1674, +0.0484, +0.2600, -0.0143, +0.0457, -0.0709, -0.0018, +0.0157, -0.0339, -0.2562, -0.0362, -0.8209, -0.1456, -0.2533, +0.1077, -0.0559, -0.4240, -0.0907, -0.3365, -1.1521, -0.1654, -0.1469, -0.3055, -0.2623, +0.2880, +0.1382, +0.1370, +0.2796, -0.0196, +0.4249, -1.0353, -0.1271, -0.4022, +0.0980, -0.0444, +0.1223, -0.2851, -0.2339, +0.6282, +0.2245, -0.2938, +0.1645, -0.0032, +0.2605, -0.5217, -0.1395, -0.3899, -0.1549, -0.0148, -0.3275, +0.3340, -0.0451, -0.4814, -0.8078, +0.0940, -1.2753, +0.1369, -0.2777, +0.1625, +0.1247, -0.1658, -0.3757, +0.3097, +0.1633, -0.3481, -0.1820, +0.2435, -0.3022, -0.3967, -0.5671, -0.2281, +0.0564, -0.0929, +0.0627, -0.2076, +0.1221, -0.0419, -0.0861, +0.0797, -0.0192, -0.2822, -0.1680, -0.3009, -0.3804, -0.4238, +0.0706, +0.1520],
-[ +0.0304, -0.2949, -0.1197, -0.2498, -0.1144, +0.2134, +0.0354, +0.4345, -0.1183, +0.2633, -0.0164, +0.0046, -0.2470, -0.0179, -0.0765, -1.0519, +0.4042, +0.2414, -0.3601, +0.2761, -0.2936, +0.2004, +0.0272, -0.3135, +0.5484, -0.2961, +0.1134, +0.1317, +0.2315, -0.5105, +0.2052, +0.3595, +0.1048, -0.6679, +0.3744, -0.0238, -0.3705, -0.5327, -0.4238, -0.3695, -0.3441, +0.1102, -0.2174, -0.2318, +0.3524, -0.8398, +0.3412, +0.6612, -0.2882, -0.1543, -0.4695, -0.5044, +0.0114, -0.2963, -0.1065, -0.4779, -0.0599, -0.0249, +0.2302, +0.2725, -0.2193, -0.4488, -0.0592, +0.3570, +0.3488, -0.3927, -0.8498, -0.5230, -0.2438, -0.3574, +0.1329, -0.0425, -0.1903, +0.0357, +0.0999, +0.2359, -0.0484, -0.1651, +0.0435, +0.3874, -0.1912, +0.3354, +0.0358, +0.0585, +0.1967, +0.0366, +0.0187, -0.0461, +0.0070, +0.1871, -0.5516, -0.0042, -1.0255, -0.3259, -0.0243, -0.5298, +0.2294, -0.5062, -0.1477, +0.1261, -0.0510, +0.1436, +0.0660, -0.5151, +0.2660, -0.5662, -0.1677, -0.8036, +0.2069, +0.1128, -1.1921, +0.2165, -0.2782, -0.0133, +0.3023, +0.4483, +0.3006, +0.1258, -0.3541, +0.4909, -0.5832, -0.2644, -0.5679, -0.0143, +0.4790, -0.5303, -0.0335, +0.1827],
-[ +0.1815, -0.0401, +0.5799, -0.1930, -0.1426, +0.2715, -0.2027, -0.4024, +0.1903, -0.2936, -0.1695, +0.1541, +0.0735, +0.1619, +0.2111, -0.2971, +0.1040, -0.2205, +0.0246, +0.3006, +0.0952, -0.0275, -0.0447, +0.1255, -0.0167, -0.3038, +0.0067, +0.0918, +0.4534, +0.3729, +0.2850, +0.3374, -0.4727, -0.1795, -0.1843, -0.7887, -0.1064, +0.3617, +0.4538, -0.4319, +0.5354, +0.2161, +0.0345, -0.0433, +0.3310, -0.3595, +0.2615, -0.0568, +0.0303, +0.3004, +0.0770, -0.2452, -0.6659, -0.5601, -0.2301, -0.0998, +0.0636, -0.1085, +0.1295, -0.0602, +0.0307, -0.0612, +0.1105, -0.0609, +0.1408, -0.2544, -0.6422, -0.0406, +0.2392, +0.0856, -0.2494, -0.0096, -0.0540, +0.0659, -0.1719, -0.1073, -0.2555, -0.2760, -0.4249, -0.0601, +0.2513, +0.1583, -0.1241, +0.1113, -0.5371, -0.0592, -0.3068, -0.5263, +0.1182, -0.1418, -0.6853, -0.5592, -0.8657, -0.0064, +0.1229, -0.6746, +0.0328, -0.5248, +0.0427, +0.0597, +0.0565, +0.1423, +0.0662, -0.1197, +0.0264, +0.4936, -1.0516, -0.4423, -0.1124, +0.0092, -0.2064, -0.8563, -0.3046, -0.4646, -0.0318, +0.1897, +0.3785, +0.4474, +0.1881, -0.2840, -0.1618, +0.0267, -0.0722, -0.1734, -0.2372, -1.1021, -0.7337, +0.1509],
-[ -0.6447, +0.3449, -0.9011, -0.2403, -0.0744, -0.1438, +0.2014, -0.3920, -0.2266, +0.0825, -0.3074, -0.4425, -0.0174, -0.3714, -1.7478, -0.1300, +0.1309, -0.2163, -0.6222, +0.5497, -0.1621, -0.6566, +0.0829, -0.3938, +0.2074, -0.0513, +0.2233, -0.6168, -0.0091, -0.1450, +0.3245, +0.1645, -0.2045, -0.1519, +0.8124, +0.1053, -0.2874, -0.5231, -0.2111, -0.2046, -0.3640, -1.6102, -0.0478, +0.2372, -0.3473, -0.2914, -0.2621, -0.0857, -0.4149, -0.5113, -1.0806, +0.1913, +0.0824, -0.1712, -0.3389, -0.9758, -0.2708, +0.1427, -1.3125, -0.7610, -1.1084, +0.0959, -0.3895, -0.0990, +0.2630, -0.2732, +0.5443, -0.6141, +0.0143, -0.2621, +0.5494, +0.5633, -0.0835, -1.4201, -0.0531, -0.0703, -0.5871, -0.1776, -0.6265, -0.1685, -0.5413, -1.0861, +0.2029, -0.2093, +0.5018, +0.3682, +0.0130, -0.4049, -0.2864, -0.5180, -0.3193, -0.2385, +0.1110, -0.1328, -0.9537, -0.4612, -0.8338, +0.2002, +0.5781, -0.5692, +0.0020, +0.4453, -0.5529, +0.0276, -0.3348, +0.6694, -0.0618, -0.0625, +0.1663, +0.3807, -0.7775, +0.0974, +0.1139, +0.1578, -0.4627, -0.4537, +0.2381, -0.0858, +0.0478, -0.2309, -0.3844, +0.1591, -0.2309, -0.0848, -0.4875, -0.2816, -0.1464, +0.3074],
-[ +0.0608, -0.1224, -0.6330, -0.1259, +0.4083, -0.1106, -0.0339, -0.3438, +0.4411, -0.1641, -0.0177, +0.1939, -0.3302, -0.3217, +0.1455, -0.0684, +0.0289, -0.3108, -0.3304, -0.3683, -0.4343, -0.2011, +0.0423, +0.2278, -0.4396, +0.0042, -0.4049, +0.4562, -0.2658, +0.5984, -0.1613, -0.0498, -0.1887, -0.1891, +0.2460, -0.0120, +0.3477, +0.3723, +0.1210, +0.9048, -0.6516, -0.4915, +0.5168, +0.0967, +0.0134, -0.4125, -0.1386, -0.4876, +0.0348, +0.2497, -0.2787, +0.0328, +0.2342, +0.4503, +0.4376, +0.3408, -0.2701, -0.0179, -0.3997, -0.4566, -0.6290, +0.0888, -0.0180, -0.4430, -0.2944, -0.1129, +0.1297, -0.2416, -0.1129, -0.0031, -0.1250, -0.0975, -0.3855, -0.2048, +0.3220, -0.2710, -0.3520, -0.3234, +0.0636, +0.4856, -0.1456, -0.0888, -1.0173, -0.3701, +0.0300, -0.4591, +0.1676, -0.1109, -0.0447, -0.0134, -0.1801, -0.2803, -0.5276, +0.0692, -0.3301, -0.5713, -0.4566, -0.0351, +0.3655, +0.0301, -0.3156, -0.0812, -0.3689, -0.1990, -0.3871, +0.6426, -0.0287, -0.1836, +0.3070, +0.2296, +0.0925, -0.5309, -0.2213, -0.1056, +0.2159, -0.0555, +0.5778, -0.1754, +0.2780, -0.2772, +0.0251, +0.3355, -0.2899, -0.0700, +0.1763, +0.2300, +0.1414, -0.4682],
-[ -0.2827, +0.2157, +0.1368, +0.0241, -0.1796, -0.2885, -0.3154, +0.2077, -0.0781, -0.3434, +0.1631, +0.2726, -0.0359, -0.1775, -1.2394, -0.2690, -0.5155, +0.0391, -0.0500, +0.1368, -0.0134, -0.1563, +0.1046, -0.1969, -0.2891, +0.0316, -0.2012, +0.3028, -0.0851, -0.3458, -0.7299, -0.2510, +0.4461, +0.2600, +0.3267, +0.0790, -0.1682, -0.1931, -0.0799, +0.2881, -0.5884, +0.0632, +0.3180, -0.3941, +0.1914, +0.5623, +0.3005, +0.0005, -0.0287, -0.2098, +0.0567, -0.6083, -0.5947, -0.5355, -0.4706, +0.4109, +0.1546, +0.0628, -0.5879, -0.5762, -0.4205, -0.1880, -0.6307, +0.3561, +0.3985, -0.5811, +0.3369, +0.2780, +0.0391, -0.3813, +0.0994, +0.3831, +0.1480, +0.0737, -0.2445, +0.0227, -0.0794, -0.0114, -0.5846, -0.3964, -0.0213, -0.4718, -0.8218, +0.0227, -0.1789, +0.1025, -0.2074, -0.0989, +0.4805, +0.1240, -0.2949, +0.2676, -0.0070, -0.1780, -0.1916, -0.1816, -0.3574, +0.0061, +0.1938, -0.0771, -0.1268, -0.3721, +0.0112, -0.4341, +0.0241, -0.1961, -0.0148, -0.1895, +0.2493, -0.1105, -0.0807, -0.0370, +0.4592, +0.6299, +0.1287, +0.3238, +0.1459, +0.3146, -0.0258, +0.4083, -0.1598, -0.1403, -0.4425, -0.0246, +0.1522, -0.1340, -0.0754, +0.0788],
-[ +0.1139, -0.1473, +0.0625, -0.2686, -0.1878, +0.1209, +0.1643, -0.6718, -0.2045, -0.2222, -0.8136, -0.0653, -0.2586, +0.0177, -0.6514, -0.4516, +0.0916, -0.3649, -0.2173, +0.2538, -0.5378, +0.2946, +0.3534, +0.3872, +0.1299, -0.0175, +0.3286, +0.0112, +0.1354, +0.4912, +0.4418, +0.3883, -0.0243, -0.0846, -0.3096, +0.1244, -0.4983, +0.0288, -0.8007, -0.1267, +0.0108, +0.1520, -0.2865, +0.4799, -0.3412, -0.2733, -0.4696, +0.6912, +0.0983, +0.0998, +0.2374, -0.1982, +0.2253, +0.1817, -0.2972, -1.1327, -0.0503, +0.0064, +0.3198, -0.3973, -1.0132, +0.0144, +0.1239, -0.3439, +0.3481, -0.1054, -0.1642, -0.3204, +0.2265, -0.6322, -0.6049, +0.0105, +0.2317, +0.0861, -0.5469, +0.3185, +0.3799, +0.2897, -0.1284, +0.1114, +0.0065, -0.2713, -0.1795, +0.2296, +0.2176, +0.0355, -0.1739, -0.2801, +0.1071, -0.3920, +0.1264, +0.1638, -0.6773, -0.2767, -0.4543, -0.1426, -0.0279, -0.0029, -0.2080, -0.3354, +0.3200, -0.2031, -0.0694, +0.2044, +0.1851, -0.0066, +0.3423, +0.3267, +0.2141, -0.1742, +0.3827, -0.0116, +0.2795, +0.3505, -0.6727, +0.0667, -0.1962, +0.1275, -0.3322, +0.1561, +0.2273, -0.7180, -0.4079, -0.6132, -0.8328, -0.0139, -0.0531, +0.0699],
-[ -0.2162, +0.3650, -0.0775, +0.1286, +0.2833, -0.2686, +0.2269, +0.1891, +0.5902, +0.0766, -0.5377, -0.4029, +0.3113, -1.0276, -0.5917, -0.0088, -0.0177, +0.3982, -0.8924, +0.0721, +0.0778, +0.4037, -0.1173, -0.1329, -0.2413, +0.1995, -0.2764, +0.2759, -0.0765, -0.0474, +0.4479, +0.0464, +0.0024, +0.2887, +0.2408, -0.2897, -0.5199, -0.3479, +0.0651, -0.0846, -0.5294, -0.3773, -0.3503, +0.0261, -0.0676, -0.6216, +0.3592, +0.1187, +0.1490, -0.1143, +0.1841, -0.0096, -0.5919, +0.3378, -0.8474, -0.9084, +0.0227, -0.7069, -0.0190, -0.9554, -0.5866, +0.2025, -0.2729, +0.1888, -0.4473, -0.1897, -0.1489, -0.0217, +0.1219, -0.3593, +0.0485, +0.2373, +0.2032, +0.5618, -0.2778, -0.4513, +0.1367, +0.2175, -0.0878, -0.2160, -0.0099, -0.1469, -0.2830, +0.3326, -0.3476, +0.0601, -0.2457, +0.2154, -0.4680, -0.3028, -0.0916, +0.1164, -0.0634, -0.4959, -0.2114, +0.2425, +0.0475, +0.2571, -0.0876, +0.0062, -0.4116, +0.4813, -0.1849, -0.0425, +0.0471, -0.4631, -0.7976, +0.2002, -0.1408, +0.2919, +0.0119, -0.5573, +0.3390, +0.4550, -0.3039, -0.1137, +0.2137, -0.0528, -0.6604, -0.0976, +0.3270, -0.0922, -0.2643, -0.4038, -0.3013, -0.1558, -0.1576, -0.3229],
-[ +0.1884, +0.1581, -0.1678, -0.1605, -0.0788, -0.2348, -0.2711, +0.0234, +0.1463, -0.4431, -0.4578, -0.1051, +0.1719, +0.0025, +0.2520, -0.1683, -0.5398, -0.5436, -0.5340, -0.3022, +0.0653, +0.2823, +0.3645, -0.2714, -0.0326, +0.2143, +0.1475, +0.3053, -0.4027, +0.1658, +0.2754, -0.0655, -0.5440, -0.1419, +0.0892, -0.2852, -0.4614, +0.0123, +0.2066, +0.4549, -0.3081, -0.7535, -0.2124, -0.4547, -0.3026, +0.3357, -0.6742, +0.1423, -0.3012, +0.0458, -0.9311, -0.7505, -0.1701, +0.2159, -0.1285, +0.2552, -0.4995, -0.0120, -0.1738, +0.1413, +0.0009, -0.6367, -0.2474, +0.3341, -0.3521, +0.1533, +0.2673, +0.0852, -0.2343, -0.0740, +0.1619, -0.0412, -0.1895, -0.1293, +0.0769, +0.0521, -0.1532, -0.2426, +0.1172, -1.5164, +0.0624, -0.3847, +0.1773, -0.1819, -0.6927, -0.3207, +0.1571, +0.1593, -0.1427, +0.3353, +0.5158, +0.0365, +0.0112, +0.3568, +0.1530, +0.1749, -0.7890, -0.1237, -0.3425, -0.5343, -0.1073, -0.0057, +0.4587, +0.0027, -0.0265, -0.3313, +0.0943, -0.2787, -0.3268, -0.3629, -0.1698, -0.0133, -0.0167, -0.5999, -1.1855, +0.2669, -0.1889, +0.2187, +0.3723, -0.5664, +0.0426, +0.0538, +0.6252, +0.0166, +0.2159, +0.1125, +0.4596, +0.0911]
+weights_dense1_b = np.array([
+ +0.1494, +0.0039, -0.0527, -0.0962, +0.0315, -0.1903, -0.0055, -0.0615,
+ -0.0553, -0.1921, -0.1072, -0.0451, -0.1178, -0.0108, -0.0561, -0.1273,
+ -0.1139, -0.0796, -0.0175, -0.0684, -0.0933, -0.1067, -0.1255, +0.0234,
+ -0.0703, -0.2935, -0.1144, -0.1077, -0.1229, -0.1456, -0.1558, +0.0667,
+ +0.0781, -0.0370, -0.1065, -0.0846, -0.0311, +0.0140, -0.1026, -0.1604,
+ -0.1456, -0.2161, -0.0539, -0.1573, -0.0612, -0.0970, -0.2703, -0.1411,
+ -0.2202, +0.1398, -0.0699, -0.1028, -0.0294, -0.1635, +0.1305, -0.1769,
+ +0.1233, -0.3288, +0.0167, +0.0028, -0.0550, -0.1999, +0.0864, +0.0176,
+ -0.0370, +0.0562, -0.0984, +0.0783, +0.0478, -0.1250, -0.2548, -0.1360,
+ -0.0914, -0.0499, -0.0393, +0.0658, -0.1763, -0.1398, -0.0844, -0.1208,
+ -0.0743, -0.1800, +0.0300, -0.0678, -0.0124, -0.0126, -0.0269, -0.1089,
+ -0.0306, -0.0458, -0.0984, -0.0951, -0.0395, +0.0311, -0.1592, -0.1021,
+ -0.3524, -0.1006, -0.1488, -0.2021, -0.0736, -0.1389, -0.0688, +0.0139,
+ +0.0820, -0.1823, -0.0241, -0.0035, -0.0373, +0.0326, -0.0615, +0.0254,
+ -0.0134, +0.0239, -0.1209, -0.0289, -0.1025, -0.1184, -0.1214, -0.0290,
+ -0.0975, +0.0992, -0.0952, -0.1083, -0.1422, -0.0548, -0.0305, -0.2508,
+ -0.0206, -0.2072, -0.0452, +0.0112, -0.0011, +0.0417, +0.0035, +0.0200,
+ -0.1942, -0.0485, -0.1137, +0.0025, +0.0786, +0.0299, -0.1345, +0.1579,
+ -0.0281, -0.0762, -0.0884, +0.0861, -0.0782, -0.1839, -0.0320, -0.2262,
+ +0.0617, -0.1688, -0.2112, -0.1037, -0.1056, -0.0510, -0.0038, +0.0895,
+ -0.2475, -0.0174, -0.1610, +0.0683, -0.2035, -0.0045, -0.1483, +0.0695,
+ -0.1126, -0.1221, +0.0023, -0.0862, -0.1456, -0.1136, -0.0341, +0.0209,
+ -0.0928, -0.0567, +0.0725, -0.0127, -0.0353, -0.1072, -0.0613, -0.1992,
+ +0.0168, -0.1877, -0.1331, -0.1073, -0.1444, +0.0069, +0.0563, -0.1909,
+ -0.1581, -0.0970, -0.0138, -0.0487, -0.1580, -0.1599, -0.0073, -0.2733,
+ -0.1690, -0.2064, +0.0071, -0.2040, -0.1194, -0.0529, -0.1376, -0.1651,
+ -0.0822, -0.1775, -0.1370, -0.2621, -0.1093, -0.0536, -0.0812, +0.0422,
+ +0.0078, -0.0437, -0.2098, -0.1435, +0.0691, -0.1066, -0.1223, +0.0092,
+ -0.0332, -0.0460, +0.0013, -0.0559, -0.1134, -0.1300, -0.0909, +0.0010,
+ -0.2052, -0.1058, -0.0746, +0.0049, +0.0770, -0.0889, +0.0130, -0.1252,
+ -0.2867, -0.0034, +0.0268, -0.0217, -0.0712, -0.0839, +0.0532, -0.1541,
+ +0.0243, -0.2173, +0.0914, -0.1751, -0.1907, -0.0940, -0.0697, -0.1361
])
-weights_dense2_b = np.array([ +0.1576, -0.1010, +0.0138, +0.3265, +0.2288, +0.0764, +0.0671, -0.1334, +0.1474, +0.1138, +0.0768, +0.1304, +0.2356, +0.0043, +0.0230, +0.1405, -0.0490, +0.2157, +0.1432, +0.1021, +0.0087, +0.1419, +0.0887, +0.1315, +0.1993, +0.1391, +0.2385, +0.0697, +0.1521, +0.1446, +0.1235, +0.2313, +0.1099, +0.1952, +0.1449, +0.2652, +0.0128, +0.2281, +0.1987, +0.1900, +0.0668, +0.1516, +0.0543, +0.0443, +0.1702, -0.0012, +0.1350, -0.0182, +0.1091, +0.1445, +0.1419, -0.0253, -0.0059, +0.0150, +0.1739, +0.0979, +0.1677, +0.0557, +0.1365, +0.1161, +0.2681, +0.1524, +0.1655, +0.1234, +0.1366, +0.2115, +0.1751, +0.0743, +0.1009, +0.3255, +0.0978, +0.3483, +0.3591, -0.0855, +0.2378, -0.0121, +0.2396, +0.0827, +0.1282, +0.2056, +0.2524, +0.1829, +0.0006, +0.0432, +0.1458, +0.1960, +0.2966, +0.1491, +0.0097, +0.0552, +0.1618, +0.0341, +0.1177, +0.0545, +0.2253, +0.1174, -0.0110, +0.0619, +0.0641, +0.1169, +0.1377, -0.0361, +0.3361, +0.0248, -0.0144, +0.2120, +0.2515, +0.1977, +0.1501, +0.1138, +0.1061, +0.1561, -0.0356, +0.1378, +0.1289, +0.0579, +0.1030, +0.1400, +0.1058, +0.1320, -0.0224, +0.0156, +0.0664, -0.0583, +0.1267, +0.3404, +0.2669, +0.0034])
+weights_dense2_w = np.array(
+ [[
+ -0.0446, -0.0941, -0.3955, -0.1329, +0.3261, -0.2340, +0.1304, +0.1444,
+ -0.0064, +0.4035, +0.5651, +0.2906, -0.2569, -0.1496, -0.6781, +0.3623,
+ +0.3923, -0.5059, +0.0361, -0.2793, -0.3257, -0.5450, +0.1372, -0.3239,
+ +0.1807, +0.4815, -0.5801, +0.0871, +0.0759, -0.4970, +0.1630, -0.2405,
+ +0.1363, -0.2391, -0.3084, -0.1048, -0.4797, +0.1461, -0.4725, -0.4272,
+ -0.1229, -0.3213, -0.3729, -0.2070, -0.2260, +0.0191, +0.4376, +0.2038,
+ +0.4303, -0.3538, -0.3511, -0.0173, -0.0621, +0.1285, -0.0412, -0.4655,
+ -0.5779, -0.1277, -0.0267, -0.3498, +0.1073, +0.0636, -0.7525, +0.1612,
+ +0.3821, -0.1038, -0.8780, +0.3191, +0.2394, -0.0068, +0.0812, -0.2313,
+ -0.2938, -0.3093, -0.3838, -0.0023, -0.5775, +0.4613, +0.3519, -0.1342,
+ -0.4099, +0.0764, -0.2711, -0.0370, +0.0079, +0.0552, +0.4197, -0.9073,
+ -0.2105, +0.2615, -1.1096, +0.0082, +0.4138, +0.2725, +0.0815, +0.3513,
+ -0.7101, -0.1694, -0.0091, +0.2357, -0.2003, +0.3896, -0.0686, -0.6690,
+ -0.0813, +0.2245, +0.2243, -0.3500, +0.3599, +0.0891, -0.5524, -0.1980,
+ -0.3951, +0.0085, +0.0538, +0.6534, -0.8200, +0.1080, -0.3786, +0.1675,
+ -0.0115, +0.1537, +0.4711, -0.0807, -0.1799, +0.0223, +0.2167, +0.2362
+ ],
+ [
+ -0.2444, -0.6241, -0.1147, -0.2118, +0.0857, -0.3879, +0.3546,
+ -0.0733, -1.0193, +0.1459, +0.0498, -0.2553, -0.2879, -0.5408,
+ -0.3574, +0.4237, -0.7382, -0.2695, +0.0282, -0.2548, -0.2155,
+ -0.2600, -0.1573, -0.3413, -0.6334, +0.0929, -0.0176, -0.3606,
+ +0.2845, -0.0617, -0.3122, +0.1209, -0.2462, +0.3425, +0.2171,
+ +0.5273, -0.1572, -0.1532, +0.5552, -0.0139, +0.1994, +0.0812,
+ -1.0411, +0.3236, -0.2614, -0.3478, -0.1349, +0.1892, +0.3215,
+ -0.2034, -0.0209, +0.2062, -0.3500, +0.1164, +0.1389, +0.2095,
+ +0.2791, -0.1504, +0.1044, +0.4266, -0.7286, +0.2604, -0.2693,
+ -0.1244, +0.1317, +0.3252, -0.7114, +0.5549, -0.1956, -0.1914,
+ -0.4135, -0.3006, -0.4114, +0.0110, -0.3341, -0.3824, -0.2613,
+ -0.7747, +0.5477, -0.0026, -0.2780, +0.3150, -0.3447, -0.0708,
+ -0.1666, +0.1757, +0.2413, -0.0522, -0.1630, -0.1557, +0.2338,
+ -0.4316, +0.0440, -0.3387, +0.2614, -0.2280, +0.0125, -0.0967,
+ -0.1448, +0.3245, +0.1507, -0.2703, -0.2256, -0.3510, -0.5730,
+ -0.6961, +0.3662, -0.3726, +0.3866, +0.1329, -0.7782, +0.0877,
+ -0.5175, -0.0080, -0.4061, +0.0042, -0.0629, -0.0861, +0.1035,
+ +0.3153, -0.1609, -0.0586, +0.1450, +0.0041, +0.1466, -0.6496,
+ +0.0201, +0.0129
+ ],
+ [
+ +0.1386, -0.0945, +0.2795, -0.0256, -0.0028, -0.0133, -0.4415,
+ -0.1106, +0.1377, +0.3588, -0.4300, +0.3529, +0.2544, +0.1488,
+ +0.4599, +0.3566, +0.1138, -0.4420, -0.1201, +0.1293, -0.5788,
+ -0.0978, -0.1088, +0.1153, -0.4146, +0.1100, +0.0620, +0.1854,
+ -0.7047, -0.0504, +0.2937, +0.0530, +0.0955, -0.0370, +0.0178,
+ +0.1662, -0.2216, -0.0763, -0.4237, -0.5979, +0.0670, -0.0144,
+ +0.0355, -0.5579, +0.2910, +0.2649, +0.0297, -0.4149, -0.2434,
+ -0.2470, -0.2179, +0.1319, -0.1494, +0.3073, -0.3072, -0.3915,
+ +0.3447, +0.2100, -0.4788, -0.0824, +0.2316, -0.0760, -0.2466,
+ +0.0284, -0.0477, -0.0012, -0.7704, +0.3028, -0.8417, +0.0159,
+ +0.6322, +0.0871, +0.1442, -0.0744, -0.0640, +0.3171, +0.0569,
+ -0.0746, -0.0438, -0.2017, -0.2061, +0.0221, -1.0163, -0.3438,
+ -0.0295, +0.1516, -0.2567, -0.4551, +0.1802, +0.2473, -0.3067,
+ -0.0302, -0.2944, +0.0247, +0.1530, -0.4357, -0.2943, -0.1051,
+ -0.3184, -0.0940, +0.1110, -0.2013, +0.1567, +0.4995, -0.6288,
+ +0.5756, +0.0462, -0.0036, -0.8926, -0.1855, +0.0631, -0.7486,
+ +0.0764, +0.2724, -0.3770, -0.4466, +0.1047, +0.2308, +0.1856,
+ -0.3025, -0.2538, -0.0370, -0.6129, -0.6437, +0.0648, +0.0632,
+ +0.1569, -0.5954
+ ],
+ [
+ -0.2110, -0.4682, +0.1521, -0.2096, +0.0752, -0.2327, -0.3026,
+ +0.0227, +0.1361, +0.1600, -0.0204, -0.5653, +0.3198, -0.2031,
+ -0.5835, +0.0099, -0.0005, -0.0378, +0.1420, +0.2448, -0.1970,
+ -0.6869, +0.1893, -0.3542, +0.3116, +0.1331, +0.2216, -0.0751,
+ +0.0818, -0.0981, -0.4190, +0.5141, -0.0763, +0.0360, -0.1761,
+ +0.0261, -0.5464, -0.7008, -0.2040, -0.1353, +0.2963, -0.1157,
+ +0.0362, -0.5863, -0.8737, -0.3414, +0.0769, +0.1460, -0.1560,
+ -0.0128, +0.2671, +0.3803, +0.2876, -0.1158, +0.0046, -0.1798,
+ -0.0418, -0.2737, -0.4797, -0.4231, -0.1860, -0.5159, -0.8221,
+ +0.3182, -0.7719, +0.1197, +0.1327, -0.3147, -0.1979, -0.3086,
+ +0.1928, -0.0266, -0.2050, -0.0781, +0.4301, -0.0320, +0.5265,
+ -0.2464, +0.3842, -0.1679, +0.0903, -0.0991, +0.5649, -0.2095,
+ -0.3192, +0.5082, +0.2163, -0.1517, +0.3231, -0.0450, -0.6572,
+ -0.2979, +0.5014, -0.6241, -0.1478, -0.3796, +0.0776, +0.0567,
+ -0.2926, +0.2549, -0.4551, -0.1126, -0.3430, +0.0577, -0.0678,
+ -0.6104, +0.1488, +0.0124, -0.0232, +0.1021, +0.4954, +0.0608,
+ -0.2865, -0.1660, +0.3615, +0.2145, +0.0863, -0.0482, +0.1043,
+ -0.0310, +0.1584, -0.1514, -0.2689, -0.2622, +0.2389, -0.0352,
+ +0.0505, -0.4725
+ ],
+ [
+ -0.0229, -0.4313, +0.0184, -0.8077, +0.5455, +0.2926, +0.1833,
+ -0.1669, -0.3142, -0.2872, -0.1973, +0.1569, -0.0577, +0.2992,
+ +0.0187, -0.3197, +0.1143, +0.3957, -0.0845, -0.0656, -0.6643,
+ -0.1391, -0.3222, +0.7873, +0.0598, +0.3911, +0.0200, +0.1554,
+ +0.2937, -0.4432, -0.2098, -0.5019, +0.2838, +0.1635, -0.0923,
+ -0.3384, -0.3427, +0.3220, +0.4029, -0.3257, +0.1441, -0.0432,
+ -0.3495, -0.5423, +0.2564, -0.0237, +0.4511, +0.0765, -0.0877,
+ -0.0430, +0.3376, -0.2686, +0.3190, +0.0444, -0.0437, +0.1836,
+ -0.0036, -0.1122, -0.5164, -0.0967, -0.0943, -0.0267, -0.2884,
+ +0.1110, -0.0452, -0.5358, -0.9480, -0.0428, +0.0632, +0.5967,
+ -0.5697, -0.5430, -0.3233, -0.1837, -0.3865, -0.1141, -0.3161,
+ -0.3135, -0.1826, -0.2103, +0.1367, +0.0738, -0.4706, -0.2797,
+ +0.2463, +0.0844, +0.1632, +0.2067, +0.2860, -0.1431, -0.1538,
+ -0.4689, +0.1815, -0.7608, -0.5361, +0.0924, -0.0427, +0.0261,
+ +0.1086, +0.0071, -0.0351, +0.1962, -0.5212, -0.2708, -0.0387,
+ -0.4651, -0.1066, +0.1502, -0.0507, -0.4060, +0.0178, +0.1007,
+ -0.3050, -0.3290, -0.7691, -0.2058, +0.2255, -0.4308, +0.1231,
+ +0.2162, +0.3136, +0.1682, +0.0186, -0.2181, +0.1038, -0.7105,
+ +0.0725, +0.1498
+ ],
+ [
+ +0.2957, +0.3931, +0.5196, +0.0034, -0.1459, -0.4853, +0.0045,
+ +0.3441, -0.6762, +0.3599, -0.2657, -0.0656, +0.2883, +0.2954,
+ -0.3889, +0.5849, +0.0604, +0.2256, -0.7857, +0.0923, +0.1446,
+ -0.4545, -0.0598, -0.0619, +0.0932, -0.0672, +0.1070, +0.2962,
+ +0.1364, -0.0010, +0.0422, +0.1428, -0.0486, -0.6373, -0.1726,
+ +0.1041, +0.0355, +0.1551, -0.8913, -0.6888, -0.1694, -0.7115,
+ +0.2172, -0.7797, +0.2613, -0.6847, -0.3206, -0.0662, -0.1301,
+ -0.2691, -0.3250, -0.5412, +0.3733, -0.6999, -0.1384, +0.2234,
+ -0.6276, -0.6873, -0.1056, -0.2576, -0.3469, -0.0035, -0.3412,
+ -0.4947, -0.2108, +0.2637, -0.4840, -0.7649, +0.0512, -0.5292,
+ -0.1976, -0.3880, -0.1312, -0.2244, -0.5623, +0.1554, -0.0144,
+ +0.1044, -0.3046, -0.0893, +0.0786, +0.1556, -2.0057, -0.2783,
+ +0.2209, -0.6801, +0.1200, -0.0627, -0.1416, +0.0931, -0.1593,
+ +0.6807, -0.0833, -0.3581, -0.1243, -0.2332, +0.0648, -0.2536,
+ +0.0485, -0.3385, -0.3248, -0.2046, -0.0735, +0.1252, -0.0138,
+ -0.2593, +0.3831, -0.2624, -0.0680, +0.1553, -0.6539, -0.3949,
+ -0.2072, -0.3056, +0.0470, -0.2456, -0.2607, -0.1460, +0.1578,
+ -0.4485, -0.1730, +0.0905, -0.5966, +0.1038, +0.4146, +0.0169,
+ -0.2569, +0.0757
+ ],
+ [
+ -0.0059, +0.2504, -1.8223, +0.0071, +0.0843, +0.0531, +0.0537,
+ -0.4270, -0.0225, +0.0206, +0.1877, -0.0539, -0.1275, -0.1903,
+ -0.2041, +0.1867, -0.2453, +0.0968, -0.7747, -0.0996, -0.1644,
+ -0.2217, -0.0222, -0.0323, +0.1196, -0.4662, -0.0733, -0.2897,
+ -0.0650, +0.1710, +0.3257, -0.6486, +0.1965, +0.4933, -0.1914,
+ -0.7322, -0.7016, -0.2255, +0.0376, +0.2672, -0.5327, +0.2688,
+ -0.0806, -0.2247, -0.1833, -0.4959, -0.7814, -0.6611, +0.1856,
+ -0.1662, -0.0610, +0.4234, +0.1225, +0.0887, +0.1060, +0.1328,
+ +0.1165, -0.3699, -0.3317, +0.1403, +0.1845, +0.0305, -0.2385,
+ -0.0139, +0.2337, -0.0865, -0.4594, +0.0413, -0.3618, +0.1392,
+ +0.0640, +0.3269, -0.4006, +0.6018, -0.1011, +0.1064, +0.0764,
+ -0.7746, -0.2271, -0.8182, -0.1293, -0.5567, -0.3629, -0.6294,
+ +0.1535, -0.5792, +0.0733, -0.1860, +0.3598, -0.0287, +0.3026,
+ -0.4029, +0.0910, +0.3008, +0.3386, +0.0652, +0.1527, +0.2761,
+ +0.2965, -0.4328, -0.1331, -0.0883, +0.1920, -0.2682, +0.2188,
+ -0.3514, -0.2600, -0.0027, -0.9167, -0.3502, +0.6296, +0.1959,
+ +0.0535, +0.2855, +0.1944, +0.6012, -0.8331, +0.3115, +0.3111,
+ +0.0916, -0.1444, -0.0131, -0.2425, +0.2020, -0.2527, +0.2171,
+ +0.0902, +0.2377
+ ],
+ [
+ +0.1734, -0.3360, +0.0102, -0.1136, +0.0421, +0.0059, +0.0081,
+ -0.1179, -0.2811, -0.3038, -0.0654, -0.0284, +0.1823, -0.5043,
+ -0.0641, +0.3135, +0.2485, -0.1943, -0.7957, -0.4855, +0.3363,
+ -0.3024, +0.0201, -0.0095, -0.2435, -0.3528, +0.1311, -0.1494,
+ -0.2564, +0.0214, +0.0812, -0.0815, -0.3220, +0.0243, +0.1589,
+ +0.2596, +0.0788, -0.1100, -0.0409, -0.0636, +0.0915, -0.0302,
+ -0.1303, +0.2093, -0.7333, -0.4362, -0.0231, +0.1416, -0.0775,
+ -0.6113, +0.1495, +0.1520, +0.1515, -0.2184, +0.2908, -0.4809,
+ +0.1760, -0.5343, +0.0255, +0.3853, -0.6806, -0.0456, -0.0844,
+ -0.2962, -0.2281, +0.2654, -1.0656, +0.0755, -0.1765, +0.1391,
+ +0.1288, +0.2546, -0.0349, +0.0460, +0.0746, -0.3408, -0.1496,
+ -0.7456, -0.2263, -0.1545, -0.3210, -0.1699, -0.0215, -0.0136,
+ +0.3570, +0.2186, +0.0431, -0.2374, -0.1237, -0.0502, +0.3524,
+ -0.3504, -0.8003, -0.1479, -0.1306, -0.1243, -0.0349, +0.0689,
+ -0.1313, -0.1078, -0.0253, -0.0653, -0.0671, -0.4589, +0.1150,
+ -0.2785, -0.4662, -0.0127, -0.2129, +0.2506, -0.3115, +0.3973,
+ -0.0523, +0.1712, -0.0820, +0.0759, -0.0481, -0.0596, +0.1819,
+ -0.3091, +0.1873, +0.2186, -0.5450, +0.0715, +0.1790, -0.2883,
+ +0.0226, +0.1730
+ ],
+ [
+ -0.2602, -0.3215, -0.0906, +0.1177, -0.1313, -0.5380, -0.4104,
+ -0.4251, -0.0429, +0.1910, +0.2934, -0.0522, -0.0154, +0.0940,
+ -0.7726, -0.0532, -0.1507, -0.4646, +0.0155, -0.1635, +0.4168,
+ +0.3530, -0.0973, -0.0352, -0.1655, -0.2412, +0.1004, +0.3036,
+ -0.0438, -0.6966, -0.3239, -0.8388, +0.0405, -0.0482, -0.4399,
+ +0.5633, -0.0991, +0.0878, -0.4014, -0.3725, -0.1872, +0.1927,
+ -0.0272, +0.2497, -0.3443, +0.0991, -0.2369, +0.2886, +0.0404,
+ -0.3542, -0.3079, -0.3784, -0.1192, -0.5404, +0.1479, +0.1591,
+ +0.2231, +0.2725, -0.1559, +0.2966, +0.0741, +0.0748, +0.3326,
+ -0.7224, -0.0826, -0.0814, +0.0424, -0.4582, +0.3849, -0.0785,
+ -0.1042, +0.1102, -0.2348, -0.0806, -0.0245, -0.1454, +0.3831,
+ -0.0851, -0.6094, -0.4785, -0.1979, -0.2312, -0.3423, -0.1665,
+ +0.3068, -0.6060, +0.1745, -1.2672, -0.3371, +0.0945, -0.0562,
+ -0.6999, -0.2454, -0.1074, +0.2825, -0.3700, +0.3908, -0.1738,
+ +0.0191, -0.5917, -0.0799, -0.4251, -0.9711, +0.0096, -0.7487,
+ -0.1138, +0.2945, -0.4373, +0.1421, -0.1377, +0.2897, -0.0829,
+ +0.2462, +0.1447, +0.0142, -1.0093, -1.0673, -0.6900, -0.2250,
+ +0.1916, -0.8061, -0.3221, +0.1838, +0.0782, +0.0042, +0.0976,
+ +0.4808, -0.2449
+ ],
+ [
+ -0.0186, +0.0312, -1.1666, +0.4912, +0.0535, -0.0724, +0.4590,
+ +0.5356, -0.2967, +0.0945, +0.3760, +0.1753, +0.5287, -0.3805,
+ -0.8444, -0.1378, -0.2789, -0.0429, +0.5450, -0.0904, +0.0773,
+ -0.4917, -0.7371, +0.0729, +0.1716, +0.0492, +0.2712, -0.4112,
+ +0.4279, -0.2601, +0.1060, -0.1974, -0.0752, -0.0291, +0.0424,
+ -0.3498, +0.3540, +0.4572, -0.0620, -0.1689, -0.7175, -0.0296,
+ +0.0981, -0.0719, +0.1335, -0.0579, -0.7234, +0.5031, +0.0332,
+ +0.2731, -0.3885, -1.1700, +0.2232, +0.1357, -0.1256, -0.3946,
+ +0.1373, +0.2081, +0.0855, -0.5177, -0.0246, +0.2997, -0.5857,
+ -0.3490, +0.1922, -0.6260, -0.2010, -0.0540, -0.5983, -0.1169,
+ -0.0199, +0.2142, -0.0344, -0.0711, +0.2242, +0.0118, +0.1590,
+ +0.1529, +0.1587, -0.7301, +0.1030, -0.2880, +0.2163, -0.2043,
+ -0.0016, -0.0082, +0.1785, -0.6902, -0.1381, -0.1248, +0.3989,
+ -0.1963, +0.4378, -0.0211, +0.2309, -0.5025, +0.1148, +0.0732,
+ +0.0534, +0.0736, -0.3570, +0.1016, +0.0007, -0.0154, -0.2812,
+ +0.4252, +0.0808, +0.3596, +0.2169, -0.2200, -0.8553, -0.7431,
+ -0.0798, -0.5308, +0.0099, +0.1634, +0.1090, +0.0750, +0.0094,
+ -0.3583, -0.2442, -0.0193, +0.1221, +0.2039, -0.4970, -0.4103,
+ -0.2623, +0.1852
+ ],
+ [
+ +0.0035, -0.2371, -0.0652, -0.5765, +0.2370, +0.1303, -0.1977,
+ -0.6236, +0.1144, -0.1280, +0.0588, -0.0054, -0.1472, -0.2433,
+ -1.1024, +0.2071, -0.1101, +0.7363, -0.0024, +0.2096, +0.0864,
+ -0.2140, +0.1191, -0.1789, +0.2744, -0.5595, -0.4182, +0.0468,
+ -0.2223, +0.1140, -0.0006, -0.4948, -0.2110, +0.2943, -0.0723,
+ -0.0925, -0.4041, +0.2033, -0.5595, +0.0529, +0.1126, -0.8388,
+ -0.2227, -0.0921, -0.2104, -0.0412, +0.1017, +0.0853, +0.2641,
+ +0.0581, +0.2180, -1.8387, +0.3215, +0.2269, -0.1205, -0.0315,
+ +0.0466, -0.4390, -0.9485, -0.9049, +0.1571, -0.1657, -0.1598,
+ -0.6076, +0.3959, -0.1420, +0.0664, -0.0393, +0.2893, -0.4381,
+ +0.0649, -0.0343, +0.1189, -0.3135, +0.0619, +0.0534, -0.0150,
+ -0.0847, -0.3386, -0.4189, -0.2144, -0.5014, -0.4263, -0.3158,
+ -1.1655, +0.4229, +0.1088, -0.0160, +0.0623, -0.1086, +0.0452,
+ -0.1172, +0.0235, -0.4329, +0.0315, -0.2861, -1.8719, +0.1323,
+ -0.1785, +0.0296, +0.0625, +0.1258, -0.2638, -0.2692, +0.2976,
+ +0.0126, -0.5463, -0.4668, -0.1375, +0.0925, -0.1242, -0.8335,
+ +0.1498, -0.4909, +0.0150, +0.1882, -0.3309, +0.3453, -0.0746,
+ +0.1613, -0.0352, +0.4158, -0.6152, -0.1984, +0.3839, -0.3962,
+ -0.0498, -0.8401
+ ],
+ [
+ -0.2221, +0.4577, -0.3264, +0.0867, +0.2288, -0.6050, +0.0765,
+ -0.0253, +0.0234, -0.1089, +0.2742, +0.0977, -0.2987, +0.3709,
+ -0.6876, -0.0137, +0.2326, +0.1873, -0.0458, +0.4263, -0.1981,
+ -0.1495, -0.2254, +0.1243, +0.2372, +0.0684, +0.0282, +0.0340,
+ +0.2636, -0.1085, +0.1307, +0.0005, +0.2727, -0.3159, -0.0499,
+ -0.5526, -0.4607, -0.1653, -0.1389, -0.2559, -0.3343, -0.1751,
+ +0.0961, -0.1130, -0.3663, +0.1649, -0.0549, +0.1994, +0.3338,
+ +0.2785, +0.3672, +0.1056, +0.3413, +0.2041, +0.2421, -0.4176,
+ +0.0595, -0.7157, -0.8599, -0.2813, -0.5280, -0.2340, -0.3723,
+ +0.3193, -0.0203, -0.7509, -0.4940, -0.0868, -0.0221, +0.0788,
+ -0.0377, +0.1623, +0.0788, -0.0519, -0.2508, -0.3549, +0.2371,
+ -0.4721, +0.5425, +0.5633, +0.0457, -0.0053, -0.4628, -0.2514,
+ -0.1613, -0.2032, +0.0440, +0.3368, +0.0844, -0.1580, -0.7842,
+ +0.1071, +0.0913, +0.2130, -0.3305, +0.1332, +0.1810, -0.1177,
+ +0.2646, -0.4359, -0.3863, -0.0371, +0.2614, -0.1002, +0.1836,
+ -0.2881, +0.4521, -0.1639, -0.0507, +0.1292, -0.2386, -0.2004,
+ -0.0219, -0.9069, +0.2525, -0.0051, +0.5764, +0.1496, +0.2575,
+ -0.1619, +0.1981, -0.0817, -0.0992, +0.1743, -0.1275, -0.2257,
+ -0.0344, +0.1149
+ ],
+ [
+ +0.0552, -0.1676, +0.0500, +0.0371, +0.2764, -0.2129, -0.2672,
+ +0.3881, +0.3348, +0.1618, -0.0235, -0.2225, +0.0011, +0.3560,
+ +0.2559, -0.2586, -0.0630, -0.0616, +0.2104, +0.1421, +0.0131,
+ -0.5461, -0.1410, -0.2444, -0.3954, +0.2889, -0.1876, +0.5588,
+ -0.2274, +0.0884, -0.4838, +0.0815, -0.4368, -0.0366, -0.0305,
+ -0.2435, +0.1682, -0.1123, -0.6352, -0.1180, -0.1304, -0.3762,
+ -0.1200, -0.0787, +0.1968, +0.0229, +0.6007, +0.3058, +0.0111,
+ +0.0071, -0.3882, -0.4516, +0.0657, -0.4349, -0.0312, -0.3833,
+ +0.3771, +0.5473, -1.1309, -0.2844, -0.2990, -0.3114, -0.2003,
+ +0.1692, -0.5216, -0.2573, +0.2162, +0.4196, +0.0645, +0.1814,
+ -0.1180, -0.1903, +0.1395, +0.3146, -0.0503, -0.0129, +0.1173,
+ -0.1289, -0.7010, +0.1966, -0.1170, +0.1836, -0.5466, +0.2949,
+ +0.1268, +0.2523, +0.1339, +0.2687, -0.1148, -0.9586, -0.3372,
+ +0.0221, -0.3042, +0.1392, -0.1978, -0.4729, +0.0023, -0.0018,
+ -0.3816, -0.2387, +0.0710, +0.0402, +0.3025, -0.0422, +0.2517,
+ -0.1266, +0.2964, -0.0651, -0.1329, +0.0103, +0.4835, -0.1226,
+ +0.0643, -0.1345, +0.0647, -0.3269, -0.4923, +0.2875, +0.1877,
+ -0.1526, -0.0785, -0.0118, -0.0353, -0.6584, +0.3742, -0.1663,
+ +0.2500, +0.0618
+ ],
+ [
+ +0.2997, +0.2519, -0.4286, -0.7198, -0.2245, -0.1805, -0.4405,
+ -0.4680, -0.1060, -0.3217, +0.1738, -0.2077, +0.1985, -0.3943,
+ -0.3274, -0.5616, -0.5938, +0.0370, -0.0538, +0.2143, -0.3124,
+ -0.3561, +0.3302, -0.2428, -0.1921, +0.0271, -0.0047, -0.2883,
+ +0.0238, -0.2252, -0.2254, +0.1708, -0.2050, +0.2460, +0.0141,
+ +0.0999, -0.1220, -0.1217, -0.1450, -0.0053, -0.4942, -0.4115,
+ +0.1852, -0.1231, +0.1924, -0.3888, -0.2041, -0.4723, -0.4349,
+ +0.0732, -0.6097, -0.3690, +0.1171, +0.1377, -0.3710, +0.4654,
+ -0.1571, -0.8847, +0.0086, -0.0884, +0.3293, -0.5117, +0.0098,
+ +0.2000, -0.2808, +0.0643, +0.1971, -0.0608, -0.4650, -0.3024,
+ +0.1653, -0.0648, +0.2489, -0.1785, -0.1707, +0.3948, -0.3938,
+ -0.6172, -0.2203, -0.7173, +0.0293, -0.3072, -0.0620, -0.2389,
+ -0.0896, +0.1239, +0.2999, -0.0323, -0.5117, -0.0260, -0.3110,
+ -0.1003, -0.5293, -0.0664, +0.2057, +0.1447, -0.3164, -0.0746,
+ -0.6058, +0.1389, +0.1527, -0.2403, -0.0355, -0.1622, -0.0819,
+ +0.2913, +0.2429, -0.0298, +0.0585, -0.0653, +0.1618, -0.0336,
+ -0.6792, +0.3777, +0.0029, -0.2496, +0.3963, -0.0700, +0.4383,
+ -0.4798, +0.2028, +0.1346, -0.6482, -0.1837, +0.0233, -0.0848,
+ +0.0192, +0.2274
+ ],
+ [
+ -0.7703, +0.3597, +0.2273, -0.0120, -0.6104, -0.3715, -1.1547,
+ -0.8693, -0.0804, -0.3563, -0.2710, +0.1459, +0.0653, +0.0391,
+ -1.0880, +0.1807, +0.3675, -0.1739, -0.1623, +0.1400, -0.1035,
+ +0.1792, +0.6849, -0.7708, -0.4373, +0.1885, -0.2048, +0.0541,
+ +0.1565, -0.4325, -0.5115, -0.0447, +0.3524, +0.1776, +0.2972,
+ -0.0688, -0.4532, -0.0173, -0.0426, -0.1938, +0.1425, -0.4570,
+ +0.0673, -0.0495, -0.3246, +0.2467, +0.3304, -0.1078, +0.3719,
+ -0.0125, -0.0105, -0.1284, +0.3591, -0.3257, +0.2117, -0.3518,
+ +0.2448, -0.5693, +0.4628, -0.4708, -0.0589, +0.2012, +0.1599,
+ -0.3289, -0.1241, -0.8050, -1.0541, +0.2217, +0.0578, -0.0257,
+ +0.4239, -0.3047, -0.4532, +0.5791, -0.0018, -0.1231, -0.1040,
+ -0.2046, -0.0637, -0.1778, -0.1759, +0.3343, -0.4349, -0.6581,
+ -0.0120, -0.3806, -0.6405, -0.1362, +0.1076, -0.9756, -1.0895,
+ -0.5013, +0.1329, -1.0341, -0.1451, -0.0347, -0.0139, -0.2391,
+ -0.3683, +0.0724, +0.3231, -0.7633, -0.1369, +0.0740, -0.0623,
+ -0.0497, -0.1996, +0.0780, +0.2873, -0.2659, -0.3895, -0.6219,
+ +0.2696, +0.4523, -0.3043, -0.2205, +0.2472, -1.0548, -0.3012,
+ -0.6168, -0.6512, -0.2143, -0.5998, -0.2672, +0.1359, -0.0752,
+ +0.0370, +0.0627
+ ],
+ [
+ -0.1791, -0.2279, -0.0998, +0.1783, +0.1553, +0.0612, -0.2220,
+ +0.1551, -0.2240, -0.0159, +0.0010, -0.0103, +0.1007, -0.3934,
+ -0.5397, -0.2077, +0.0963, -0.1834, -0.2112, -0.0267, -0.3809,
+ -0.2319, +0.2167, +0.0076, +0.0075, -0.0750, +0.0607, +0.1455,
+ +0.0941, -0.0205, -0.2981, -0.0061, +0.4115, -0.4933, +0.2443,
+ -0.9828, -0.3445, -0.2593, -0.3871, +0.0736, -0.8643, -0.0187,
+ +0.1316, -0.2119, +0.3713, +0.0419, -0.5368, +0.1741, -0.1143,
+ +0.0186, -0.2846, -0.4499, -0.2979, -0.0987, -0.1089, -0.1469,
+ +0.1726, -0.4902, +0.3746, -0.1956, -0.6684, -0.1877, -0.4473,
+ +0.3690, +0.1347, -0.1845, -1.4047, -0.1341, -0.0740, -0.0375,
+ -0.1693, -0.3976, -0.6494, -0.0323, -0.2126, +0.3526, -0.2334,
+ -0.3229, +0.4134, +0.0701, +0.2353, +0.4844, +0.0562, +0.3268,
+ -0.1159, -0.1046, -0.0269, -0.0188, -0.1613, -0.2217, -0.2000,
+ -0.0957, -0.2712, +0.3059, +0.1249, -0.1035, +0.0004, +0.3311,
+ +0.1874, +0.3168, +0.0562, +0.1328, +0.1546, -0.1332, -0.0177,
+ +0.2608, -0.1027, -0.4310, -0.5956, +0.0371, +0.0779, -0.1145,
+ +0.0611, +0.1766, +0.2322, +0.3979, -0.1862, +0.3387, -0.6133,
+ +0.0790, +0.0620, -0.1411, -0.0586, -0.0211, -0.1644, -0.4890,
+ -0.0665, +0.2908
+ ],
+ [
+ -0.1590, +0.3465, -0.7111, +0.0057, +0.2907, -0.4929, +0.1248,
+ -0.0589, -0.0498, -0.3394, +0.3763, +0.2212, -0.0642, +0.4740,
+ -0.3273, -0.3461, +0.1982, -0.4864, +0.3201, +0.1274, +0.2486,
+ +0.0471, -0.0542, +0.2365, +0.4782, -0.9680, -0.0935, -0.0158,
+ -0.1450, -0.3454, -0.2127, -0.2524, +0.1208, -0.0273, +0.3810,
+ -0.0663, +0.0663, -0.2722, -0.6524, -0.3031, +0.1824, -0.5041,
+ +0.0428, +0.3808, -0.4099, +0.1713, -0.2006, +0.3985, -0.1635,
+ -0.0436, -0.8630, +0.0073, -0.0152, +0.2548, +0.3976, +0.2089,
+ -0.0484, +0.0710, +0.0378, -0.0727, -0.3489, -0.2270, +0.2633,
+ +0.0113, +0.3312, +0.0097, -0.5475, +0.1103, +0.0917, -0.2627,
+ -0.5849, +0.1446, -0.8225, -0.3470, -0.0024, -0.2059, -0.4963,
+ +0.0666, -1.5108, -0.2249, +0.1441, -0.2078, -0.2021, -0.2921,
+ -0.3632, +0.0481, +0.0159, -0.3559, -0.3166, +0.2004, -0.4084,
+ -0.3994, +0.1976, +0.0868, +0.1715, +0.0243, -0.0022, +0.3939,
+ +0.0631, -0.5910, -0.0901, +0.0470, -0.1276, +0.0298, +0.0838,
+ +0.2862, -0.7131, -0.1051, -0.4813, +0.1589, -0.1359, +0.1241,
+ -0.0412, +0.1048, +0.1344, -0.3297, -0.0250, +0.1921, +0.0646,
+ +0.1873, -0.3154, +0.1462, -0.1932, +0.4339, -0.4673, +0.1966,
+ -0.2193, +0.1271
+ ],
+ [
+ -0.4045, -0.4693, -0.2753, -0.0697, -0.7086, -0.1363, +0.0742,
+ +0.5169, -0.9451, +0.0164, +0.7178, +0.4367, -0.5113, -0.0481,
+ -0.3382, +0.3882, -0.6975, +0.3492, +0.6143, +0.2262, -0.3421,
+ -0.1838, +0.5108, +0.2796, +0.3800, +0.0532, -0.4792, -0.4716,
+ +0.0690, -0.0716, +0.2828, -0.7554, +0.1276, -0.2303, +0.0311,
+ -0.2633, +0.0998, +0.2469, +0.1871, +0.6439, -0.4219, -0.2035,
+ -0.4298, +0.0361, +0.1351, +0.2658, -0.2374, -0.1598, -0.5585,
+ -0.0315, -0.9313, +0.2618, +0.2350, -0.0825, +0.0885, +0.1367,
+ +0.3425, +0.0241, -0.4690, -0.1568, -0.2416, -0.2253, -0.0125,
+ -0.1595, +0.0867, +0.4414, -0.8874, +0.0626, -0.3080, +0.5134,
+ +0.4091, -0.2617, -0.1513, -0.1776, +0.0203, +0.2636, +0.0000,
+ -0.4166, -0.0429, +0.2566, -0.3680, -0.1859, -0.6129, +0.4622,
+ -0.1716, -0.0095, -0.1997, +0.3254, +0.4619, -0.4222, +0.0490,
+ +0.2444, -0.0382, -0.0066, +0.0251, -0.7795, +0.6492, -0.4009,
+ +0.0306, -0.6512, +0.0904, -0.5018, +0.2744, +0.6262, -0.0631,
+ -0.7705, -0.3628, -0.0445, +0.1403, -0.3503, +0.3548, -0.4655,
+ +0.6479, -0.2118, +0.2087, -0.8546, +0.7755, -0.2266, +0.2387,
+ -0.6748, +0.1535, -0.3294, +0.3806, +0.1586, -0.1722, -0.2350,
+ +0.1667, +0.3890
+ ],
+ [
+ +0.2363, +0.0062, -0.4151, -0.2195, -0.1890, +0.1727, -0.1118,
+ -0.2844, +0.1809, -0.2691, -0.1235, -0.1263, +0.3011, -0.5891,
+ +0.4425, -0.1007, -0.1312, -0.2862, +0.1523, +0.0050, -0.0170,
+ -0.3431, -0.2285, +0.0159, +0.1520, -0.6582, +0.1684, -0.4045,
+ -0.2205, +0.1423, +0.0978, -0.0692, -0.6432, +0.2055, -0.0115,
+ +0.0345, +0.0718, -0.1850, -0.3148, -0.0285, +0.4103, +0.3684,
+ +0.0221, -0.9018, -0.4790, -0.2507, -0.0904, +0.3063, +0.1512,
+ -0.0405, -0.5723, -0.7270, -0.0956, +0.1412, -0.0119, -0.3245,
+ +0.2918, -0.4344, +0.1103, +0.2323, -0.3513, +0.3947, +0.3163,
+ -0.3286, +0.0400, -0.4976, -0.0799, +0.1862, -0.4608, -0.4698,
+ -0.3919, -0.1890, +0.3467, -0.4846, +0.1217, -0.4737, -0.0228,
+ -0.0274, -0.7486, -0.7364, +0.0778, +0.1966, -0.0731, -0.7374,
+ -0.3736, -0.5404, -0.0662, -0.2419, +0.1435, +0.1261, -0.8224,
+ -0.2903, +0.1371, +0.0677, +0.1414, -0.7651, -0.2402, -0.2509,
+ +0.3953, -1.0583, -0.4834, +0.1641, -0.4187, -0.3944, -0.3237,
+ -0.2496, -0.3212, -0.0233, -0.0451, +0.0084, +0.0396, -0.5585,
+ +0.0647, -0.7654, +0.0435, +0.2010, -0.7568, -0.0416, -0.7364,
+ -0.1277, -0.3532, +0.1159, +0.1172, -0.0711, +0.1222, +0.1614,
+ +0.2695, -0.1347
+ ],
+ [
+ +0.2645, +0.1945, -0.1109, -0.0107, +0.4603, -0.0164, -0.6991,
+ +0.0160, -0.2493, -0.0361, +0.0486, +0.1446, +0.1816, -0.3309,
+ -0.5692, +0.3186, +0.0398, +0.1935, +0.0052, +0.1339, -0.6104,
+ -0.0547, -0.0493, +0.1449, -0.0981, -0.4863, -0.0619, -0.0866,
+ -0.2730, -0.0892, -0.5666, +0.0349, -0.1451, -0.0458, +0.0709,
+ -0.0688, -0.3157, -0.1346, +0.0223, +0.1968, -0.3147, -0.2957,
+ +0.0356, -0.4077, -0.0574, +0.1900, -0.2019, -0.4952, -0.4156,
+ -0.2254, +0.3388, -0.1667, -0.0230, +0.0165, -0.1358, -0.0144,
+ +0.0272, -0.2540, -0.0612, -0.0324, -0.0505, +0.1923, -0.3608,
+ +0.3274, -0.5640, +0.2636, +0.2367, -0.1310, +0.0460, +0.0487,
+ +0.0208, -0.3474, +0.1411, +0.2065, +0.6770, -0.1130, -0.0721,
+ -0.6301, -0.0159, -0.0925, +0.1345, +0.1874, -0.4512, -0.2718,
+ +0.0344, -0.2044, +0.1453, -0.0164, -0.1500, +0.3967, +0.0505,
+ -0.0252, +0.2409, -0.4191, +0.0563, +0.0028, +0.1797, -0.6223,
+ +0.3218, -0.3501, -0.1397, -0.3705, -0.0733, +0.2525, +0.1673,
+ +0.2652, +0.3524, +0.2129, +0.0589, +0.0883, +0.4070, +0.3489,
+ +0.0569, -0.1190, +0.4708, -0.2421, +0.2813, +0.1846, +0.2897,
+ -0.2035, +0.2092, +0.1079, +0.3770, -0.0807, -0.2196, +0.1587,
+ +0.0665, +0.1521
+ ],
+ [
+ -0.0032, -0.5900, +0.3245, +0.2203, -0.4119, +0.0732, -0.1448,
+ -0.2840, -0.5423, +0.4369, +0.1149, -0.1663, -0.0846, -0.4860,
+ -0.7153, +0.2717, +0.3148, +0.0577, +0.0600, +0.1907, +0.0226,
+ -0.8129, -0.0191, -0.1380, -0.3814, -0.2589, +0.1204, -0.1775,
+ -0.4343, -0.3241, -0.4191, +0.2309, -0.1817, +0.1551, +0.1934,
+ -0.6179, -0.3449, -0.3706, -0.1836, -0.0723, +0.1246, -0.1750,
+ +0.0323, +0.0048, +0.1908, -0.0128, -0.2133, +0.2548, +0.2636,
+ +0.2050, -0.5303, +0.2526, +0.0808, -0.5870, -0.2439, +0.2156,
+ -0.4137, -0.7845, -0.0266, -0.1659, -0.0701, -0.0901, +0.4030,
+ -0.2117, -0.3111, +0.2580, -0.3229, +0.2362, +0.5040, -0.0254,
+ +0.1128, +0.0537, +0.0629, +0.0724, -0.0315, +0.3396, +0.0600,
+ +0.2878, +0.1927, +0.0392, -0.4752, -0.1950, -0.1491, -0.4002,
+ +0.2534, +0.0002, -0.0474, +0.3546, +0.3228, +0.4452, -0.0011,
+ +0.0549, -0.0518, +0.2764, +0.2517, +0.2436, -0.4300, +0.2737,
+ +0.3223, +0.0856, +0.1481, -1.0614, -0.0964, -0.6597, -0.1409,
+ -0.1445, -0.1676, -0.5498, +0.7005, +0.3196, +0.2127, -0.0677,
+ -0.2303, -0.2276, -0.1833, -0.2009, -0.0879, -0.1477, +0.2008,
+ -0.1563, +0.0598, -0.0930, +0.1721, -0.2699, -0.2913, +0.0134,
+ -0.2100, -0.2508
+ ],
+ [
+ +0.0078, -0.1145, +0.0566, +0.2845, +0.3333, +0.0245, +0.5178,
+ -0.2139, -0.5225, +0.1092, +0.3087, -0.2633, -0.4887, +0.5600,
+ -0.3808, -0.4829, +0.3219, +0.3766, +0.0972, +0.4930, -0.2441,
+ -0.2812, -0.2231, -0.0461, -0.6873, -0.0303, -0.0595, +0.1965,
+ +0.1405, +0.2027, +0.1398, -0.5602, -0.5044, +0.3049, -0.8612,
+ -0.0465, +0.4593, -0.1495, +0.4121, +0.3910, +0.1221, -0.3441,
+ -0.1128, -0.3937, -0.0790, -0.2019, -0.5485, +0.1180, +0.0659,
+ -0.0949, -0.1865, +0.8964, +0.1803, +0.2051, -0.3293, -0.3495,
+ -0.2919, +0.1497, -0.0474, -1.0231, +0.0527, -0.4692, -0.0999,
+ +0.0488, -0.1689, +0.1371, -0.1849, +0.1495, -1.0595, +0.4409,
+ -0.1860, +0.3221, -0.4063, +0.2084, +0.3131, -0.0811, -0.0254,
+ +1.0520, +0.2568, -0.1223, -0.6538, -0.3910, +0.0634, -0.1927,
+ +0.0842, -0.5116, +0.0424, +0.0742, +0.0284, -0.9449, -0.2828,
+ -0.2224, +0.1159, -0.0119, -0.0894, -0.2882, -0.3089, +0.2021,
+ -0.1726, -0.1260, -0.2500, -0.0621, -0.6379, +0.2073, +0.3437,
+ +0.2344, +0.1052, +0.0429, -0.1970, +0.7690, -0.2105, -0.6152,
+ +0.1540, -0.1216, -0.1457, -0.0201, -0.7810, -0.5367, -0.1856,
+ -0.3119, -0.6950, -0.0800, +0.1553, +0.7838, -0.4806, -0.7120,
+ -1.0775, +0.4206
+ ],
+ [
+ -0.8158, -0.0751, +0.4568, +0.1936, -0.0115, +0.0016, +0.1775,
+ -0.3664, +0.2353, -0.1059, -0.0433, -0.2364, -0.0069, -0.0294,
+ -0.3629, +0.4730, -0.3616, +0.2660, +0.4088, -0.0482, +0.2876,
+ -0.0399, +0.1708, +0.3116, +0.0624, +0.1124, +0.2188, -0.1548,
+ +0.0379, +0.2865, +0.0004, -0.3470, -0.4660, -0.1543, -0.6684,
+ +0.3219, +0.7255, +0.2310, -0.2165, +0.0654, -0.5981, -0.2871,
+ -0.4359, -0.0235, -0.4874, -0.6068, -0.1394, +0.0140, +0.1378,
+ +0.0300, -0.3226, -0.1644, +0.0784, -0.3535, +0.4106, +0.3939,
+ +0.4227, -0.2622, -0.0644, -0.7142, -0.6646, -0.3376, -0.0979,
+ -0.1231, -0.2758, -0.7267, -0.0163, -0.3791, +0.2953, -0.0657,
+ +0.0056, -0.4484, -1.0532, +0.5263, -1.1149, -0.1071, -0.5389,
+ -0.0615, -0.0329, +0.1728, -0.0696, -0.3026, -0.0906, -0.1880,
+ +0.1664, -0.4204, +0.2661, -0.6305, -0.2993, -0.1241, -0.2866,
+ -0.1463, +0.4917, +0.1292, -0.4802, +0.3295, -0.7186, -0.1402,
+ -0.0365, +0.0668, +0.1496, -0.3388, -0.0329, -0.2554, +0.1411,
+ -0.6357, -0.1040, +0.1403, +0.1908, -0.7587, -0.5095, +0.2143,
+ +0.2150, +0.2288, +0.2723, -0.8710, +0.1903, +0.0446, -0.7277,
+ -0.1252, -0.0186, +0.2522, -0.4735, -0.0302, -0.3595, -0.3273,
+ +0.2083, +0.0594
+ ],
+ [
+ -0.2945, +0.3638, +0.1284, -0.5290, -0.1601, +0.1974, +0.1350,
+ -0.3181, +0.1355, -0.1144, -0.8185, +0.3295, +0.0454, -0.2519,
+ +0.0312, -0.0144, +0.0092, +0.1483, +0.0112, +0.1281, +0.2530,
+ +0.0103, -0.2943, +0.0510, +0.2044, +0.0298, +0.2082, -0.0052,
+ +0.1255, +0.1062, -0.6600, -0.0876, +0.0886, -0.1130, -0.4472,
+ -0.0706, -0.2610, -0.4739, -0.3537, +0.0546, -0.3391, -0.5774,
+ -0.1172, +0.1768, +0.3232, +0.0907, -0.5683, -0.6098, +0.1459,
+ +0.3442, -0.3454, +0.0279, +0.1736, -0.1270, +0.1902, +0.0658,
+ -0.0248, -0.2342, +0.1925, +0.1986, +0.1576, -0.6727, -0.3078,
+ +0.1383, -0.2497, -0.1600, +0.2205, -0.3507, +0.1797, +0.5265,
+ -0.3245, +0.0958, -0.1797, +0.0096, +0.3309, -0.2368, +0.0322,
+ -0.2754, +0.1351, +0.5305, +0.1616, +0.5841, -0.7230, -0.3630,
+ -0.0726, -0.5375, -0.2105, -0.1580, +0.1014, +0.1227, +0.0446,
+ +0.0279, +0.5773, -0.5343, +0.2156, -0.0660, -0.3511, -0.0986,
+ -0.2209, +0.1967, +0.0479, +0.4054, -0.4945, +0.2346, -0.4003,
+ +0.1255, +0.0379, -0.3276, -0.3174, -0.1166, +0.1421, -0.3541,
+ +0.0644, -0.2061, -0.0139, +0.1682, -0.2627, +0.0623, +0.3165,
+ -0.2602, +0.3458, +0.2270, -0.4983, -0.1965, -0.1811, +0.1990,
+ -0.0536, -0.3008
+ ],
+ [
+ +0.2861, +0.2465, +0.5445, -0.6241, -0.3810, -0.2431, +0.0899,
+ +0.0009, +0.0287, -0.2860, +0.4379, +0.1100, -0.0060, -0.0688,
+ +0.3326, +0.4050, -0.0543, -0.3589, -0.4444, -0.1794, +0.0463,
+ -0.4859, +0.5408, +0.1241, -0.1452, +0.1877, +0.3102, -0.5119,
+ -0.4563, +0.2339, +0.0762, -0.0091, -0.2146, +0.0441, -0.8371,
+ +0.1044, +0.3922, +0.0952, +0.2457, -0.1154, +0.2800, +0.0238,
+ -0.1393, +0.1442, -0.6630, +0.3521, -0.2741, -0.0738, -0.0247,
+ -0.0797, -0.2095, +0.5173, -1.1573, +0.4417, +0.2038, -0.2982,
+ -0.2218, -0.0335, -0.0754, +0.0173, -0.1934, -0.7999, -0.7296,
+ -0.1534, +0.0536, -0.5079, +0.3942, +0.1031, +0.0451, +0.3108,
+ +0.0228, -0.5315, -0.5942, +0.1103, -0.1635, -0.0243, -0.3393,
+ -0.2886, +0.1906, +0.0561, -0.1120, -0.2488, -0.2236, -0.3785,
+ -0.0452, +0.2679, +0.2678, +0.4436, -0.8340, +0.0203, +0.6116,
+ -0.3027, +0.1799, -0.2438, +0.1136, -0.2686, -0.0847, +0.0744,
+ +0.0928, +0.2443, +0.0078, -0.0683, -0.4921, -0.0881, -0.1307,
+ +0.3243, -0.4150, +0.0227, -0.5241, -0.5408, +0.2310, +0.2375,
+ -0.0665, +0.2242, -0.2104, +0.2351, -0.1965, -0.3067, +0.0265,
+ -0.1175, -0.3326, -0.3971, -0.4137, -0.0187, -0.4536, -0.0317,
+ -0.2076, +0.1488
+ ],
+ [
+ +0.3728, -0.0547, +0.3402, +0.0846, -0.2939, -0.4488, -0.3421,
+ +0.3539, +0.2334, -0.1906, +0.2732, +0.2161, -0.4480, +0.1510,
+ -0.4346, -0.0497, +0.2783, -0.1186, +0.0806, -0.0484, +0.1960,
+ +0.2053, -0.0394, +0.0148, -0.0442, +0.1445, -0.2074, +0.2616,
+ -0.0416, +0.2471, -0.3292, +0.2827, +0.1714, -0.0269, -0.1959,
+ -0.3425, +0.3473, -0.2343, -0.3136, +0.2331, -0.0308, +0.1485,
+ +0.4697, -0.1206, +0.3913, -0.1763, -0.3010, -0.2376, +0.5187,
+ +0.1515, -0.2541, -0.0851, -0.5678, +0.1875, -0.0576, +0.2598,
+ -0.0535, +0.0647, -0.2367, -0.5131, -0.6636, +0.0245, +0.1720,
+ -0.1660, +0.0015, -0.5347, +0.0851, -0.1086, -0.0278, +0.3490,
+ -0.3233, -0.1908, +0.2611, +0.2172, -0.0438, +0.1540, +0.0241,
+ +0.3071, -0.2689, +0.0820, +0.3680, -0.1333, -0.4390, -0.0022,
+ -0.1614, -0.2464, -0.5837, -0.1894, +0.0748, +0.2046, -0.1179,
+ -0.3081, -0.2560, +0.0728, -0.0119, +0.1377, -0.2225, -0.1516,
+ -0.0038, +0.0417, +0.3232, -0.1597, +0.0374, -0.2734, -0.0756,
+ +0.2224, -0.1316, -0.1672, +0.1052, +0.1462, +0.3924, -0.1192,
+ -0.2089, -0.0764, -0.0825, -0.1494, -0.2589, +0.1217, -0.2977,
+ -0.2204, -0.2216, -0.3703, -0.3574, -0.1172, -0.2267, +0.2539,
+ -0.0252, +0.0847
+ ],
+ [
+ +0.1868, -0.6792, -0.0882, -0.4607, -0.0270, +0.1324, +0.2618,
+ -0.6255, -0.0388, +0.3012, +0.1471, -0.1281, -0.3204, -0.1431,
+ -0.3314, -0.0240, -0.1630, -0.2548, +0.1775, -0.1358, -0.2844,
+ +0.0252, -0.4802, -0.0492, -0.2956, +0.0343, +0.2928, +0.2291,
+ -0.0586, +0.1699, +0.2495, -0.0260, +0.1860, -0.0989, +0.0219,
+ +0.0784, -0.1875, +0.2573, -0.1494, -0.0104, +0.1539, +0.3493,
+ -0.1276, +0.2420, +0.2307, -0.1657, -0.3181, +0.0017, -0.2638,
+ +0.1521, +0.2645, -0.9728, -0.0588, -0.3231, +0.2092, -0.3449,
+ +0.4395, +0.2772, +0.0681, -0.0655, +0.0825, +0.0245, +0.6292,
+ +0.1525, -0.3409, -0.0468, -0.3370, +0.1332, -0.0825, +0.1383,
+ +0.0434, +0.3655, +0.1437, -0.2284, -0.1684, -0.0226, +0.4623,
+ +0.1211, -0.1569, +0.0185, +0.3112, +0.1661, +0.0546, +0.2685,
+ +0.1671, +0.0382, +0.1157, +0.2854, +0.2848, +0.0935, +0.3446,
+ -0.3609, -0.2390, +0.1744, -0.7724, +0.0076, -0.3620, +0.4923,
+ -0.0388, -0.1553, +0.2411, -0.0320, +0.4227, +0.2251, -0.2288,
+ -0.6397, -0.1282, +0.4254, +0.0105, +0.2636, -0.0833, -0.0003,
+ +0.1051, -0.0291, -0.3264, -0.0814, +0.1735, -0.0074, -0.4138,
+ -0.0254, -0.0859, +0.0787, -0.1913, +0.1291, +0.1845, -0.0069,
+ +0.0697, +0.1905
+ ],
+ [
+ +0.2668, +0.0176, -0.6247, +0.0919, -0.4115, -0.2334, +0.0598,
+ +0.1609, +0.5839, +0.1131, +0.2215, -0.2243, +0.1482, -0.3540,
+ -0.9145, +0.0116, -0.0904, -0.3873, -0.0561, -0.1550, -0.2506,
+ +0.1287, -0.0165, -0.3660, -0.1245, -0.5657, -0.2736, -0.4638,
+ +0.3541, -0.0719, +0.2303, -0.2123, +0.1793, +0.1374, +0.4679,
+ -0.3017, -0.2900, -0.0085, -0.0199, -0.0094, -0.0539, -0.4537,
+ -0.1137, +0.1031, -0.2512, -0.5477, -0.3711, +0.0679, -0.0909,
+ -0.4900, -0.0460, +0.1870, +0.5657, +0.0770, -0.1924, +0.5013,
+ +0.1926, +0.4636, -0.2005, -0.6079, -0.0038, -0.3662, -0.1998,
+ +0.2434, -0.1351, -0.1438, +0.4540, +0.3861, -0.5414, +0.1765,
+ +0.5507, +0.0502, -0.2789, +0.0302, -0.4437, +0.1469, +0.0083,
+ -0.0509, +0.0401, +0.0566, -0.3248, -0.1318, -1.5129, -0.6188,
+ -0.1140, -1.1974, +0.2079, -0.1738, +0.2441, -0.8853, +0.0682,
+ +0.0367, +0.2440, -0.6512, +0.0619, +0.2182, +0.1542, +0.2227,
+ -0.4152, +0.4476, -0.4592, +0.6061, -0.5287, +0.5690, -0.5691,
+ +0.0677, -0.2069, +0.0190, -0.1155, +0.5428, +0.4470, +0.0292,
+ +0.3965, +0.0130, +0.4818, -0.6723, -0.6049, +0.1751, -0.0091,
+ -0.0193, -0.4040, +0.1776, -0.0811, +0.5117, +0.1059, +0.2048,
+ +0.3580, +0.0120
+ ],
+ [
+ -0.1210, +0.0283, -0.2150, -0.8675, -0.1966, -0.1280, -0.3534,
+ +0.1179, -0.5637, -0.0615, -0.2321, +0.0095, +0.1918, +0.0317,
+ -0.2031, -0.1552, +0.3155, +0.4319, +0.2815, -0.0709, -0.6060,
+ -0.0318, -0.6541, -0.3911, +0.0916, +0.1339, +0.3901, -0.0215,
+ +0.3117, +0.3603, +0.3742, -0.2424, -0.2102, -0.0055, -0.1783,
+ +0.2992, -0.0213, +0.2737, +0.3640, -0.0041, -0.0435, +0.1138,
+ -0.0185, -0.0374, +0.0415, +0.4626, +0.3861, -0.2194, -0.6983,
+ +0.1617, +0.1974, -0.0364, +0.4909, +0.1799, +0.2560, +0.0741,
+ +0.0866, +0.0264, -0.4130, -0.0046, -0.5335, -0.0196, +0.3220,
+ -0.0230, +0.2521, +0.1357, -0.2103, +0.1343, +0.1675, +0.0260,
+ -0.1268, +0.2371, +0.0360, +0.2276, +0.1925, +0.2276, +0.0839,
+ +0.1985, -0.0862, +0.1063, -0.1310, +0.1342, +0.1287, -0.1455,
+ -0.3308, -0.1680, -0.5989, -0.5364, -0.0396, -0.4750, -0.0452,
+ +0.2292, -0.0566, +0.3250, -0.0889, -0.1587, +0.0793, -0.2573,
+ +0.3200, +0.4030, -0.0636, +0.4392, +0.1043, +0.0802, +0.0769,
+ +0.4630, +0.1506, +0.0572, +0.0029, -0.3777, -1.6826, -0.0892,
+ -0.7466, -0.1378, +0.3277, +0.1467, -0.0098, +0.0221, -0.1759,
+ -0.7071, +0.0824, -0.0311, -0.2508, -0.0275, -0.7920, -0.3872,
+ +0.1502, +0.2264
+ ],
+ [
+ +0.6120, +0.3405, +0.2589, +0.0686, -0.1953, +0.6403, -0.1969,
+ +0.0595, +0.1195, +0.2618, +0.1715, +0.0922, +0.1265, -0.1682,
+ +0.0085, -0.0564, -0.2752, -0.2192, +0.0928, -0.1574, +0.1297,
+ +0.1780, +0.2758, +0.0059, +0.2249, -0.2070, -0.2551, +0.0703,
+ +0.0269, -0.2630, +0.0450, +0.2389, +0.2634, -0.2034, -0.4609,
+ +0.4847, +0.5883, -0.3472, +0.2286, +0.0655, -0.6584, +0.3056,
+ +0.2531, -0.0975, -0.1207, -0.1381, -0.5765, +0.4057, -0.2481,
+ +0.1628, -0.0124, +0.1207, -0.4008, -0.1172, -0.2151, -0.0345,
+ +0.0495, +0.0189, +0.3476, +0.0653, +0.0872, -0.1548, -0.0870,
+ -0.5931, -0.1480, -0.0160, +0.3780, -0.0113, -0.1431, -0.2628,
+ -0.0559, -0.4389, +0.2481, +0.0285, +0.2956, -0.2034, -0.1550,
+ +0.0492, -0.0950, -0.1279, +0.0670, -0.2606, -0.0781, +0.1651,
+ -0.6137, -0.2109, +0.0098, -0.4534, +0.0486, +0.1961, -0.4423,
+ +0.1798, -0.1662, -0.1309, +0.2564, -0.3861, -0.0668, -0.2116,
+ -0.3516, -0.0911, +0.1962, -0.6550, -0.3101, -0.1711, -0.3370,
+ -0.2917, +0.2500, +0.2666, -0.0542, -0.4167, -0.3549, -0.0180,
+ +0.2593, +0.0414, -0.1374, +0.3264, +0.0359, -0.4018, -0.1284,
+ -0.0707, +0.3961, -0.3629, +0.5779, +0.3261, -0.1960, +0.0196,
+ +0.1802, +0.1772
+ ],
+ [
+ +0.3321, -0.0043, +0.0059, +0.1838, -0.0379, -0.6290, -0.2934,
+ -0.0023, +0.4021, +0.1333, +0.3395, +0.3662, -0.5307, +0.4866,
+ +0.1920, +0.1895, +0.1353, -0.0677, +0.0010, -0.1776, +0.0715,
+ +0.1955, +0.1733, +0.0839, +0.1278, +0.0549, -0.1681, -0.0210,
+ +0.0268, -0.2156, -0.0524, +0.0486, +0.1273, +0.0394, +0.4595,
+ +0.1428, -0.4473, -0.1574, -0.5620, +0.0088, -0.1087, -0.3781,
+ +0.0653, +0.0713, +0.0020, +0.1512, -0.0755, -0.1028, -0.0136,
+ -0.0456, -0.3270, -0.0032, +0.2283, +0.2919, +0.3500, -0.5352,
+ -0.1475, +0.2793, -0.7237, -0.3808, -1.2308, -0.2369, -0.1346,
+ -0.1291, +0.4355, -0.2403, -0.3712, +0.0012, +0.2265, +0.4574,
+ +0.0566, +0.5269, +0.3710, +0.5246, -0.0498, -0.3951, -0.4347,
+ -0.3339, -0.4218, +0.0127, -0.0504, +0.2275, -0.2729, +0.2287,
+ +0.0500, +0.2769, -0.1740, -0.3289, +0.0437, -0.1089, -0.1714,
+ -0.3370, +0.1238, -0.2227, -0.2236, -0.0241, +0.0526, -0.1371,
+ +0.0734, +0.1850, +0.1059, -0.1044, +0.1228, -0.1843, +0.1778,
+ +0.1081, +0.2087, -0.7055, +0.0547, +0.0166, +0.0231, -0.1416,
+ +0.3223, -0.1833, +0.1695, -0.2619, +0.1388, +0.2318, +0.0007,
+ -0.1106, -0.0560, +0.1814, -0.1111, -0.2346, +0.2086, -0.1681,
+ -0.4507, -0.2912
+ ],
+ [
+ -0.0355, +0.2780, -0.0415, -0.6060, +0.1641, -0.1634, -0.1836,
+ -0.2687, -0.2778, +0.3303, -0.5843, +0.2118, -0.0916, +0.1060,
+ +0.0583, +0.0854, +0.2461, -0.2423, +0.4740, +0.3551, -0.3546,
+ +0.0514, -0.1922, -0.8780, -0.1073, +0.0772, +0.1236, -0.2780,
+ +0.1447, -0.6879, +0.0313, +0.2184, -0.2200, -0.0125, +0.0931,
+ -0.1300, -0.1865, -0.4454, -0.8373, -0.0907, -0.3115, +0.0840,
+ -0.2306, -0.1615, -0.3491, +0.2386, +0.1848, -0.5184, -0.1454,
+ -0.2316, +0.2788, -0.0251, -0.0211, +0.0219, +0.1418, +0.0277,
+ -0.2427, -1.2938, -0.1140, -0.2718, -0.6272, -0.0525, +0.1877,
+ +0.2890, +0.3268, -0.0594, +0.1912, +0.4100, -0.2659, -0.0808,
+ -0.8520, -0.7808, -0.2231, +0.4269, +0.1724, +0.3903, -0.4007,
+ -0.3331, -0.1801, -0.3650, +0.0508, +0.4958, +0.2926, -0.2167,
+ -0.2007, -0.0711, +0.2235, +0.0508, -0.0419, +0.2554, +0.0702,
+ +0.0802, -0.0612, -0.0652, +0.3999, +0.4148, +0.6440, -0.1218,
+ -0.4333, -0.2390, -0.2230, +0.0354, +0.1575, +0.0190, -0.2055,
+ +0.1771, -0.7678, -0.2000, +0.1853, +0.1183, +0.0925, -0.2047,
+ -0.4217, -0.0655, -0.0234, +0.2635, +0.0828, +0.2193, -0.6872,
+ -0.3432, -0.2302, +0.1799, -0.2867, +0.0938, -0.1178, -0.0551,
+ -0.4497, -0.1970
+ ],
+ [
+ -0.5875, +0.3584, +0.1795, -0.4308, +0.3049, +0.3270, +0.3174,
+ -0.1452, -0.1415, +0.2994, -1.2432, -0.3681, +0.0554, +0.1826,
+ +0.1509, +0.6676, +0.7488, +0.0322, -0.9482, -0.0708, -0.1230,
+ +0.3096, +0.0785, -0.0805, -0.6251, +0.1364, -0.3964, -0.9179,
+ +0.4554, +0.0184, +0.5066, +0.1493, +0.0249, -0.5184, -1.4056,
+ +0.0259, +0.3481, -0.4445, +0.1686, -0.0919, -0.1951, -1.3686,
+ -0.3031, -0.7120, -0.1386, +0.3186, +0.4143, +0.1699, +0.3723,
+ -0.5573, +0.0541, +0.7135, -0.1683, +0.3588, +0.2727, -0.5074,
+ -0.7353, -1.2056, +0.1675, -0.3630, -0.0839, +0.2155, +0.3176,
+ +0.2199, +0.0528, +0.1867, -0.1459, -0.1960, -0.5922, -0.1418,
+ +0.1251, -0.2371, -0.0244, -0.3642, -0.0267, -0.3112, +0.0506,
+ +0.2327, -0.0061, +0.0202, +0.0529, -0.1410, -0.5588, -0.3405,
+ -0.1945, +0.0048, -0.2415, -0.0087, +0.0536, -0.2444, -0.3201,
+ -0.0885, +0.4312, -0.0041, -0.2366, +0.2506, +0.0255, -0.4700,
+ -0.0447, +0.1439, +0.3104, +0.1605, +0.0736, +0.1862, -0.0253,
+ -0.1050, +0.5843, +0.0937, -0.3332, -0.2927, -0.3305, +0.0606,
+ +0.3630, -0.0441, +0.3914, +0.1469, -0.3773, -0.1831, -0.4460,
+ -0.2917, -0.5101, +0.5178, +0.0635, -0.3741, +0.0059, -0.3863,
+ -0.0546, +0.2805
+ ],
+ [
+ +0.0601, -0.3253, +0.0195, -0.1363, +0.3744, +0.0671, -0.1641,
+ -0.4333, +0.4887, +0.2348, -0.1369, -0.2670, +0.1986, -0.5604,
+ -1.0478, -0.3187, -0.4200, -0.2033, -0.5111, +0.1593, +0.0223,
+ -0.2550, -0.0922, -0.2716, +0.3623, -0.1694, -0.0972, +0.1189,
+ -0.6272, -0.0722, +0.1894, -0.6329, -0.3364, -0.7210, -0.8415,
+ -0.3291, +0.0917, -0.4014, +0.2275, -0.3271, -0.2019, -0.3149,
+ +0.5368, -0.0693, +0.5510, -0.1304, -0.2988, -0.1306, +0.0359,
+ +0.1579, -0.6640, +0.1081, -1.5365, -0.1597, +0.2577, -0.0664,
+ +0.0757, +0.1524, -0.0956, -0.1541, -0.4604, -0.4904, +0.0975,
+ +0.2428, -0.1907, -0.7102, +0.6586, -0.1683, -0.0257, -0.3399,
+ -0.1199, -0.0780, +0.0957, -0.2709, +0.1472, +0.0477, +0.0115,
+ -0.1198, +0.3382, +0.4367, +0.0999, -0.6750, -0.8398, +0.0322,
+ +0.0039, -0.3979, -0.1288, -0.5003, -0.2096, -1.1291, -0.4065,
+ -0.3172, +0.1936, -0.6337, -0.6576, +0.0531, +0.4156, -0.9388,
+ -0.0643, -0.7279, -0.5641, -0.3065, +0.4290, +0.0895, -0.1019,
+ -0.3363, +0.1544, -0.0767, +0.0565, -0.7275, -0.0629, -0.8995,
+ -0.0352, -0.0069, -0.2988, -0.5636, +0.5480, -0.3188, -0.7048,
+ -0.3809, -0.1963, +0.3920, +0.1438, +0.1053, -0.2073, +0.2638,
+ -0.1706, +0.0799
+ ],
+ [
+ -0.2158, +0.0953, +0.2846, -0.2392, -0.2678, +0.0783, +0.3179,
+ -0.2224, +0.6093, -0.5543, -0.1057, -0.2840, -0.3915, -0.2513,
+ +0.1723, -0.3655, +0.0223, -0.4514, +0.0781, -0.3668, -0.0650,
+ -0.2735, -1.0161, -0.0027, -0.3664, -0.0702, -0.1575, -0.2282,
+ +0.0369, -0.0807, +0.1153, -0.0076, -0.1323, +0.4017, +0.1480,
+ +0.2383, -0.4470, +0.1887, -0.1691, +0.3031, +0.1124, -0.5467,
+ +0.0554, +0.0814, -0.4822, +0.0195, -0.3758, +0.4181, -0.4839,
+ -0.3081, +0.4140, +0.1578, +0.1257, +0.2257, -0.5583, -0.5895,
+ -0.8581, -0.3002, +0.0568, -0.3166, -0.8867, -0.0909, -0.5856,
+ -0.1936, -0.4399, +0.1872, -0.2999, +0.4525, -0.1103, +0.1011,
+ -0.1481, -0.0094, -0.2643, -0.3380, +0.5789, -0.2954, -0.4386,
+ -0.7334, +0.3065, +0.4677, -0.0934, +0.2365, +0.2516, +0.3897,
+ -0.0673, -0.0134, -0.0030, +0.1351, -0.4304, +0.0894, +0.1702,
+ -0.1998, -0.1700, -0.1687, +0.1565, -0.3954, -0.4844, -0.3194,
+ -0.5078, +0.0651, +0.1964, +0.0848, -0.1559, -0.1095, -0.3068,
+ -0.0296, -0.3526, -0.5551, -0.2015, -0.3554, -0.0166, -0.0325,
+ -0.3315, +0.6864, +0.1491, +0.4219, +0.4374, -0.1169, -0.2291,
+ +0.5127, -0.3610, -0.4966, +0.4471, +0.0802, -0.5580, -0.5791,
+ -0.1772, +0.2302
+ ],
+ [
+ -0.1076, +0.1499, -0.0961, -0.2042, +0.2166, -0.2431, +0.0062,
+ -0.7276, -0.1863, -0.3058, -0.2379, +0.1921, -0.4037, +0.0759,
+ -0.1372, -0.1939, -0.2092, -0.7652, -0.0190, +0.3077, -0.0457,
+ -0.0271, -0.5684, +0.0415, +0.0116, -0.8223, +0.3359, -0.1225,
+ +0.1816, +0.2140, +0.1602, -0.1146, -0.1266, -0.0036, -0.7904,
+ -0.2256, -0.1559, -0.2645, +0.0860, -0.0661, -0.2869, -0.6140,
+ -0.0998, +0.2239, -0.1742, +0.2176, +0.3107, +0.0136, -0.1963,
+ +0.5052, +0.0713, -0.3807, +0.2308, -0.5190, +0.1811, -0.1509,
+ +0.1385, -0.0837, +0.1361, -0.2535, +0.1506, -0.3724, +0.0996,
+ +0.1964, +0.1111, -0.0517, -0.0306, +0.1187, +0.1788, -0.0407,
+ -0.1487, -0.0854, +0.2843, -0.0753, -0.0068, -0.0077, -0.3471,
+ +0.0351, -0.6159, -0.4226, +0.5148, +0.0071, -0.7155, +0.2349,
+ -0.0137, +0.1020, -0.0478, -0.0962, -0.3094, +0.0115, +0.0320,
+ +0.1118, -0.0642, -0.6710, -0.0404, +0.2625, -0.1370, +0.0298,
+ -0.0184, -0.1681, +0.0445, +0.0099, +0.0830, +0.2498, +0.3416,
+ -0.2665, +0.1916, +0.0037, -0.6989, -0.3035, -0.5451, -0.0226,
+ +0.1792, +0.2112, +0.1199, -0.4196, +0.3648, +0.1852, +0.1674,
+ +0.3833, +0.4238, +0.2341, -0.1482, -0.0028, +0.1002, -0.2465,
+ +0.0602, +0.2140
+ ],
+ [
+ +0.0213, +0.1944, -0.1501, -0.7898, -0.0269, -0.1696, -0.1227,
+ +0.3991, +0.3180, -0.0466, +0.5871, +0.0320, +0.3256, +0.0336,
+ -0.3113, -0.0198, -0.1346, -0.6108, -0.1094, -0.5958, -0.0453,
+ -0.5481, -0.1500, -0.0589, +0.0894, +0.1282, -0.6472, -0.0027,
+ -0.2055, +0.2224, +0.1027, +0.1256, -0.0334, -0.1769, -0.0391,
+ -0.3949, +0.1055, +0.2503, -0.1800, -0.3791, -0.2318, -0.0518,
+ -0.1476, +0.1280, +0.0072, -0.0926, -0.0673, +0.2434, -0.3668,
+ -0.9051, -0.1701, +0.0967, +0.0836, -0.0320, +0.0400, +0.0664,
+ -0.2545, -0.2088, +0.0896, -0.3086, -0.1286, -0.1372, +0.3918,
+ +0.2618, -0.1957, -0.2447, -0.3575, -0.3319, +0.6881, -0.1629,
+ +0.0188, -0.3465, -0.1682, +0.2730, -0.1074, -0.0268, -0.2431,
+ +0.0457, +0.4783, +0.2920, -0.8347, +0.0237, +0.0183, +0.2163,
+ +0.2028, +0.0512, +0.3901, +0.3220, +0.1953, +0.2893, +0.1298,
+ +0.1812, -0.4022, -0.2563, -0.1943, +0.0630, -0.3236, +0.3854,
+ -0.0505, +0.0693, +0.0277, -0.5653, -0.0168, +0.0141, -0.2540,
+ -0.5629, -0.0544, -0.1690, +0.2695, -0.5674, +0.4644, +0.5105,
+ -0.0195, -0.4197, +0.0466, -0.3659, +0.3466, -0.1359, -0.2359,
+ -0.3740, +0.2405, +0.1225, -0.5024, +0.0566, -0.8196, -0.1433,
+ +0.0337, +0.0528
+ ],
+ [
+ -0.6809, +0.2662, -0.5515, +0.0274, +0.4504, +0.3657, -0.0369,
+ -0.0298, +0.0075, -0.1811, +0.1554, -0.5186, +0.5404, -0.3754,
+ -0.3679, -0.0857, +0.0986, -0.5003, +0.1381, -0.2794, -0.4324,
+ +0.0690, -0.3677, +0.0815, -0.0896, -0.6115, +0.3429, -0.1858,
+ -0.1057, -0.4543, +0.1465, -0.1958, +0.0853, -0.1470, +0.1513,
+ -0.2316, +0.2884, -0.4537, -0.3710, -0.0103, +0.2550, -0.1489,
+ -0.2394, -0.2326, +0.0281, -0.1502, +0.0989, +0.2860, -0.1225,
+ -0.4216, +0.3528, -0.2252, +0.0390, -0.5138, -0.2122, -0.0263,
+ +0.1364, -0.4858, +0.3086, +0.1359, +0.3356, -0.6935, -0.6898,
+ +0.2928, -0.2900, +0.4967, +0.1789, +0.0129, -0.0865, +0.1469,
+ +0.1938, +0.3798, +0.1427, -0.3017, +0.5246, -0.0486, -0.5537,
+ -0.0919, -0.1737, +0.0380, -0.0290, -0.3807, -0.6776, -0.2915,
+ -0.0784, -0.2607, +0.0507, -0.0996, -0.0567, +0.3834, -0.0326,
+ +0.1360, +0.0460, -0.1078, +0.4804, +0.2062, +0.3488, -0.1236,
+ +0.3503, +0.0557, -0.0188, +0.2796, -0.0616, -0.0295, -0.3695,
+ +0.1613, -0.2866, +0.3682, -0.1529, -0.0211, -0.8208, -0.5679,
+ +0.3730, +0.2508, -0.0373, -0.5967, +0.2355, -0.0826, -0.1477,
+ -0.4036, +0.0439, +0.3214, -0.0763, +0.1182, -0.1230, -0.0080,
+ +0.0365, -0.3488
+ ],
+ [
+ +0.1278, +0.3544, -0.0588, -0.9237, +0.1073, +0.2965, +0.5606,
+ +0.1852, -0.4272, -0.6675, -0.2859, -0.7539, +0.0184, +0.0534,
+ -0.8694, -0.1548, +0.2093, +0.0162, -0.2391, -0.3411, +0.2604,
+ -1.3084, +0.3698, -0.0768, -0.0322, +0.0754, -0.0044, +0.1771,
+ -0.1628, +0.4309, +0.0774, -0.0721, -0.2629, -0.0708, -0.3502,
+ -0.0600, +0.1463, -0.5095, -1.0829, -0.9172, +0.2253, +0.1346,
+ -0.1799, -0.0397, -0.1397, +0.0269, -0.2786, +0.1675, -0.3110,
+ +0.0059, +0.3807, +0.1454, +0.0373, -0.0626, -0.0482, +0.3647,
+ -0.1477, +0.4116, +0.1811, -0.3096, +0.1492, -0.0770, -0.1550,
+ +0.3186, -0.5793, -0.0217, +0.1216, +0.0893, -1.0605, -0.0276,
+ -0.3422, +0.0822, -0.4680, +0.2439, -0.3746, +0.0006, -0.2558,
+ +0.1921, -0.0572, -0.0718, -0.5186, +0.0136, -0.7412, -0.2912,
+ -0.1026, -0.3082, -0.0322, -0.1574, +0.0616, +0.1399, -0.5695,
+ -0.5556, -0.1188, +0.0646, -0.4050, +0.3945, +0.4077, +0.1311,
+ -0.8293, -0.0814, -0.7487, +0.0789, +0.2741, +0.1798, +0.1800,
+ +0.0221, +0.2849, +0.1241, +0.0981, -0.0291, +0.0349, -0.2348,
+ -1.1890, +0.2165, -0.2498, +0.3480, -0.1510, -0.0254, +0.4350,
+ -0.2413, -0.2154, +0.1620, +0.3549, +0.1094, +0.3039, -0.1670,
+ -0.5215, +0.2193
+ ],
+ [
+ -0.5056, -0.2717, -0.0887, +0.1180, +0.2221, -0.0533, +0.3635,
+ +0.0107, -0.0155, -0.3851, -0.0780, +0.4512, -0.0052, -0.2470,
+ -0.0436, -0.3644, +0.2348, -0.3132, -0.1388, -0.3696, -0.2221,
+ -0.1212, -0.1152, +0.1401, +0.2334, -0.2287, -0.0463, +0.0870,
+ -0.1798, +0.0395, -0.8861, -0.8117, +0.0519, -0.0148, -0.1086,
+ +0.2235, -0.2144, -0.2035, +0.3049, +0.2782, -0.0790, -0.3271,
+ +0.1502, +0.0752, +0.1874, -0.2961, -0.1831, -0.1052, -0.1899,
+ -0.1599, -0.2232, -0.0929, +0.1634, +0.2954, +0.1783, +0.1850,
+ +0.0323, +0.1821, -0.1331, -0.0664, +0.2822, -0.3062, -0.2497,
+ -1.2594, -0.3746, +0.1056, +0.2596, +0.0462, +0.2250, -0.5202,
+ -0.2983, -0.3262, -0.2862, -0.4389, +0.1809, +0.1076, +0.2707,
+ +0.4548, -0.0305, -0.0603, +0.0805, -0.3495, -0.3292, -0.4320,
+ +0.2417, +0.1606, +0.3576, -0.0476, -0.3210, +0.1739, +0.3417,
+ -0.2769, -0.1329, +0.6614, +0.1064, -0.5903, +0.3824, -0.0035,
+ -0.1594, -1.0897, +0.1392, -0.0113, -0.0069, +0.3172, +0.1027,
+ -0.1457, -1.0550, +0.2104, -0.8771, +0.1007, -0.3465, +0.3272,
+ +0.0404, +0.0174, +0.3485, -0.2760, +0.0764, -0.0402, +0.1597,
+ +0.4512, +0.4985, -0.8222, -0.5071, +0.0934, -0.1479, -0.6469,
+ -0.1912, +0.2672
+ ],
+ [
+ +0.5416, -0.0218, -0.0531, +0.0453, +0.1252, -0.1311, +0.2916,
+ -0.0341, +0.3304, +0.0958, +0.0507, -0.2015, -0.2878, -0.5418,
+ -0.0068, +0.0552, +0.0864, +0.4119, +0.0150, -0.0622, +0.0781,
+ -0.4440, -0.5189, +0.0631, +0.0681, -0.0632, -0.1314, -0.0119,
+ -0.0225, -0.1634, -0.3359, +0.1974, -0.2654, -0.1948, -0.0087,
+ +0.0303, +0.4607, +0.1021, +0.0181, -0.0214, +0.1044, +0.0861,
+ +0.3070, -0.2432, +0.1628, +0.0187, -0.9277, +0.1928, -0.6063,
+ +0.3662, -0.1792, -0.0239, -0.0632, -0.6483, +0.3550, -0.1499,
+ -0.0971, +0.2099, +0.2688, -0.0530, +0.1171, +0.5035, -0.8688,
+ -0.3405, -0.2476, +0.4547, -0.4105, -0.1177, -0.3137, +0.1011,
+ +0.0825, -0.3973, +0.1754, +0.2616, -0.1194, -0.0725, -0.2332,
+ -0.5832, -0.1741, -0.4962, +0.1793, -0.3603, +0.5548, -0.2168,
+ -0.4409, +0.2611, -0.1732, -0.2258, +0.4478, +0.2887, -0.6937,
+ +0.4469, -0.1434, +0.2411, -0.0069, -0.8774, -0.2686, -0.0973,
+ +0.1061, -0.0011, -0.0416, -0.2424, +0.1575, +0.1909, -0.6973,
+ -0.0013, -0.0070, -0.2964, +0.1380, +0.5137, -0.0704, -0.2486,
+ -0.1062, +0.1285, -0.3033, +0.0060, -0.1700, -0.0587, +0.1942,
+ +0.3036, +0.2824, -0.8177, -0.6379, +0.4813, +0.0342, -0.1333,
+ +0.0801, +0.4477
+ ],
+ [
+ -0.0211, +0.2675, +0.3353, -0.3372, -0.1233, +0.2106, +0.0731,
+ -0.1431, -0.1459, +0.2807, -0.2799, -0.2038, -0.1239, -0.4392,
+ +0.2931, +0.4137, -0.2620, -0.1753, +0.4271, -0.1496, -0.3291,
+ +0.3312, +0.1065, +0.1967, +0.3853, -0.0131, +0.3213, -0.1285,
+ -0.6470, -0.2297, -0.1128, +0.3138, -0.2046, -0.0544, +0.2242,
+ -0.1240, +0.2349, -0.4463, -0.3117, -0.1976, -0.5940, +0.5098,
+ +0.0314, +0.1411, -0.1443, -1.3227, -0.0915, +0.0622, +0.3047,
+ -0.6741, -0.0068, +0.1571, +0.0197, +0.3689, +0.2350, -0.7219,
+ -0.3110, -0.3136, +0.1014, +0.1670, -0.0109, -0.1335, -0.1780,
+ +0.2741, -0.5067, -0.0343, -0.2735, -0.1306, +0.0644, -0.0421,
+ -0.3508, -0.0239, -0.0895, +0.7201, -0.4332, -0.2279, +0.3636,
+ +0.4006, +0.0258, +0.0039, +0.0240, +0.0969, +0.1108, -0.3942,
+ -0.0191, -0.0833, -0.0460, -0.0104, -0.3314, -0.3009, -0.2580,
+ -0.0891, -0.4601, +0.0273, -0.6587, +0.0187, +0.1647, +0.2728,
+ -0.3057, -0.6602, +0.2252, +0.0499, +0.0645, -0.3887, +0.0085,
+ +0.2773, -0.2943, +0.0106, -0.1876, +0.1680, +0.4481, -0.6070,
+ -0.3804, +0.0686, -0.1384, +0.0941, -0.2830, -0.3419, +0.5389,
+ +0.0071, +0.0309, +0.3877, -0.2346, -0.2765, +0.3154, +0.5432,
+ +0.1597, -0.0707
+ ],
+ [
+ -0.3307, +0.0719, -0.4069, -0.4818, -0.0336, +0.2526, +0.0127,
+ +0.1715, +0.1634, -0.1317, -0.0556, -0.6635, +0.0385, -0.1778,
+ -0.6021, +0.0995, -0.3965, +0.5307, +0.2085, +0.0421, -0.2732,
+ -0.4179, -0.3875, -0.2914, +0.0900, +0.1833, +0.2219, -0.4152,
+ +0.4455, -0.3731, -0.2920, -0.0412, +0.0676, -0.4575, -0.5457,
+ -0.3103, -0.1316, -0.6066, -0.0151, -0.2290, -0.5575, +0.4713,
+ +0.0446, +0.1031, -0.0860, +0.1306, -0.5180, -0.0828, -0.0814,
+ -0.0137, -1.1862, -0.0610, -0.0665, -0.4811, +0.0875, -0.1226,
+ -0.1726, +0.1026, +0.2877, -0.2522, -0.8006, +0.0242, -0.6489,
+ -0.1083, +0.1570, -0.0922, -0.5692, +0.2164, -0.0050, +0.0594,
+ +0.3049, -0.1859, -0.8103, -0.2647, -0.1506, -0.3981, -0.0826,
+ +0.2345, +0.3153, -0.3429, +0.0491, -0.1324, -0.2087, -0.0861,
+ -0.8154, -0.0180, +0.2558, -0.2299, +0.0994, +0.0263, -0.8396,
+ +0.1073, +0.1554, -0.3760, +0.0870, -0.0737, -0.3097, -0.1488,
+ -0.0324, -0.2025, +0.3044, +0.1957, -0.0953, -0.1347, -0.6328,
+ +0.0435, -0.3573, -0.6667, -0.0919, -1.0430, -0.0192, -0.1639,
+ +0.4036, -0.1974, -0.5038, -0.0258, +0.2064, +0.2843, +0.0147,
+ -0.0562, -0.1918, -0.3606, -0.4848, -0.1829, -0.3000, +0.0925,
+ -0.2469, -0.0005
+ ],
+ [
+ -0.1075, +0.0796, -0.0946, -0.4344, +0.2005, -0.1093, -0.0906,
+ -0.3207, -0.2558, -0.0439, +0.5002, -0.5107, -0.3569, -0.2400,
+ -0.9696, +0.1216, +0.1939, -0.0901, +0.0303, -0.5634, -0.0879,
+ -0.0478, -0.6500, -0.1287, -0.0194, -0.4115, +0.1487, -0.3913,
+ +0.2391, +0.2528, +0.1589, +0.1568, -0.2328, -0.3401, -0.3910,
+ -0.4641, -0.3274, -0.2689, -0.5790, -0.2490, -0.3726, +0.1373,
+ -0.3168, +0.1565, +0.0834, -0.1442, +0.0261, +0.0699, -0.5031,
+ +0.1383, -0.3060, +0.0458, -0.1907, -0.1535, -0.0182, -0.2781,
+ -0.0593, -0.3813, +0.2376, +0.0838, +0.0307, +0.1134, +0.0186,
+ +0.0102, +0.0446, -0.0612, +0.2964, +0.0673, +0.4004, -0.1744,
+ +0.2707, -0.0061, +0.3257, -0.8955, -0.0757, -0.6494, -0.1417,
+ -0.2841, +0.1827, +0.0669, -0.2435, +0.0048, -0.3185, -0.2073,
+ +0.2819, +0.0463, -0.2587, +0.1456, -0.1462, -0.1835, -0.3942,
+ +0.1628, +0.4768, -0.3747, +0.0178, +0.1807, -0.1081, +0.0570,
+ -0.1036, +0.3498, -0.3699, +0.1021, -0.5282, -1.1311, -0.1090,
+ +0.3226, -0.4719, -0.1089, -0.4208, +0.4415, -0.5734, -0.4619,
+ +0.3115, +0.3256, +0.1768, -0.3252, -0.7296, +0.6043, -0.3889,
+ +0.1948, -0.1121, -0.3825, -0.3001, +0.0001, -0.3872, -0.0690,
+ +0.2413, +0.2725
+ ],
+ [
+ -0.1956, +0.4824, +0.0299, +0.0923, -0.1255, -0.0784, +0.1399,
+ -0.0119, +0.2045, +0.1789, -0.0844, +0.0612, +0.0869, -0.1022,
+ +0.1522, +0.1175, -0.3761, -0.8891, +0.1135, -0.1164, -0.0650,
+ -0.4960, -0.0575, +0.3796, -0.4186, +0.5628, -0.0502, -0.2575,
+ -1.6787, -0.1565, -0.3031, +0.2404, -1.0437, -0.0959, -0.1703,
+ +0.1407, +0.1496, +0.1953, -0.0319, +0.3103, +0.1761, +0.0003,
+ -0.5419, -0.6587, +0.0537, +0.2545, -0.3464, +0.0076, -0.1283,
+ -0.4792, +0.1090, -0.2502, +0.0810, +0.5328, -0.2368, -0.2101,
+ -0.0410, -0.0465, -0.0782, -0.0789, -0.1115, +0.0534, -0.0064,
+ -1.3387, +0.2155, -0.0807, -0.3716, -0.1701, +0.0104, +0.0665,
+ -0.0696, -0.6764, -0.0896, +0.1293, +0.2936, -0.2979, +0.1135,
+ +0.1420, +0.2191, +0.0649, -1.5397, +0.0106, -0.0295, +0.0041,
+ +0.1493, +0.2680, -0.1745, +0.0864, +0.0223, +0.1098, +0.1272,
+ +0.1090, -0.3073, +0.0846, -0.1849, +0.2400, +0.0479, -0.1117,
+ -0.3259, +0.2560, -0.8979, -0.2436, -0.2723, +0.0895, +0.2896,
+ +0.5229, +0.3580, +0.2622, +0.1865, -0.0928, -0.1333, -0.0331,
+ -0.2025, +0.0284, +0.0933, -0.4256, +0.1458, -0.0047, +0.2814,
+ -0.5681, -0.1660, -0.0740, -0.3705, -0.1294, -0.2887, -0.1671,
+ -0.3191, +0.0041
+ ],
+ [
+ -0.0429, -0.2979, -0.8061, +0.0274, +0.1359, -0.0807, +0.2634,
+ -0.1513, -0.1274, -0.0166, -0.2593, -0.0043, -0.3913, -0.4622,
+ -1.0735, -0.2252, -0.3954, -0.2352, +0.1754, -0.3066, -0.5369,
+ -0.2073, -0.0621, -0.2404, +0.1481, +0.1076, -0.2903, +0.0644,
+ +0.3461, -0.8494, -0.2225, -0.4445, +0.0074, +0.1606, -0.2494,
+ +0.1894, -0.4898, +0.2003, -0.8726, +0.1727, +0.4279, +0.0250,
+ -0.2323, -0.4568, -0.9386, +0.4602, -0.0544, -0.6053, -0.3673,
+ -0.2031, -0.2869, -0.0142, -0.1154, -0.0311, +0.3106, -0.1357,
+ -0.0287, -0.6635, +0.0821, -0.7078, -0.8762, -0.4313, -1.1641,
+ +0.1237, -0.2846, -0.7949, -0.8328, +0.1506, +0.3018, -0.0569,
+ +0.3055, -0.2692, -0.8944, -0.6283, +0.0082, +0.1982, +0.2366,
+ -0.2263, +0.1205, -0.3662, -0.0564, -0.8527, -0.0458, -0.2136,
+ -0.8190, +0.3705, +0.1591, +0.0972, +0.1972, +0.1188, +0.1552,
+ -0.0021, -0.3104, -0.0915, +0.0861, -0.0970, -0.1669, -0.2250,
+ +0.1361, -0.2040, -0.1728, +0.0874, -0.4176, -0.0232, +0.2895,
+ -0.3241, -0.2774, -0.6778, +0.0860, -0.1810, -0.2635, -0.3905,
+ +0.2894, -0.5524, -0.5900, +0.0042, -0.1872, +0.0342, -0.1982,
+ -0.3431, -0.2942, -0.1713, -0.3947, -0.0634, -0.2148, -0.3236,
+ -0.6599, -0.4746
+ ],
+ [
+ +0.1139, +0.0650, -0.2456, -0.1315, +0.1407, +0.0788, -0.1801,
+ +0.4116, +0.0631, +0.3614, +0.1779, +0.2011, +0.1047, +0.1695,
+ +0.0276, -0.1528, -0.1153, -0.3329, +0.1846, -0.2067, -0.1040,
+ -0.3134, -0.0784, -0.0427, +0.2053, +0.1852, -0.2523, +0.0244,
+ -0.1028, -0.4057, -0.4726, -0.4021, +0.1813, -0.1851, +0.1457,
+ -0.4243, +0.2401, -0.1664, +0.4241, +0.1109, +0.0009, +0.4179,
+ -0.0435, +0.0391, -0.1372, +0.1172, -0.4394, +0.2111, -0.4688,
+ +0.0953, -0.8070, -0.0438, -0.1590, -0.5387, -0.0352, +0.1419,
+ +0.3123, +0.4866, -0.3642, -0.1444, +0.2279, +0.1875, +0.2849,
+ -0.0600, +0.4420, +0.3253, -0.2210, +0.0820, +0.0518, +0.2397,
+ -0.6165, +0.2275, -0.0655, -0.5054, +0.1406, +0.0747, -0.2759,
+ +0.2004, +0.2437, -0.9419, +0.1028, +0.0414, +0.1167, +0.0623,
+ +0.2964, -0.1441, -0.2434, -0.0737, -0.0669, +0.4142, -0.3767,
+ -0.4335, -0.2037, -0.4858, +0.1892, -0.0506, +0.1072, +0.0308,
+ -0.0045, +0.1688, +0.0354, -0.1328, -0.0729, +0.1582, -0.7064,
+ -0.2073, +0.1505, +0.1551, -0.4480, +0.3366, -0.0612, -0.4353,
+ +0.0585, +0.0633, -0.0932, -0.0445, +0.0806, +0.1299, -0.0159,
+ +0.3052, +0.2307, -0.1101, -0.0202, +0.0697, -0.5824, -0.0746,
+ +0.4108, -0.0447
+ ],
+ [
+ +0.0791, +0.1980, -0.7039, +0.0263, +0.2395, +0.6237, +0.2502,
+ -0.5161, +0.2494, -0.2117, +0.1475, +0.0525, -0.4173, -0.3249,
+ +0.2539, -0.1223, -0.0348, -0.2279, +0.2262, +0.0258, -0.3077,
+ +0.2887, +0.3885, +0.1906, +0.2463, +0.3811, -0.6282, +0.0522,
+ +0.5306, -0.4458, -0.1445, -0.3747, -0.0662, +0.2248, -0.1537,
+ -0.2953, +0.0561, -0.2883, -0.5619, +0.0355, -0.2044, +0.1899,
+ -0.0981, -0.2455, +0.0141, +0.0599, -0.0083, +0.0112, -0.2022,
+ -0.2484, -0.4551, -0.3796, +0.0054, +0.0155, -0.1069, -0.0031,
+ -0.4725, +0.2876, +0.0632, -0.6091, +0.0202, +0.0060, +0.4156,
+ -0.3036, -0.0778, +0.2482, -0.8074, +0.2175, -0.2130, +0.2723,
+ +0.1917, -0.1859, +0.3197, -0.1314, -0.1503, +0.1386, +0.1615,
+ -0.5322, -0.4531, -0.2186, -0.0994, -0.4077, +0.4061, -0.0434,
+ -0.2415, -0.6183, -0.0757, -0.2556, -0.2224, +0.0449, +0.4767,
+ -0.0516, -0.1578, -0.5435, -0.3362, +0.5258, -0.0355, -0.0297,
+ +0.3339, +0.0571, -0.1741, +0.4465, +0.2506, -0.6265, -0.4877,
+ +0.2635, -0.1913, -0.0469, +0.2758, -0.1095, +0.1190, -0.0785,
+ +0.0585, +0.3044, -0.4372, -0.4773, -0.4492, +0.2806, -0.5223,
+ +0.4161, -0.3399, +0.0181, +0.0459, +0.0355, -0.2409, +0.3043,
+ -0.5086, -0.3526
+ ],
+ [
+ +0.3889, -0.1236, +0.3455, +0.0586, +0.1031, -0.0423, +0.2450,
+ +0.3118, -0.0065, -0.2184, -0.1482, -0.3720, +0.2949, +0.2279,
+ -0.0590, -0.1256, +0.0081, -0.0231, -0.0424, -0.0446, -0.0472,
+ -0.0739, +0.0330, +0.2615, +0.0390, +0.0315, -0.8050, -0.0950,
+ -0.0147, -0.0005, -0.4977, +0.1281, -0.4847, -0.0590, +0.2566,
+ +0.0080, +0.3070, +0.0687, -0.3527, -0.0516, -0.0147, -0.1813,
+ +0.3453, -0.0237, +0.1650, -0.5538, -0.2602, -0.4506, +0.0339,
+ -0.2247, +0.0678, +0.3342, -0.1982, -0.0218, +0.1906, +0.1715,
+ +0.0353, -0.0505, +0.3488, +0.1096, +0.1575, -0.1131, -0.0731,
+ +0.0549, +0.2869, +0.0115, +0.5333, -0.3713, -0.3464, +0.1477,
+ -0.0973, -0.5280, +0.0714, +0.2884, +0.1430, +0.1944, +0.2250,
+ +0.2365, +0.3119, +0.0493, -0.2922, +0.2082, -0.2683, -0.2334,
+ -0.0036, -0.1826, +0.0553, +0.0514, +0.0699, +0.4359, -0.0839,
+ -0.1283, -0.5059, +0.0360, +0.4593, -0.2900, +0.3191, -0.0913,
+ -0.0334, -0.0426, -0.2070, -0.0938, +0.1743, -0.0897, +0.0871,
+ +0.0905, -0.4720, -0.0107, +0.3723, -0.0417, -0.1012, -0.0172,
+ -0.3901, -0.3876, +0.1151, +0.0425, -0.3587, +0.0249, +0.0674,
+ -0.2577, +0.1353, -0.1724, +0.1267, -0.2325, +0.0940, +0.4211,
+ +0.2862, -0.4374
+ ],
+ [
+ -0.3170, +0.3755, -0.0338, -0.6477, -0.1268, +0.4264, -0.2412,
+ -0.3584, -0.4816, -0.0234, -0.4274, -0.0597, +0.4883, -0.4695,
+ -0.0844, +0.2464, -0.1324, -0.1116, +0.3023, +0.2658, +0.1502,
+ +0.0145, -0.1165, +0.0199, +0.0481, +0.2250, +0.2717, +0.0514,
+ -0.5709, -0.8578, -0.5535, -0.1945, -0.1825, -1.0669, -0.0163,
+ +0.2724, -0.1275, +0.4192, -0.0253, -0.0427, -0.1992, +0.2067,
+ +0.3362, +0.0737, -0.8661, -0.2856, -0.2030, +0.0765, -0.1862,
+ -0.7112, +0.0424, +0.3103, -0.0769, +0.2623, +0.1757, +0.0937,
+ +0.2951, +0.0081, -0.2650, +0.4250, -0.0401, +0.0961, +0.4578,
+ -0.1580, +0.2566, -0.1072, +0.0640, -0.2257, +0.1407, -0.2923,
+ -0.0112, -0.3022, -0.2181, -1.1515, +0.5188, +0.1174, +0.2920,
+ -0.1971, +0.0040, +0.0855, -1.0107, -0.2752, -0.3839, -0.2948,
+ -0.0194, +0.2019, -0.4102, -0.3485, -0.4294, +0.1244, -0.0475,
+ +0.0760, -0.0122, +0.0635, -0.4242, +0.1172, -0.1831, +0.2975,
+ -0.0734, +0.0206, -0.6166, +1.0285, -0.8004, +0.2025, -0.3087,
+ +0.0608, -0.0776, +0.4676, -0.6982, +0.0874, +0.3236, -0.1107,
+ -0.2018, +0.0993, -0.1123, +0.5077, -0.2170, -0.8204, -0.2160,
+ -0.1872, +0.6235, +0.2099, +0.0830, +0.5081, -0.3071, -0.3446,
+ -0.2227, -0.3825
+ ],
+ [
+ -0.1874, -0.1186, -0.6802, +0.0035, +0.1394, -0.3427, +0.1561,
+ -0.0044, -0.4163, -0.6432, +0.0009, +0.0743, +0.0019, +0.3348,
+ -0.1833, +0.0599, -0.0237, -0.8147, -0.5931, +0.0681, +0.3820,
+ -0.4131, -0.5803, +0.5772, -0.1047, -0.1667, -0.0174, -0.4283,
+ -0.0115, -0.2094, +0.3176, -0.4656, +0.1398, -0.2553, +0.3680,
+ -0.2766, -0.0749, +0.3381, +0.6150, -0.5616, +0.5847, -0.2923,
+ -0.0928, +0.2362, -0.4309, +0.2479, +0.3509, +0.0306, -0.0601,
+ -0.0772, -0.4807, -0.0940, +0.0597, +0.2288, -0.2230, -0.1378,
+ -0.0027, +0.1361, +0.1256, -0.0968, -0.4223, -0.1213, -0.0766,
+ -0.3987, +0.4523, +0.1027, +0.0623, +0.1629, +0.0932, -0.1068,
+ -0.0629, -0.2282, -0.1594, -0.2082, -0.4811, +0.2055, +0.3540,
+ +0.0748, +0.1092, -0.3655, -0.1293, +0.5093, +0.2215, -0.3072,
+ +0.2241, -0.0072, -0.2497, -1.0213, +0.1769, -0.1960, -0.5724,
+ -0.1859, +0.2190, -0.4151, +0.4209, -0.1399, -0.2326, +0.1927,
+ +0.1507, -0.3548, -0.2342, +0.3334, -0.4695, -0.0160, +0.0182,
+ -0.0142, +0.0374, -0.4114, -0.7137, -0.0206, -0.9733, -0.2071,
+ +0.1435, +0.0653, -0.2332, -0.5594, -0.0698, +0.1158, +0.3619,
+ +0.0128, -0.1712, +0.5550, -0.0249, -0.2328, -1.0144, +0.0697,
+ +0.2297, -0.0154
+ ],
+ [
+ +0.1416, +0.2309, +0.1272, +0.3941, -0.1264, +0.0519, +0.0873,
+ +0.1319, +0.2100, +0.5420, +0.0346, +0.1919, -0.0527, +0.2655,
+ -0.0654, +0.0043, +0.3115, +0.4582, +0.3955, +0.0363, -0.3897,
+ +0.2471, -0.1910, -0.3071, +0.0255, +0.1280, -0.0897, +0.4849,
+ +0.1039, -0.2925, -0.0640, +0.1888, +0.1011, -0.2415, +0.3240,
+ -0.7261, +0.4590, -0.3333, +0.2433, +0.1094, -0.1727, -0.0460,
+ -0.2958, -0.1053, -0.0891, -0.0464, +0.0229, -0.1550, -0.2716,
+ +0.0343, +0.0671, +0.0667, -0.4367, +0.2242, +0.0838, +0.1480,
+ -0.1503, +0.1468, -0.0787, +0.1684, +0.5497, +0.3268, +0.0520,
+ -0.3957, +0.3271, +0.0407, -0.0103, -0.6582, -0.4209, +0.2281,
+ +0.2063, +0.1261, -0.0853, +0.1172, +0.2424, +0.2464, -0.3707,
+ +0.2101, +0.1751, +0.1536, -0.3106, -0.2551, -0.3719, -0.4328,
+ -0.5526, +0.3865, -0.0679, +0.4122, +0.0144, +0.5162, +0.3118,
+ -0.0527, -0.5021, -0.0328, -0.0653, +0.2858, +0.3345, -0.1361,
+ +0.2132, +0.0117, +0.1889, -0.1802, -0.0858, +0.2928, -0.3164,
+ +0.0148, -0.3775, -0.1734, +0.0018, +0.2143, +0.2750, -0.4583,
+ -0.3690, +0.0197, -0.0628, -0.0013, -0.3150, -0.0254, +0.1141,
+ +0.1115, -0.0689, +0.2310, -0.3745, -0.1398, -0.5079, +0.0076,
+ +0.1439, -0.2340
+ ],
+ [
+ -0.0705, +0.2175, -0.3332, -0.1569, -0.1880, -0.0037, +0.1646,
+ +0.1630, -0.6191, -0.8408, -0.3053, -0.1745, +0.0026, +0.4307,
+ -0.4499, -0.1112, -0.0265, +0.2433, -0.0564, +0.2633, -0.2392,
+ -0.0076, -0.3069, -0.4411, +0.1402, -0.6455, +0.3210, +0.0260,
+ -0.3119, +0.5672, -0.0835, -0.5722, -0.6016, +0.1153, +0.1611,
+ -0.7369, -1.3666, +0.0773, -0.0642, -1.0518, +0.0271, +0.1978,
+ -0.2372, +0.6399, +0.0095, -0.1786, -0.8306, +0.1600, +0.0155,
+ -0.0362, -0.3337, -0.6398, -0.5897, -0.0730, +0.2387, -0.2654,
+ +0.2886, -0.0430, -0.1995, +0.8904, +0.4374, -0.5649, -0.1457,
+ +0.4233, +0.5757, -0.1515, -0.6817, +0.2119, -1.2438, +0.0547,
+ -0.8169, -0.2639, +0.0272, -0.0893, +0.2654, -0.0196, +0.2261,
+ -0.5399, +0.5351, -0.0945, -0.2289, -0.8261, +0.4079, +0.3965,
+ -0.3613, -0.3296, -0.1655, -0.3622, +0.4279, -0.0974, -0.6180,
+ -0.2898, +0.2287, -1.0311, +0.5108, -0.5468, -0.5000, -0.0666,
+ +0.6999, +0.0559, +0.0413, -0.5421, -0.3508, +0.6266, -0.4022,
+ -0.8094, -0.6987, -0.0470, -0.2295, -0.0360, +0.0580, -0.6328,
+ -0.5165, -0.6991, -0.1251, -0.3032, -0.8044, -0.0751, +0.1579,
+ +0.2006, +0.4040, -0.0811, +0.3109, -0.0211, -0.1546, +0.1875,
+ -0.0905, +0.0186
+ ],
+ [
+ -0.1124, -0.0259, -1.0389, -0.2415, -0.1909, -0.0094, +0.1439,
+ -0.2701, -0.2011, +0.1145, +0.1781, +0.0553, -0.2120, -0.2954,
+ +0.3016, -0.0922, -0.3145, +0.2040, +0.0703, -0.2844, -0.0642,
+ +0.4545, +0.0644, -0.1845, -0.0994, -0.8798, -0.1192, -0.5188,
+ +0.0076, -0.2705, +0.1672, +0.4707, -0.0896, +0.3602, -0.4464,
+ -0.1122, +0.1324, -0.1451, +0.1014, +0.0307, -0.9547, +0.0565,
+ -0.1124, -1.5838, +0.0327, -1.1211, -0.2453, +0.1526, -0.2564,
+ -0.0585, +0.2328, +0.0004, +0.0644, +0.4235, +0.3800, -0.0384,
+ +0.0893, +0.0122, -0.4679, -0.2261, -0.4993, +0.4685, -0.0971,
+ -0.1161, -0.1099, -0.1286, -0.3552, -0.5843, +0.0891, -0.7263,
+ -0.2820, -0.0843, -0.2338, +0.0958, -0.4697, -0.1636, +0.2075,
+ -0.1443, -0.0772, +0.1051, -0.6447, -0.6946, -0.6446, +0.1869,
+ -0.0377, +0.2761, +0.2183, -0.2731, +0.4264, -0.0304, -0.3574,
+ -0.1569, +0.0530, -0.2232, +0.5197, -0.2320, +0.1347, +0.2012,
+ +0.4305, +0.5680, +0.0232, +0.0364, -0.0573, -0.0205, +0.2564,
+ +0.1661, -0.2184, -0.0759, -0.1445, -0.0086, -0.0486, -0.3832,
+ -0.5249, +0.3752, -0.1400, -0.4232, -0.5390, +0.1935, -0.4422,
+ +0.5784, +0.2731, -0.1560, -0.2261, -0.1864, -0.3307, -0.4695,
+ +0.1852, -0.3265
+ ],
+ [
+ -0.6703, +0.0926, -0.5231, -0.0533, -0.1457, -0.4545, +0.1801,
+ +0.3127, -0.2343, +0.3361, +0.3834, -0.7315, +0.0778, -0.3351,
+ +0.4405, -0.4576, -0.5709, +0.2803, +0.0452, +0.0133, -0.2356,
+ -0.6245, -0.0676, -0.2523, +0.0208, -0.5238, -0.9113, -0.2605,
+ -0.4297, -0.5623, +0.4107, -0.0113, +0.1714, -0.4200, -0.5485,
+ -0.0135, -0.5424, -0.9021, +0.4813, -0.0478, -0.0835, +0.2108,
+ +0.1599, -0.2998, -0.1875, -0.1832, +0.2381, -0.3613, +0.0165,
+ +0.2614, -0.0388, +0.0995, +0.0900, -0.3565, -0.0507, -0.4172,
+ -0.4961, -0.0002, -0.2006, +0.3034, +0.1398, +0.3606, +0.1704,
+ +0.0951, -0.8070, -0.0367, -0.2107, +0.3901, -0.2230, -0.1858,
+ +0.0469, +0.3347, -1.5453, +0.0425, +0.3040, +0.7134, -0.7763,
+ -0.1766, -0.3002, -0.5227, +0.0830, -0.1727, -0.4539, -0.1433,
+ -0.0327, +0.4274, +0.6077, -0.0714, -0.0844, -0.1670, -0.1059,
+ -0.1060, +0.2655, +0.3415, -0.0698, +0.0529, -0.6991, -0.0675,
+ +0.2832, -1.2297, +0.1104, -0.1522, -0.0114, +0.0321, -0.8254,
+ +0.2382, -0.1540, -0.4243, -0.5772, +0.2560, +0.0717, +0.5933,
+ +0.1687, +0.5182, -0.2102, +0.0605, -0.0974, -0.6947, -0.5887,
+ -0.1060, +0.1320, -0.5905, -0.0760, +0.1181, +0.3569, -1.1210,
+ -0.1727, -0.3395
+ ],
+ [
+ -0.1772, +0.3237, -0.4493, -0.3765, -0.0837, -0.1910, +0.0285,
+ +0.0285, -0.0667, -0.3530, -0.4776, +0.1161, +0.1717, +0.0996,
+ -0.2512, +0.1541, +0.1372, -0.4701, +0.3240, +0.2725, +0.3984,
+ +0.2341, -0.1772, -0.0638, -0.9732, -0.2302, +0.1441, +0.2924,
+ -0.0501, -0.1822, +0.2711, -0.4964, -0.2970, -0.0056, -0.3456,
+ -0.2073, +0.2572, +0.1298, -1.3292, +0.1337, +0.3027, +0.1671,
+ +0.4342, -0.2896, +0.1945, -0.0109, -0.0791, +0.4136, -0.3764,
+ +0.1054, -0.0079, -0.9551, +0.1080, +0.1019, +0.0474, -0.6121,
+ +0.0449, +0.0598, -1.1097, +0.0250, -0.1256, -0.1458, -0.2722,
+ +0.1970, +0.0081, +0.0660, -0.1319, +0.2402, +0.1193, -0.2687,
+ +0.1651, -0.0789, -0.0503, +0.1427, +0.1901, -0.4159, -0.1638,
+ +0.0628, -0.3589, -0.0816, +0.2290, +0.0615, -0.0529, +0.5482,
+ -0.2030, -0.1866, -0.1962, +0.1167, -0.0306, -0.0570, -0.5030,
+ +0.2395, -0.0310, +0.1479, -0.4245, +0.1024, -0.1648, +0.0096,
+ +0.4198, -0.0484, -0.4378, -0.1204, +0.0451, -0.1932, +0.1844,
+ +0.0525, -0.2658, +0.2161, +0.0031, +0.0196, -0.4107, -0.0498,
+ +0.0715, +0.0926, -0.4154, -0.8397, -0.0224, -0.0883, +0.0899,
+ -0.2138, +0.3100, +0.0488, +0.1945, -0.2503, +0.1935, -0.2487,
+ +0.1230, +0.1808
+ ],
+ [
+ +0.0978, +0.2190, -0.0593, -0.2084, +0.1471, +0.2789, +0.1923,
+ +0.0510, -0.1054, +0.0873, -0.3996, -0.3414, -0.1372, +0.4061,
+ +0.4627, -0.3202, -0.4714, -0.9601, -0.4819, -0.0822, +0.2082,
+ +0.4049, -0.3494, -0.2458, +0.1077, +0.0142, +0.2404, -0.2345,
+ -0.1056, -0.2140, -0.2043, -0.0387, +0.2045, +0.0874, -0.2327,
+ -0.2445, -0.2904, -0.5968, -0.2412, -0.0058, -0.2166, -1.6990,
+ +0.0953, -0.4337, +0.2621, +0.0671, +0.2875, +0.2830, -0.0937,
+ -0.1816, -0.1853, -0.2221, -0.1232, -0.2037, -0.5923, -0.1751,
+ -0.5312, +0.0452, +0.0293, -0.1305, -0.6181, +0.3799, +0.0910,
+ +0.2810, -0.1294, -0.3590, -0.0479, +0.5384, +0.4292, +0.2362,
+ +0.0533, +0.3635, +0.1747, -0.0539, +0.2116, +0.1162, -0.1256,
+ -0.1487, +0.3834, -0.1898, -0.6399, +0.3572, -0.2274, -0.3151,
+ -0.5312, +0.2602, +0.4891, +0.5756, +0.1359, +0.0022, -0.0719,
+ +0.1784, -0.1273, -0.1417, +0.0633, -0.0857, -0.0686, -0.1350,
+ +0.0348, +0.0844, -0.3420, +0.4479, +0.0563, +0.3900, -0.0671,
+ -0.2740, -0.4127, +0.2551, -0.1971, -0.2538, -0.7251, +0.1549,
+ -0.4616, +0.0078, -0.1966, -0.2291, +0.4462, -0.0231, +0.1826,
+ -0.2767, +0.2035, +0.2113, +0.2010, -0.1224, +0.0935, +0.0749,
+ +0.5143, -0.2320
+ ],
+ [
+ +0.4054, +0.2429, -0.0183, -0.0671, +0.0756, -0.3977, -0.0052,
+ +0.3820, +0.1232, -0.6040, +0.1117, +0.1694, +0.0706, -0.0372,
+ -0.3751, -0.1524, +0.1442, +0.2963, +0.3444, -0.1264, -0.2681,
+ +0.2256, -0.1735, +0.1759, -0.1471, -0.0931, -0.1282, -0.0297,
+ -0.4555, +0.1279, -0.3330, -0.0396, -0.2031, +0.0297, -0.2009,
+ -0.4507, +0.1667, -0.0241, +0.0708, -0.0017, +0.4077, -0.4664,
+ +0.1849, +0.2298, +0.0304, -0.1883, -0.1395, -0.4955, -0.3710,
+ -0.1001, +0.2081, -0.1213, +0.1483, -0.0164, -0.0292, -0.2213,
+ +0.0290, -0.1306, -0.7133, -0.2339, +0.0027, +0.3779, -0.1889,
+ -0.4761, +0.0219, -0.3321, -0.0823, -0.3801, -0.4626, +0.0792,
+ -0.1393, +0.0571, +0.2609, +0.5688, +0.1841, -0.1736, +0.4979,
+ -0.2646, -0.1537, -0.0628, +0.4625, +0.1443, +0.0340, -0.2156,
+ -0.1324, +0.1748, -0.0408, +0.2963, -0.0362, -0.0399, -0.2844,
+ -0.1848, +0.0143, +0.2672, +0.0449, -0.0820, +0.2961, +0.0566,
+ +0.1471, +0.0741, -0.1360, -0.3407, +0.1218, +0.2081, +0.3921,
+ -0.1527, -0.3588, +0.1095, +0.5187, +0.1537, +0.3488, +0.1492,
+ +0.1520, +0.0071, +0.0351, -0.4850, +0.0759, -0.1150, +0.1143,
+ -0.2452, +0.1051, -0.3250, +0.3133, +0.1014, +0.4137, +0.0760,
+ -0.0911, -0.1412
+ ],
+ [
+ +0.2362, +0.1948, -0.0234, -0.3180, -0.3947, -0.4324, +0.0409,
+ +0.3256, +0.3289, +0.2192, +0.5133, -0.0905, -0.1503, -0.2234,
+ -0.1854, -0.1960, +0.3640, +0.5452, -0.2586, -0.2272, -0.4349,
+ -0.4656, -0.1711, -0.6232, -0.0941, -0.0505, -0.0344, +0.4293,
+ +0.0385, +0.5727, +0.1007, +0.5269, -0.1729, -0.1460, +0.0340,
+ +0.0289, -0.1339, -0.5340, -0.2329, +0.0951, -0.0265, +0.0880,
+ -0.1202, -0.2510, +0.5979, -0.3229, +0.1184, +0.0523, -0.4103,
+ -0.3743, -0.0977, -1.0859, -0.6775, +0.3640, -0.8403, +0.0808,
+ +0.1736, -1.3813, -0.3318, -0.0426, +0.0144, -0.0157, +0.3430,
+ -0.2677, -0.9526, -0.1665, -0.5873, +0.5943, -0.0056, +0.1360,
+ -0.6386, -0.0068, -0.3385, +0.3513, -0.3315, +0.2062, -0.0138,
+ -0.0954, +0.3514, -0.2501, -0.1372, +0.1850, +0.3187, +0.2417,
+ -0.0165, -0.0188, -0.4274, -0.6362, -0.0069, -0.2832, +0.2678,
+ +0.1463, -0.2544, +0.1819, -0.1543, +0.5009, -0.0178, -0.3187,
+ +0.2966, +0.2476, +0.2248, +0.1764, -0.3332, -0.4743, -0.0223,
+ -0.1946, +0.3361, +0.3132, -0.4011, -0.0480, -0.2854, +0.0791,
+ +0.3655, -0.0550, -0.3133, -0.0224, +0.3137, +0.0587, -0.0012,
+ -0.0146, -0.9586, -0.4508, -0.3847, +0.7080, -0.1266, -0.0618,
+ +0.2187, +0.1620
+ ],
+ [
+ -0.2008, +0.1522, -0.5955, +0.6051, +0.1620, +0.0268, +0.1630,
+ +0.2391, +0.0104, +0.1939, +0.0231, -0.2313, +0.0025, +0.1624,
+ -0.3330, -1.0833, +0.0795, +0.4136, -0.1967, -0.1655, -0.4112,
+ -0.5563, +0.0014, +0.2210, +0.0668, +0.0035, +0.0021, -0.3850,
+ +0.0200, -0.1434, +0.2206, +0.4751, -0.2284, -0.3879, -0.4084,
+ -0.3560, -0.4632, -0.4490, +0.4050, -0.1352, +0.6847, -0.1648,
+ -0.0965, -0.1461, -0.4165, +0.1370, +0.1259, +0.4660, -0.2856,
+ -0.2612, -0.0582, -0.3693, -0.1022, +0.2008, +0.0215, -0.0236,
+ +0.1790, -0.6251, -0.2491, -0.3790, -0.3333, -0.4391, +0.3633,
+ -0.2411, +0.1885, +0.4584, +0.0208, +0.1701, +0.1982, -0.0979,
+ +0.4661, +0.0457, +0.1591, +0.1819, +0.0283, +0.4571, -0.5580,
+ -0.1806, -0.3569, -1.1665, +0.0674, -0.2786, -0.2875, +0.4527,
+ -1.1245, +0.3730, +0.1160, +0.1188, -0.2990, +0.0239, -0.6229,
+ -0.2620, -0.3014, -0.4404, -0.0490, -0.3869, -0.6526, -0.5756,
+ -0.8867, -0.7128, -0.0526, +0.0577, -0.3834, +0.0532, -0.0304,
+ +0.0433, +0.1128, -0.6711, +0.4782, -0.0905, -0.5573, -0.4746,
+ -0.2918, +0.4604, +0.6131, -0.1770, -0.2956, +0.3240, -0.4591,
+ +0.0128, -1.1714, -0.1943, -0.0942, -0.0663, +0.0099, +0.3937,
+ +0.0239, +0.2766
+ ],
+ [
+ +0.0170, +0.1780, -0.4973, -0.0716, -0.2169, +0.4612, -0.1626,
+ -0.4549, +0.0101, -0.2997, -0.1466, -0.4529, +0.4533, -0.2593,
+ -0.1703, -0.0386, -0.1084, +0.2293, +0.2698, +0.1456, +0.4082,
+ +0.0162, -0.2304, -0.1280, -0.6106, +0.1895, +0.3912, +0.1475,
+ +0.0724, -0.0967, -0.0013, -0.5470, +0.2986, -0.1856, +0.2783,
+ -0.0052, -0.0829, +0.4755, -0.0281, -0.3022, -0.3180, -0.2155,
+ -0.0571, -0.4241, +0.2273, -0.1250, -0.2180, -0.1371, +0.2904,
+ -0.1918, +0.0821, -0.0508, +0.0111, +0.4068, -0.2078, -0.2357,
+ +0.1265, -0.3957, -0.2841, -0.1312, +0.0499, -0.1635, +0.5007,
+ -0.1800, -0.1760, -0.2792, +0.3352, +0.2681, +0.0224, +0.0703,
+ +0.0863, +0.4539, +0.3918, -0.2057, -0.0448, +0.4148, -0.4861,
+ +0.0167, -0.2710, +0.2207, -0.0376, +0.1143, -0.0410, +0.2689,
+ +0.2591, -0.1383, +0.0083, -0.0713, +0.4651, -0.0582, -0.8496,
+ -0.5416, -0.0562, +0.0845, +0.3523, +0.0582, -0.0935, -0.9280,
+ +0.2553, -0.1722, -0.1497, -0.0048, +0.1228, -0.0553, -0.0358,
+ -0.0211, -0.2331, -0.0881, +0.6748, +0.1664, -0.2651, -0.3012,
+ +0.0718, +0.2363, -0.2371, +0.2396, +0.0795, +0.1391, +0.0848,
+ -1.2251, -0.2978, -0.3685, -0.2829, -0.2450, +0.3609, +0.3417,
+ +0.1501, +0.3238
+ ],
+ [
+ +0.0900, -0.2040, -0.3442, -0.0759, -0.0008, -0.1255, -0.4207,
+ -0.1525, +0.0554, -0.0316, -0.0605, +0.0019, -0.1811, -0.4385,
+ +0.2662, -0.0091, -0.2444, +0.4792, -0.1383, -0.0188, +0.0034,
+ +0.0720, +0.0144, -0.0678, -0.1145, -0.3357, +0.0574, -0.0022,
+ -0.2551, +0.2565, -0.2532, -0.5748, +0.0039, +0.2820, +0.0501,
+ -0.2402, +0.2779, -0.3452, +0.0553, +0.2286, +0.1530, -0.2965,
+ -0.0433, +0.2779, +0.2508, +0.2410, -0.4465, -0.3985, +0.3084,
+ +0.3646, -0.1586, -0.2752, -0.1026, -0.1534, +0.0080, -0.1443,
+ +0.0291, -0.0555, +0.4796, -0.3250, +0.0324, -1.3958, -0.1115,
+ -0.4174, -0.8049, -0.1630, -0.0525, -0.1305, +0.0095, -0.0867,
+ +0.6708, -0.0000, -0.0843, -0.0231, +0.0889, +0.3775, +0.0640,
+ -0.2378, -0.5108, +0.5505, +0.2033, -0.0100, -0.6312, +0.2917,
+ -0.0302, -0.6544, -0.0306, -0.1413, +0.0555, +0.0217, +0.0254,
+ +0.1307, -0.3287, -0.2562, -0.5944, +0.1274, -0.2151, +0.1284,
+ -0.1192, -0.0702, +0.0741, -0.4227, +0.3265, +0.4678, +0.3035,
+ +0.0018, +0.3776, -0.1378, -0.1743, +0.3270, +0.2135, +0.1307,
+ +0.3493, +0.0399, -0.0457, -0.2329, +0.0670, +0.1151, +0.1365,
+ -0.0620, -0.2110, +0.3270, -0.0685, -0.1888, +0.2463, +0.0731,
+ +0.2472, -0.1711
+ ],
+ [
+ -0.6258, +0.0343, -0.4289, -0.0230, +0.1648, -0.2181, -0.0405,
+ +0.2619, -0.3522, +0.2752, -0.2303, -0.8017, +0.0875, -0.5309,
+ -0.0828, +0.0963, -0.0591, -0.1077, -0.5009, +0.0188, -0.3606,
+ +0.1645, -0.4699, -0.0852, -0.0179, +0.1350, -0.1510, -0.3459,
+ -0.0844, -0.3181, +0.2630, -0.4920, +0.0747, +0.1878, +0.1468,
+ -0.1660, +0.3766, -0.7024, -0.1669, -0.3311, -0.0016, -0.4786,
+ -0.0991, -0.1425, -0.0974, -0.2058, -0.1966, +0.2934, -0.3269,
+ -0.3688, +0.1155, -0.1031, -0.1258, -0.4646, +0.2674, +0.1911,
+ +0.4869, -0.1837, -0.5085, -0.5208, -0.1521, -0.0067, -0.0239,
+ -0.2621, -0.3033, -0.5556, +0.1006, -0.0904, -0.0944, +0.0145,
+ +0.3106, +0.1368, -0.0789, +0.0792, +0.2908, +0.2396, +0.3105,
+ -0.6561, +0.1680, -0.1279, -0.2308, -0.2565, +0.4570, +0.5447,
+ -0.2268, +0.1352, -0.3080, -0.1836, +0.4647, -0.3035, +0.0227,
+ -0.0715, -0.0236, -0.2222, +0.0024, +0.1746, +0.5088, -0.3626,
+ +0.1088, -0.4604, -0.1205, -0.0737, +0.2408, -0.4081, -0.2848,
+ -0.0930, +0.6972, -0.6394, -0.3911, +0.3077, +0.1641, -0.2980,
+ +0.3526, +0.4996, +0.4259, -0.4143, -0.0722, -0.0489, -1.0649,
+ +0.1243, -0.1063, -0.2763, -0.3938, +0.0349, -0.2978, -0.1311,
+ -0.1644, -0.2178
+ ],
+ [
+ +0.2228, -0.1594, -0.1861, -0.4351, -0.3284, -0.3570, -0.1520,
+ -0.3707, -0.2458, +0.1899, +0.1590, -0.4710, -0.3044, +0.2631,
+ +0.4542, +0.5799, +0.1573, -0.0166, -0.3127, -0.2947, +0.2246,
+ -0.2435, +0.3069, -0.2311, -0.5902, +0.4220, +0.2568, +0.1050,
+ +0.0542, -0.3542, -0.2701, -0.0067, +0.1571, +0.0236, +0.0788,
+ -0.3256, -0.4584, -0.2293, -0.2716, -0.0985, -0.3065, -0.1393,
+ +0.3065, -0.2204, -0.2763, +0.5014, +0.5428, -0.3151, -0.0117,
+ -0.5099, +0.5324, -0.0418, +0.1083, +0.2712, +0.1853, -0.0178,
+ +0.1567, -0.8271, -0.0563, -0.0500, +0.1297, -0.0225, -0.3542,
+ -0.0787, -0.1147, -0.0703, -0.3248, +0.2742, -0.0758, -0.5295,
+ -0.8132, -0.0120, -0.2870, +0.3596, -0.4447, +0.1253, +0.3223,
+ +0.0799, -0.2196, -0.1284, -0.3209, +0.6268, +0.3135, -0.3077,
+ +0.5631, +0.0843, -0.1243, +0.3294, +0.2224, -0.3047, -0.3792,
+ -0.5224, -0.0835, -0.0596, -0.4145, -0.4059, +0.2051, -0.5110,
+ -0.2352, -0.1687, +0.3791, -1.1113, +0.0344, -0.5561, -0.0971,
+ -0.1956, -0.9917, +0.0974, +0.4424, +0.2190, -0.5096, +0.1050,
+ -0.1065, +0.1762, -0.2220, -0.3448, -0.0259, +0.0306, +0.3688,
+ +0.0888, +0.5377, -0.0213, +0.0768, +0.1048, -0.2878, -0.1735,
+ -0.0799, -0.3435
+ ],
+ [
+ -0.2558, -0.1894, -0.4240, -0.1683, +0.2696, -0.6537, -0.4097,
+ -0.8188, +0.0788, -0.0674, +0.0466, -0.1045, -0.3688, +0.1775,
+ +0.0076, +0.0276, -0.0015, -0.2355, -0.0081, +0.3447, +0.3784,
+ -0.5474, +0.1801, -0.1660, +0.3446, +0.4288, +0.2730, -0.1667,
+ +0.3351, +0.1431, +0.3574, -0.8036, +0.2580, -0.0009, -0.2548,
+ +0.2669, -0.0010, +0.2673, -0.0481, +0.2498, -0.1628, +0.0913,
+ +0.3274, +0.1052, -0.1022, +0.4280, -0.1549, -0.4395, +0.1083,
+ +0.3907, -0.2138, +0.2467, -0.8071, +0.2845, +0.2277, +0.0958,
+ +0.1499, +0.0426, -1.0645, +0.2627, -1.0988, +0.0073, -0.2371,
+ -0.1110, -0.0370, +0.1322, +0.1908, -0.0820, -0.0871, -0.0927,
+ -0.2126, -0.1933, -0.5629, -0.0014, -0.1545, +0.4580, -0.1378,
+ +0.0316, -0.5284, +0.1727, -0.1004, -0.2099, +0.0290, +0.1137,
+ +0.0408, -0.1891, -0.2607, -0.5103, -0.0073, -0.3733, -0.2262,
+ -0.5160, +0.2817, -0.1558, +0.0888, +0.3333, +0.6985, -0.2266,
+ -0.3598, +0.1534, +0.2226, +0.2616, -1.3961, +0.2103, +0.2918,
+ +0.1863, -0.1366, -0.0886, +0.0040, -0.1006, -0.2855, -0.3092,
+ +0.0798, +0.0321, -0.0850, +0.1356, +0.1690, -0.0924, +0.1542,
+ -0.1020, -0.4774, -0.2607, -0.0833, -0.1287, +0.0672, +0.2268,
+ -0.1807, -0.0932
+ ],
+ [
+ -0.2405, -0.3201, +0.7086, -0.1859, -0.1761, -0.2028, -0.2184,
+ -0.1675, -0.1567, +0.0830, -0.6260, -0.0593, -0.4650, +0.2506,
+ -0.0680, +0.4262, -0.2814, -0.5134, +0.0255, +0.1273, -0.2961,
+ +0.1498, -0.3338, +0.0174, -0.2212, +0.3174, -0.1205, +0.4797,
+ +0.0533, -0.0115, +0.2920, +0.2266, -0.1898, +0.1149, -0.1576,
+ -0.2620, +0.1099, -0.3745, -0.0760, +0.0467, -0.3250, +0.1586,
+ +0.0099, -0.2494, -0.7048, -0.4182, +0.5150, +0.5745, -0.1478,
+ -0.2727, -0.2478, -0.2406, -0.2523, +0.1856, -0.0971, -0.6087,
+ -0.0432, -0.9908, +0.1931, -0.1341, +0.2256, +0.3962, +0.7869,
+ +0.0154, -0.2696, -0.0954, -0.3696, -0.0110, -0.1052, -0.0975,
+ +0.1781, +0.1258, -0.0776, +0.0353, -0.2180, +0.1670, -0.0379,
+ +0.3439, +0.0207, -0.1833, +0.2566, -0.0464, +0.2096, +0.4449,
+ +0.0416, +0.1547, +0.3403, +0.0345, +0.4687, -0.2652, -0.0801,
+ -0.0020, +0.2610, -0.1122, +0.3909, +0.0769, -0.4641, +0.0736,
+ -0.1571, -0.3774, +0.2008, +0.0973, +0.0370, +0.2582, +0.1885,
+ -0.1066, -0.2197, -0.4079, -0.0710, -0.4423, -0.4312, -0.0751,
+ -0.1196, +0.3101, -0.0285, +0.5479, -0.1970, -0.2913, -0.4369,
+ +0.5454, -0.6903, -0.8019, +0.0506, -0.1360, +0.0087, +0.0290,
+ -0.2148, -0.1939
+ ],
+ [
+ -0.4610, -0.2473, -0.0072, +0.1139, -0.0247, -0.0270, +0.1747,
+ +0.2458, +0.0063, -0.0531, -0.0759, +0.0047, +0.0364, -0.5022,
+ -0.1617, -0.7361, -0.6447, -0.2081, +0.2924, +0.2775, -0.2411,
+ -0.0804, +0.0894, +0.2635, +0.5808, +0.0442, +0.0549, +0.3769,
+ -0.2544, +0.1273, +0.2322, -0.0005, +0.0571, -0.2578, -0.3183,
+ -0.0808, -0.0843, -0.4059, +0.5397, +0.4067, +0.1236, +0.0372,
+ -0.0280, +0.3330, -0.0433, -0.6466, +0.1857, -0.0144, -0.3054,
+ +0.4676, +0.0957, -0.0832, +0.0522, +0.1565, +0.1035, -0.1486,
+ -0.0411, +0.1708, -0.6490, +0.2695, -1.4983, -0.0924, +0.0861,
+ -0.3205, +0.1533, -0.5704, -0.1770, +0.0457, -0.2784, +0.1999,
+ -0.5306, -0.3039, +0.0315, -0.0714, -0.2366, +0.2338, -0.0119,
+ -0.1229, -0.4881, -0.1953, -0.0109, +0.3970, +0.0111, +0.0094,
+ +0.2245, -0.3690, -0.2375, -0.5421, +0.3655, -0.1213, -0.1289,
+ +0.4099, -0.2984, +0.2335, -1.0059, +0.3213, -0.1308, +0.0610,
+ -0.4671, +0.1776, -0.2169, +0.0928, +0.4206, +0.0827, -0.0566,
+ -0.1113, -0.2543, +0.0759, +0.2825, +0.0447, -0.4559, -0.0657,
+ +0.1503, +0.0488, -0.2538, -0.1964, +0.1072, -0.1280, +0.6441,
+ -0.4528, +0.3117, +0.2581, -0.4013, -0.0773, -0.0911, -0.3778,
+ +0.0242, +0.0215
+ ],
+ [
+ -0.3375, -0.5719, -0.6334, -0.0649, -0.0854, +0.0065, +0.0112,
+ -0.8870, +0.3573, +0.4600, +0.1725, -0.0770, -0.3685, -0.0545,
+ -0.5765, +0.0273, -0.1385, +0.2495, +0.2816, +0.2096, -0.1360,
+ -1.0331, +0.0761, -0.2855, -0.0729, -0.2590, -0.1185, -0.2533,
+ +0.1765, -0.4079, +0.2194, -0.5630, +0.2157, +0.2393, +0.1017,
+ -0.7140, +0.0217, -0.4780, +0.1821, +0.2813, -0.3911, -0.3134,
+ +0.0405, -0.0632, -0.1073, -0.1237, -0.2487, +0.6443, +0.2270,
+ -0.2456, -0.1470, -0.4370, -0.2383, +0.1560, +0.1944, -0.4339,
+ +0.1600, +0.2022, +0.0125, -0.9087, -0.2564, -0.1490, -0.3016,
+ -0.3584, -0.4661, -0.1902, -0.7473, +0.2934, +0.5054, -0.0753,
+ +0.3913, +0.2743, -0.0716, -0.0532, -0.1229, +0.3036, +0.0937,
+ -0.6381, +0.3031, +0.0587, -0.3400, -0.0665, +0.0558, +0.1511,
+ +0.1622, +0.1003, -0.2812, -0.1361, -0.2708, +0.2619, -0.0755,
+ -0.3061, -0.1715, +0.0845, +0.0100, +0.0034, -0.5785, +0.1349,
+ -0.1744, -0.2035, +0.4662, +0.1399, -0.3066, -0.4236, -0.0472,
+ -0.2843, -0.2385, -0.5794, +0.1820, +0.3557, -0.0862, +0.3738,
+ +0.1450, +0.1000, +0.5473, +0.1507, -0.5443, +0.0914, -0.3537,
+ +0.3741, -0.1891, +0.3546, +0.3191, -0.5246, +0.4230, -0.5878,
+ -0.1751, -0.0542
+ ],
+ [
+ +0.0213, -0.1471, +0.3261, -0.4587, -0.1803, +0.3454, -0.4453,
+ -0.3145, -0.3858, -0.2512, -0.1947, -0.1724, +0.0583, +0.0332,
+ +0.3049, -0.2802, -0.1356, -0.1136, -0.2123, +0.5089, +0.2820,
+ -0.1252, +0.0767, +0.0704, -0.4895, +0.2362, -0.1172, +0.0923,
+ +0.1067, +0.3615, -0.0697, +0.2067, -0.5127, +0.0913, -0.3579,
+ +0.2358, -0.3798, +0.0920, +0.1841, -0.2430, -0.0443, -0.0572,
+ +0.0997, +0.1046, +0.1505, +0.4334, +0.0064, +0.1389, -0.1436,
+ -0.1635, +0.0277, -0.1091, -0.0032, +0.2427, +0.2126, +0.1951,
+ -0.1043, -0.4167, +0.0660, +0.3166, -0.0735, +0.4281, -0.0680,
+ +0.2983, +0.2509, +0.0579, -0.1808, +0.2992, +0.4224, +0.1334,
+ -0.3825, +0.2144, -0.3767, +0.0435, +0.2921, +0.3553, -0.6511,
+ -0.4253, +0.0686, -0.3102, -0.0320, +0.1272, -0.0162, +0.3658,
+ -0.0617, +0.2804, +0.0475, +0.2362, -0.3137, -0.3116, -0.0363,
+ -0.0645, -0.3065, -0.0121, -0.1316, -0.1926, +0.2697, -0.3122,
+ -0.1086, -0.2185, +0.0241, +0.1630, +0.1691, -0.2266, +0.0638,
+ -0.3642, +0.0405, +0.0430, -0.3574, -0.2212, -0.1512, +0.2038,
+ -0.5828, -0.2209, -0.0242, +0.2462, +0.1717, -0.0077, -0.0030,
+ -0.0895, +0.1574, +0.4435, -0.0056, -0.1508, +0.2267, -0.9727,
+ +0.0261, -0.1215
+ ],
+ [
+ -0.3160, -0.1400, +0.4377, -0.3019, +0.3067, +0.2706, -0.0765,
+ -0.0643, +0.2614, -0.2829, -0.0770, -0.4608, +0.0010, -0.7371,
+ +0.1481, +0.0234, +0.2131, +0.5582, -0.5795, -0.1648, -0.3535,
+ +0.2181, -0.3191, +0.0782, +0.0203, -0.1470, -0.3755, -0.2801,
+ +0.4999, +0.1431, +0.3485, -0.0319, -0.2214, -0.5425, -0.4827,
+ +0.0720, +0.0499, +0.0915, +0.1852, +0.4811, -0.2475, +0.3030,
+ +0.1523, -0.8120, +0.1666, -0.1881, -0.2929, -1.0035, +0.1171,
+ -0.1081, -0.2652, +0.2682, +0.2016, -0.1875, +0.1921, +0.1625,
+ -0.2025, -0.6555, -0.4698, -0.6763, -0.0720, +0.0744, +0.0735,
+ -0.2397, -0.7100, -0.0878, -0.2742, -0.0971, +0.3277, -0.0065,
+ -0.1009, -0.2990, +0.0095, -0.1290, +0.1047, +0.2795, -0.0224,
+ -0.1167, +0.1958, +0.0617, +0.0240, -0.1795, -0.1911, -0.3702,
+ -0.1098, +0.0642, -0.1415, +0.2290, +0.2341, -0.1400, -0.3408,
+ -0.1841, +0.0148, +0.1168, +0.3008, -0.3096, +0.1196, -0.4468,
+ +0.1721, +0.1640, -0.0977, -0.0530, +0.0229, +0.1476, -0.1028,
+ -0.1261, -0.1420, +0.1022, +0.3167, -0.6265, +0.1797, -0.0936,
+ +0.0511, -0.1893, -0.0957, +0.6811, +0.1573, -0.2752, +0.1701,
+ -0.2201, -0.5291, -0.2507, +0.3921, -0.1902, +0.0837, -0.0864,
+ +0.2542, -0.3904
+ ],
+ [
+ +0.3549, -0.3863, +0.0507, +0.2643, -0.5068, +0.0091, -0.1987,
+ +0.2044, +0.1588, -0.1687, +0.3042, -0.2765, -0.1975, +0.3145,
+ -0.3224, +0.0269, +0.1342, +0.1690, -0.3698, +0.0475, +0.2741,
+ +0.1402, -0.3399, +0.1895, -0.3704, +0.0448, -0.6119, -0.4312,
+ -0.1161, +0.1789, -0.2738, -0.0005, -0.1235, -0.1129, -0.1537,
+ -0.4127, +0.3147, -0.4615, -0.1564, +0.1232, -0.0074, +0.4090,
+ +0.1535, +0.1611, -0.0459, +0.0316, -0.0453, +0.2114, +0.2703,
+ -0.1030, +0.2373, -0.1695, +0.1394, +0.2881, +0.1062, +0.2914,
+ -0.0610, -0.0085, -0.2375, -0.0314, -0.0266, +0.0097, -0.1276,
+ +0.2307, +0.3851, -0.0813, +0.0323, +0.3472, -0.1466, -0.0722,
+ -0.2811, +0.1014, +0.1024, -0.0211, +0.1074, -0.0008, -0.1776,
+ +0.2776, -0.2850, +0.1980, +0.3691, -0.0283, +0.1396, +0.1274,
+ -0.1716, -0.1685, -0.4215, +0.0225, +0.0786, -0.1001, +0.4591,
+ -0.0575, -0.3971, +0.1456, -0.2183, +0.0558, -0.0271, +0.3083,
+ +0.0568, +0.2462, -0.1597, -0.0232, +0.1730, -0.3045, +0.0611,
+ -0.0139, +0.0820, +0.1426, +0.2030, +0.1218, -0.0595, -0.0221,
+ -0.1941, -0.2436, +0.0602, +0.3822, -0.0739, +0.3550, -0.2108,
+ -0.1007, +0.0043, -0.1852, +0.0749, -0.1664, +0.1066, -0.0244,
+ +0.1905, -0.0022
+ ],
+ [
+ -0.4225, +0.0205, +0.2343, +0.6412, -0.1847, -0.3596, +0.0700,
+ -0.0939, -0.0499, -0.0930, -0.0358, -0.8865, -0.0728, -0.0062,
+ -0.0464, -0.0181, +0.2364, -0.0239, +0.5704, -0.0628, -0.1030,
+ -0.4086, +0.5106, +0.1740, +0.0949, -0.1879, +0.1340, -0.0541,
+ +0.3082, -0.0291, +0.3116, +0.0689, -0.1211, -0.1224, +0.0628,
+ -0.4648, +0.2210, +0.0961, -0.2342, +0.0106, +0.0186, +0.0873,
+ -1.5674, +0.2819, -0.2889, -0.2208, -0.5178, +0.4684, +0.0253,
+ -0.4241, +0.1826, -0.1348, +0.2715, +0.2436, +0.2658, +0.2304,
+ +0.1359, -0.0806, -0.5793, +0.3441, +0.2264, -0.2614, -0.1882,
+ -0.3382, +0.1948, +0.4520, -0.9745, +0.1227, -0.3187, +0.1561,
+ +0.1611, -0.2133, -0.1997, -0.4954, -0.2462, +0.1609, +0.1442,
+ +0.1312, +0.1740, -0.3870, -0.4074, -0.3078, -0.0300, +0.2480,
+ +0.2126, +0.2092, -0.8827, -0.5479, +0.1335, -0.3101, -0.0703,
+ +0.0903, -0.2329, -0.1830, +0.4569, -1.1144, -0.0159, +0.6270,
+ +0.1413, +0.3254, -0.0640, -0.9923, -0.2731, -0.8292, +0.3298,
+ -0.3924, -0.2309, +0.2209, -0.1428, +0.1210, +0.3638, +0.0533,
+ -0.2677, -0.4959, +0.0251, -0.2504, -0.0507, -0.0921, +0.1597,
+ +0.1228, +0.0347, +0.1019, -0.0810, -0.1491, +0.0628, +0.2191,
+ -0.4947, +0.0954
+ ],
+ [
+ +0.1637, +0.0948, -0.4648, +0.3582, +0.0854, +0.0058, +0.1979,
+ -0.5683, +0.2024, +0.6277, -0.1446, +0.1466, -0.3083, -0.0088,
+ +0.2004, -0.5835, -0.0979, -0.4047, +0.1741, +0.2211, -0.1131,
+ -0.9463, -0.0805, +0.2657, +0.1303, +0.3516, +0.1750, +0.1509,
+ +0.2827, +0.0082, -0.0395, -0.2700, -0.9032, +0.0319, +0.1324,
+ +0.1078, -0.5541, +0.7263, +0.3923, -0.0758, -0.7597, -0.5127,
+ +0.1942, -0.2357, -0.5484, -0.1027, +0.3685, -0.3620, +0.3254,
+ -0.2113, -0.8554, +0.4961, +0.1886, +0.2338, +0.1664, -0.5808,
+ -0.0672, +0.1681, +0.1266, +0.0296, -1.1437, -1.3080, -0.7877,
+ -0.2797, +0.0179, -0.3475, +0.2645, +0.2776, +0.2837, +0.3169,
+ +0.2472, -0.0013, -0.1141, -0.0726, -0.1195, +0.2691, -1.2304,
+ -0.3329, -0.7756, +0.3802, -0.1996, +0.2079, -0.1404, +0.2316,
+ +0.4997, +0.1979, +0.1014, +0.0706, -0.3750, -0.8870, +0.1731,
+ +0.3022, -0.2311, -0.2704, -0.1208, -0.1827, -0.9557, +0.1715,
+ -0.3653, +0.2939, -0.6981, +0.2919, -0.4313, -0.3437, -0.0768,
+ +0.0977, -0.3232, -0.3931, -0.2694, -0.2122, -0.0491, -0.3902,
+ +0.2010, -0.4833, -0.4078, -0.0292, -0.0444, -0.3722, -0.1701,
+ -0.0076, -0.7189, -0.1509, -0.0553, -0.9382, -0.0043, -0.5509,
+ -0.0923, +0.0345
+ ],
+ [
+ +0.1160, -0.2954, -0.3315, -0.1049, -0.1665, -0.6713, +0.2705,
+ +0.2416, -0.1831, -0.4300, +0.1659, +0.0535, -0.3640, +0.4983,
+ +0.1289, +0.1666, -0.3206, -0.0546, +0.1964, -0.0279, +0.0947,
+ +0.0797, -0.3268, +0.1590, -0.2458, +0.0288, +0.2251, -0.3009,
+ -0.1476, +0.2927, +0.1510, -0.0044, -0.3690, +0.3700, +0.2042,
+ -0.3515, -0.4181, +0.0056, -0.0933, -0.4424, +0.3104, -0.0206,
+ -0.7065, +0.4244, +0.0692, +0.0821, -0.0387, +0.0745, +0.1301,
+ -0.1519, -0.0195, +0.0234, +0.1581, +0.2883, +0.0212, -0.4560,
+ -0.5068, -0.5831, +0.4690, -0.1566, -0.0208, +0.1124, +0.0008,
+ -0.3741, -0.2130, -0.2332, -0.3150, +0.0841, -0.0527, -0.1880,
+ -0.0400, -0.1145, +0.2574, +0.1251, -1.0734, -0.2387, -0.1422,
+ -0.2481, +0.0069, +0.0068, +0.0484, -0.0377, +0.3183, -0.2792,
+ +0.2541, -0.2930, -0.0113, -0.1120, +0.0407, -0.0675, -1.0289,
+ +0.2839, +0.2054, +0.0621, -0.1725, -0.6597, +0.2531, -0.1362,
+ -0.1612, +0.2407, -0.2504, +0.0369, +0.2115, -0.4549, -0.1791,
+ +0.1713, -0.2896, -0.1486, +0.2133, +0.0461, -0.3307, +0.0050,
+ -0.4137, +0.2785, -0.4291, -0.0957, +0.2633, -0.0458, -0.0116,
+ +0.2395, +0.0834, -0.1063, -0.5765, -0.1646, -0.0355, -0.6641,
+ -0.4030, +0.1182
+ ],
+ [
+ -0.1603, +0.1595, -0.8431, -0.6778, +0.1075, -0.2351, -0.1148,
+ +0.0481, +0.0980, +0.1509, -0.4538, -0.6482, +0.3181, -0.7497,
+ -0.6013, +0.1111, +0.0616, -0.1351, -0.0651, +0.3321, -0.0197,
+ -0.1127, -0.0341, +0.3115, -0.3223, +0.0818, +0.1163, -0.0377,
+ +0.1245, -0.3289, -0.0432, +0.1208, -0.1961, +0.0422, -0.0774,
+ -0.0120, -0.3441, +0.5444, -0.2227, +0.0064, -0.4028, -0.0151,
+ -0.3354, +0.3311, -0.0559, +0.0867, +0.4502, +0.0128, +0.0003,
+ -0.1244, +0.7798, +0.5170, -0.0804, +0.6044, -0.3152, +0.0484,
+ -0.1151, +0.5629, -0.6603, -0.2273, -0.1492, -0.2242, -0.0485,
+ -0.5484, -0.2776, -0.5286, -0.0948, +0.0538, -0.1728, -0.2477,
+ +0.0368, -0.0486, -0.1006, +0.0436, -0.1171, +0.5106, +0.2599,
+ -0.2541, -0.3214, +0.0887, +0.1058, -0.0414, +0.7731, +0.4503,
+ -0.3084, -0.3069, -0.8430, -0.2717, +0.0244, -0.0623, +0.4468,
+ -0.0700, -0.6146, -0.4785, +0.1428, +0.0444, +0.8492, +0.0297,
+ +0.1108, -0.1313, -0.2234, +0.0726, +0.1076, -0.1348, +0.2932,
+ -0.8258, +0.1431, -0.2649, +0.3067, +0.1376, +0.4508, +0.1335,
+ +0.4536, +0.1607, +0.4285, -0.0105, +0.1935, +0.0985, -0.4130,
+ -0.3155, -0.9062, -0.3534, +0.1880, -0.5299, -0.3446, -0.2847,
+ -0.5438, +0.2116
+ ],
+ [
+ +0.5761, -0.3813, -0.3865, +0.1568, -0.1607, -0.2502, +0.0219,
+ -0.8582, -0.5226, +0.5144, -0.1524, +0.0812, -0.4727, -0.3335,
+ -0.1110, +0.3647, +0.0783, -0.5708, -0.3820, -0.3120, -0.3096,
+ -0.0256, -0.4717, +0.1317, +0.5989, +0.4897, -0.0469, +0.0568,
+ -0.2580, -0.2221, -0.4452, -0.2594, -0.9505, +0.4975, -0.5212,
+ +0.2497, -0.0509, +0.1511, -0.6159, +0.0438, -0.1114, +0.2150,
+ -0.0859, +0.2133, -0.0728, -0.3740, -0.4002, +0.4732, +0.4738,
+ +0.5238, -0.0480, -0.2455, -0.0934, -0.2782, -0.2165, -0.1058,
+ -0.0855, +0.5160, -0.1801, +0.0536, +0.3633, -0.2925, -0.7053,
+ +0.0379, +0.2051, -0.0552, -0.7254, +0.1808, -0.8717, -0.2988,
+ -0.3500, -0.4196, -0.1360, -0.3550, +0.3361, -0.4210, -0.1077,
+ -0.4150, +0.3904, -0.2485, -0.3365, +0.2199, -0.6205, +0.1837,
+ -0.1190, -0.3000, -0.3884, +0.2614, +0.0790, -0.0139, -0.3965,
+ +0.3965, -0.4885, +0.4306, +0.1003, -0.0760, +0.4036, +0.0463,
+ +0.3266, -0.2110, -0.5959, -0.4129, -0.0650, +0.3431, -0.6494,
+ +0.2506, -0.3991, -0.1680, -0.1170, -0.0935, +0.0483, -0.0313,
+ +0.1041, -0.5254, -0.1478, -0.0523, +0.0539, +0.0581, -0.3135,
+ +0.4106, -0.0569, -0.1274, -0.7759, -0.1341, +0.1121, -0.2227,
+ -0.3384, +0.2073
+ ],
+ [
+ -0.0015, -0.0050, +0.0626, -0.2167, -0.1618, -0.1563, +0.0808,
+ +0.3984, +0.3761, -0.7672, -0.0743, +0.1242, +0.2863, +0.0726,
+ +0.2476, -0.2723, -0.0107, +0.0697, -0.2586, +0.0376, -0.5399,
+ -0.5003, +0.2620, +0.0800, -0.1510, -0.3301, -0.0241, +0.2990,
+ -0.3245, +0.4816, +0.1996, +0.1130, -0.8881, +0.3102, +0.0306,
+ +0.0916, -0.5965, -0.4686, +0.0940, +0.0700, -0.4971, +0.3605,
+ +0.0462, -0.3902, +0.1146, -0.5735, -0.6344, -0.9496, -0.5057,
+ -0.1810, -0.0559, -0.2218, -0.0443, -0.2366, +0.0693, -0.4752,
+ +0.1593, -0.3631, +0.3647, +0.1596, +0.1076, -0.1984, -0.4186,
+ +0.3248, +0.1609, +0.2158, +0.1010, +0.2301, +0.1915, -0.1493,
+ -0.8783, +0.0871, -0.1188, -0.2275, -0.0359, +0.3421, +0.0802,
+ -0.6345, -0.1397, -0.1732, +0.0109, -0.1552, -1.1050, +0.0960,
+ +0.2679, +0.0425, +0.3679, -0.4878, +0.4553, -0.8658, +0.0454,
+ -0.6804, -0.1970, -0.4404, -0.0434, -0.3961, -0.1004, +0.2561,
+ -0.4153, +0.1440, -0.0352, +0.4118, -0.2326, -0.0680, +0.0416,
+ -0.2793, +0.2123, +0.1383, -0.1678, +0.1839, -0.2010, +0.2858,
+ -0.3092, +0.2992, -0.2234, -0.2068, +0.1857, -0.2247, +0.1250,
+ +0.0474, +0.1694, -0.3829, -0.3199, -0.0096, -0.0066, -0.4101,
+ +0.2096, +0.1492
+ ],
+ [
+ -1.0530, -0.1616, +0.1781, -0.2967, -0.3292, -0.1714, -0.1484,
+ +0.0427, +0.3548, -0.0519, -0.2956, -0.8272, +0.0106, +0.5496,
+ -0.5411, -0.0851, +0.2586, -0.2523, +0.0898, -0.3291, -0.4361,
+ +0.2933, -0.3067, -0.1003, +0.4732, +0.3920, +0.2250, +0.2445,
+ +0.2729, +0.6164, +0.1556, -0.6162, +0.1678, +0.1554, -0.0462,
+ -1.0487, -0.0951, +0.0250, -0.0550, -0.0011, -0.0247, -0.4949,
+ +0.3541, +0.2239, -0.3604, +0.2358, -0.9694, -0.5448, -0.6723,
+ -0.5508, -0.0862, -0.5063, -0.2174, -0.2356, -0.2273, +0.0797,
+ -0.3075, -0.0495, +0.1235, -0.1639, -0.3079, -0.1264, -0.4438,
+ +0.3899, -0.1129, -0.5128, -0.6813, -0.1342, -0.1244, +0.0879,
+ +0.5020, +0.0280, +0.3070, +0.2640, -0.4427, +0.1822, +0.0034,
+ +0.2847, -0.2542, -0.4012, +0.0463, -0.4115, -0.5966, -0.3262,
+ -0.0476, -0.5559, -0.2575, +0.2801, -0.2403, +0.2426, -0.1122,
+ -0.0639, -0.0933, +0.3127, -0.4744, -0.1973, -0.7071, -0.2202,
+ -1.0998, -0.1894, -0.2028, -0.2228, -0.1441, -0.4315, -0.8790,
+ +0.1403, -0.3170, -0.1493, -0.3308, -0.5001, +0.2890, -0.4068,
+ -0.1283, -0.4281, +0.2751, +0.1483, +0.4841, -0.3758, +0.4211,
+ -0.1636, -0.0437, -0.1343, -1.0156, +0.2221, +0.1052, -0.5406,
+ -0.4152, +0.0602
+ ],
+ [
+ -0.2308, -0.2978, +0.0745, -0.2628, -0.3429, -0.0427, +0.0573,
+ +0.1858, -0.2774, -0.2777, -0.0013, -0.1791, +0.0037, -0.0213,
+ +0.0925, -0.0212, -0.2492, +0.0183, +0.3678, -0.0179, -0.0583,
+ +0.0586, -0.0014, +0.1517, +0.3286, +0.6509, +0.2159, -0.3924,
+ +0.0795, +0.2268, -0.1243, +0.2543, -0.0295, +0.0129, -0.0151,
+ +0.1521, -0.5144, +0.1643, -0.5641, +0.0363, +0.4261, +0.0787,
+ -0.0144, +0.2405, +0.1561, +0.1014, -0.0883, -0.1637, +0.1274,
+ +0.0933, -0.2461, -0.2536, +0.2394, +0.4473, -0.3484, +0.1002,
+ -0.3076, +0.0268, +0.0668, -0.0877, -0.2816, -0.6566, +0.1330,
+ -0.3667, +0.3127, -0.1171, +0.2557, +0.3192, +0.3922, +0.2430,
+ -0.8649, -0.3526, +0.4035, -0.0499, +0.1406, +0.1930, -0.1427,
+ +0.1748, +0.1786, +0.0764, +0.3115, +0.2849, -0.0117, +0.0284,
+ +0.1940, -0.5640, +0.2338, +0.2769, -0.2405, -0.4534, -0.4668,
+ -0.0395, +0.2209, +0.0711, -0.0354, +0.4161, -0.0014, -0.2474,
+ -0.1787, +0.2895, +0.2003, +0.0210, +0.1707, -0.1632, -0.1909,
+ -0.0915, -0.2660, +0.0307, +0.0622, +0.0725, +0.3364, -0.0440,
+ -0.0147, -0.4324, -0.4612, +0.2892, -0.0327, +0.0708, -0.2288,
+ -0.6771, +0.1125, +0.4182, -0.4915, -0.2478, +0.1810, -0.4989,
+ -0.3241, -0.0827
+ ],
+ [
+ +0.0611, +0.2865, -0.1639, -0.5949, -0.6014, -0.0413, +0.4919,
+ -0.1920, +0.1659, -0.4057, -0.0116, +0.1717, -1.8083, +0.3695,
+ +0.1806, -0.4881, +0.5887, -1.2683, -0.1151, -0.5173, +0.2263,
+ +0.2536, +0.2895, -0.4869, -0.1181, +0.0537, +0.2262, +0.1881,
+ -0.1279, -0.7002, -0.3557, -0.0005, -0.2306, -0.8433, -0.0015,
+ -0.1687, +0.2881, +0.0146, -1.0380, +0.0755, +0.3358, +0.1864,
+ -0.3233, +0.3758, -0.1901, +0.0065, -0.3992, -0.3306, +0.1113,
+ -0.2037, -0.1552, -0.3460, +0.3272, -0.2249, -0.8292, -0.1383,
+ -0.2892, -0.1736, -0.3339, +0.0082, -0.5588, -0.0003, -1.3892,
+ +0.1160, -0.3565, -0.0793, -0.3037, +0.1453, -0.2012, +0.1600,
+ -0.0894, +0.1147, -0.2503, -1.0418, -0.1991, +0.0348, -0.6366,
+ +0.1861, +0.0672, -0.4284, -0.0243, +0.1470, -1.0503, -0.4545,
+ +0.1642, +0.5413, -0.2965, +0.4746, +0.0497, -0.0846, +0.3373,
+ +0.1835, -0.3656, -0.9899, -0.7913, +0.2604, -0.4761, -0.3113,
+ -0.3797, +0.0733, +0.0392, +0.0518, -0.3743, -0.1053, -0.2166,
+ +0.0327, +0.0788, +0.2358, -0.1864, -0.4050, +0.1921, -0.8714,
+ -0.6943, -0.1009, -0.2309, +0.0990, +0.0303, -0.2281, -0.6570,
+ +0.1796, -0.2536, -0.7205, +0.0996, +0.1210, -0.2807, -0.0518,
+ -0.1800, +0.1282
+ ],
+ [
+ -0.7158, -0.0248, -0.1820, -1.0689, -0.8583, +0.1329, -0.2660,
+ +0.0176, +0.0568, +0.3375, +0.2250, -0.0206, -0.4120, -0.8021,
+ +0.2371, +0.1026, -0.3022, -0.1062, -0.1898, +0.0673, -0.1232,
+ +0.2277, -0.0368, -0.0241, -0.1203, -0.3597, -0.2682, -0.0838,
+ +0.1016, +0.0101, +0.1256, +0.0478, -0.5503, -0.0960, -0.6214,
+ -0.3078, -0.1974, -0.4763, -0.4231, -0.8695, -0.2724, +0.1457,
+ +0.1207, -0.3700, -0.0486, +0.1690, -0.0181, -0.2192, -0.0046,
+ -0.3685, -0.0330, +0.2796, +0.1762, -0.2772, -0.0359, -0.2993,
+ -0.1015, -0.1635, +0.2030, -0.1603, +0.2134, -0.1556, -0.5028,
+ -0.4694, +0.3322, -0.0483, -0.7822, -0.8137, -0.7079, +0.0925,
+ +0.1491, -0.1615, +0.3602, -0.5017, -0.0455, +0.1418, -0.0643,
+ -0.2456, -0.1544, -0.3930, -0.7707, -0.1255, -0.5566, +0.3966,
+ -0.1460, +0.0126, +0.0630, -0.1355, +0.0769, +0.2010, -0.6037,
+ -0.2071, -0.1490, +0.2603, -0.0213, +0.0620, +0.1688, +0.1827,
+ +0.4220, +0.3981, +0.2312, -0.3357, -0.1231, +0.1700, -0.1651,
+ +0.0388, -0.1009, -0.2646, +0.1996, -0.3023, +0.1891, -0.4615,
+ -0.3505, +0.1069, -0.1581, -0.0312, -0.8901, +0.0545, -0.6672,
+ -0.5027, +0.2211, +0.1013, -0.7583, -0.1434, -0.6627, -0.2156,
+ +0.2614, +0.3662
+ ],
+ [
+ -0.2563, -0.0474, -0.2365, -0.1934, -0.3914, -0.0048, -0.2730,
+ -0.2007, -0.1603, -0.2423, -0.5630, -0.3473, +0.0258, -0.9864,
+ +0.4544, -0.4950, +0.0337, -0.0502, +0.2225, -0.7403, -0.9425,
+ -0.4985, -0.1403, +0.0626, +0.3485, +0.2418, -0.0540, -0.7098,
+ +0.0510, +0.0277, +0.1600, -0.1689, -0.1595, +0.1059, -0.0557,
+ +0.0532, -0.0278, -0.5567, -0.2592, -0.5742, -1.0013, +0.1918,
+ -0.0463, +0.1362, -0.1924, +0.3461, -0.5660, +0.1042, +0.0646,
+ -0.1462, -0.3421, +0.2529, +0.0525, -0.2629, -0.1130, -0.6224,
+ -0.2830, +0.3472, +0.3616, -0.1641, -0.5444, -0.3770, +0.4742,
+ -0.3860, -0.5951, -0.1638, -0.7594, +0.1544, -0.2297, -0.5665,
+ -0.4948, +0.2582, -0.1000, -0.1965, +0.0185, +0.1803, +0.5790,
+ -1.2134, -0.1435, +0.2652, -0.1434, -0.3791, +0.3301, -0.7856,
+ +0.2785, -1.0229, +0.0838, -0.2758, -0.3962, -0.4106, -0.6214,
+ -0.1216, +0.0602, +0.0587, +0.0879, -0.9288, -0.1678, -0.5674,
+ +0.1685, -0.4010, -0.0188, -0.1108, -0.1286, -0.1027, +0.4474,
+ -0.5951, +0.6017, -0.6050, -0.0316, -0.1669, -0.1520, -0.0173,
+ -0.6195, -0.0047, -0.5535, +0.2926, -0.2384, +0.1254, -0.4349,
+ +0.1235, -0.5216, -0.7084, -0.1835, -0.1166, -0.5433, -1.7441,
+ +0.1094, +0.0133
+ ],
+ [
+ -0.1527, +0.2050, +0.0983, -0.1605, -0.1750, -0.1275, +0.0175,
+ -0.4205, -0.2100, +0.0893, +0.2032, +0.0399, -0.4218, +0.0874,
+ -0.6308, +0.2939, +0.0782, +0.0255, +0.0107, -0.2254, -0.9162,
+ +0.2254, -0.3521, +0.2638, -0.1499, -0.1506, -0.2354, +0.2721,
+ +0.5795, -0.3090, +0.1415, -0.3314, +0.0392, -0.5504, +0.1330,
+ -0.2533, -0.0513, -0.5682, +0.1356, -0.7459, -0.7628, -0.0834,
+ -0.3449, +0.3160, +0.0946, +0.3228, +0.0644, +0.1491, +0.0060,
+ -0.3167, -0.3146, -0.8460, -0.3023, +0.2308, +0.1187, -0.5089,
+ +0.0434, -0.0090, -0.5630, +0.0231, +0.1602, -0.2552, -0.5270,
+ -0.7234, +0.5465, -0.4352, -0.7148, -0.3853, +0.4611, +0.4006,
+ -0.6137, +0.4332, -0.2807, +0.0564, +0.1006, -0.2015, -0.0501,
+ -0.1992, +0.0239, -0.0428, -0.2136, +0.0181, +0.0028, -0.2133,
+ +0.4164, +0.0994, +0.1958, +0.0943, -0.3896, -0.1137, -0.0743,
+ -0.0451, +0.0772, -0.2562, +0.3917, -0.2452, +0.5537, -0.0203,
+ +0.3696, +0.1016, -0.3851, -0.0034, -0.3018, -0.4717, +0.1248,
+ -0.0375, +0.0164, -0.2870, -0.2551, -0.3909, +0.2639, -0.5118,
+ +0.2163, -0.1475, -0.2449, -0.1022, -0.3885, -1.1527, +0.3727,
+ +0.3782, +0.1173, +0.4259, -0.0340, -0.0485, +0.1656, +0.2814,
+ +0.0839, -0.5007
+ ],
+ [
+ +0.4765, -0.1649, -0.1024, +0.0055, -0.1214, +0.1782, -0.2572,
+ -0.4435, -0.7717, -0.1426, -0.3608, -0.7833, +0.1269, -0.0235,
+ +0.1364, +0.3735, -0.2381, -0.0663, -0.1387, -0.4519, -0.6952,
+ -0.2574, +0.3000, -0.3859, -0.0087, -0.0432, -0.1001, -0.3128,
+ -0.0270, -0.3285, -0.1081, +0.1883, -0.8374, -1.1177, +0.2704,
+ +0.1830, +0.1482, +0.4163, +0.2134, -0.7739, +0.4174, -0.3978,
+ -0.5230, +0.2132, -0.2400, -0.1015, +0.3938, +0.6610, -0.2333,
+ -0.0563, +0.0737, -0.3698, -0.4550, -0.2412, +0.3110, +0.0754,
+ -0.1881, -0.1304, -0.3407, +0.2422, -0.1928, -0.6068, -0.4171,
+ -0.1750, -0.4661, +0.1497, -0.8435, +0.4782, -0.0119, +0.0284,
+ -1.0337, -0.0165, -0.0950, +0.4089, -0.3840, -0.0563, -0.5054,
+ +0.0379, +0.3352, -0.1341, +0.0938, -0.8643, -0.1014, +0.0840,
+ -0.5156, -0.1637, +0.0072, +0.3067, -0.0884, -0.7413, +0.5943,
+ -0.0905, -0.2211, -0.5878, +0.3823, -0.3302, -0.3392, -0.5429,
+ +0.1319, -1.0519, +0.3625, +0.3302, -0.0129, -0.1716, -0.5146,
+ -0.0158, -0.3191, -0.2978, +0.0817, +0.1130, +0.0154, +0.6382,
+ -0.3736, +0.2939, +0.2334, +0.2609, +0.2365, +0.2562, +0.2581,
+ +0.3822, -0.3219, +0.0573, +0.2748, -0.0081, +0.1287, -0.5954,
+ -0.5557, +0.3334
+ ],
+ [
+ -0.1244, -0.0739, -0.1773, -0.0051, -0.2568, +0.0253, -0.3943,
+ +0.4885, -1.2380, +0.1550, -0.0180, +0.0387, -0.1563, -0.0694,
+ +0.3956, -0.1860, +0.2417, -0.0104, +0.1181, -0.1433, -0.1424,
+ -0.2395, +0.1543, +0.0020, +0.3424, -0.8965, +0.2261, -0.0223,
+ -0.0491, -0.1797, -0.7054, +0.0414, +0.1474, -0.0349, -0.0832,
+ -0.0827, +0.0572, +0.2952, -0.0980, -0.5059, -0.3756, -0.3521,
+ +0.3812, -0.2648, +0.1227, +0.5788, -0.1290, +0.1006, -0.6027,
+ +0.0324, -0.1361, +0.1538, +0.1624, -0.4140, -0.2818, +0.2475,
+ -0.3697, +0.0158, +0.0414, -0.4090, +0.1862, +0.3428, +0.3250,
+ -0.2630, +0.1261, +0.2009, +0.3502, -0.0755, -0.2826, +0.1526,
+ -0.2166, -0.2248, -0.4648, -0.6940, +0.2055, -0.2284, -0.0808,
+ -0.1773, +0.4859, -0.8962, -0.0136, -0.5233, -0.4861, -0.1999,
+ -0.0792, +0.6809, -0.4605, -0.0301, +0.1620, -0.5748, -0.1882,
+ +0.2918, +0.2180, -0.0636, -0.3878, -0.0864, +0.1710, +0.1606,
+ -0.0546, -0.3337, -0.6139, +0.1103, +0.0151, +0.0350, +0.1895,
+ +0.3184, +0.3794, +0.0449, -0.1940, +0.1791, -0.2073, +0.1471,
+ -0.5927, +0.0492, +0.1733, -1.0351, -0.3525, +0.2772, -0.0317,
+ -0.9995, -0.0498, -0.1881, +0.5443, +0.2347, +0.5254, -0.3914,
+ -0.0550, -0.1160
+ ],
+ [
+ -0.0967, +0.3455, -0.2238, +0.2009, +0.1764, +0.0967, -0.0590,
+ +0.3214, -0.0303, -0.2983, -0.4011, -0.5049, -0.1646, -0.0277,
+ -0.4578, +0.7766, +0.0177, -0.6196, -0.1869, -0.7060, -0.7281,
+ -0.3773, +0.3006, +0.1190, -0.1093, -0.3381, +0.3843, +0.2368,
+ -0.0337, -0.1140, -0.3126, -0.4312, +0.5474, -0.4514, +0.0049,
+ +0.3787, -0.1660, +0.7759, -0.3546, +0.0536, -0.1700, +0.0265,
+ -0.1812, -0.2721, +0.0742, -0.2028, -0.3201, +0.1234, -0.4013,
+ +0.1645, -0.7290, -0.1574, -0.2551, -0.6970, -0.3877, -0.3200,
+ +0.1977, -0.8099, -0.0750, -0.0673, -0.2181, -1.0244, -0.3877,
+ +0.0909, -0.3593, -0.5187, -0.2553, +0.0355, -0.3642, +0.0107,
+ +0.1705, +0.4053, -0.2568, +0.1740, -0.2911, -0.1625, +0.2549,
+ +0.0840, +0.3694, -0.6590, -0.3594, -0.1929, +0.2237, -0.1976,
+ +0.1534, -0.3068, +0.1278, +0.4571, -0.2539, +0.2164, -0.5471,
+ -0.0529, +0.0369, +0.4208, -0.0814, +0.3714, -0.5938, -0.3710,
+ +0.3114, +0.6259, +0.0059, +0.0130, -0.5826, +0.0877, -0.2332,
+ +0.0354, -0.8047, +0.1317, -0.9597, +0.1143, -0.2499, +0.1294,
+ -0.0472, -0.5513, +0.0643, +0.1936, -0.1909, +0.1698, +0.0858,
+ -0.1199, -0.6053, +0.0864, +0.0556, -0.3210, -0.3413, +0.0078,
+ +0.1152, -0.4971
+ ],
+ [
+ -0.0527, -0.0277, -0.5070, +0.1096, +0.2826, +0.3327, -0.0866,
+ +0.0629, -0.1437, +0.2578, +0.0404, -0.3073, +0.3690, -0.3613,
+ -0.2037, -0.5715, -0.1269, +0.1994, -0.0578, -0.1329, -0.0046,
+ -0.6498, -0.1521, -0.2816, -0.1446, -0.0221, +0.0810, -0.3729,
+ +0.4460, +0.6792, +0.1963, -0.0118, -0.3029, -1.0091, -0.5706,
+ +0.1085, -0.6219, -0.3816, -0.8965, +0.4163, -0.0812, -0.1559,
+ +0.0440, -0.2807, -1.0406, -0.2695, -0.0474, -0.1721, +0.2909,
+ +0.2715, -1.6228, -0.3200, -0.1958, +0.0388, +0.1530, -0.9646,
+ +0.2767, +0.4320, -0.1137, -0.6233, +0.1335, -0.2247, +0.4663,
+ +0.0214, -0.2247, +0.3232, -0.7008, +0.4906, +0.3080, -0.0374,
+ -0.6051, +0.2417, -0.3725, +0.4420, +0.2252, -0.3977, -0.4043,
+ +0.1437, +0.5895, -0.9664, -0.1180, +0.5082, +0.0914, +0.3361,
+ -0.7208, -0.5858, -0.5050, -0.0817, +0.2920, +0.0912, +0.4496,
+ -0.2410, -0.3415, +0.1653, -0.1557, +0.7604, -0.5723, -0.5638,
+ -0.3500, -0.8521, -0.2054, +0.0974, +0.2551, -0.2385, -0.0929,
+ -0.0650, -0.0434, -0.3776, +0.4589, +0.2075, -0.4577, -0.0888,
+ +0.0540, -0.3768, -0.3778, -1.2187, -0.2733, -0.3868, -0.5227,
+ +0.5560, +0.1831, +0.1179, -0.4877, -0.1921, -0.2940, -0.1083,
+ +0.1321, +0.0658
+ ],
+ [
+ +0.0851, +0.1237, +0.3079, -0.3762, -0.2870, +0.1797, +0.1528,
+ +0.1408, -0.0854, +0.2107, -0.0888, +0.1461, +0.0396, +0.0078,
+ +0.2542, -0.0276, +0.1926, +0.0659, -0.1361, +0.0434, +0.3480,
+ -0.0129, -0.0772, +0.0886, -0.0437, -0.0188, -0.4141, +0.1342,
+ -0.2803, -0.0198, -0.2619, +0.0503, -0.3024, -0.1624, -0.0729,
+ +0.0999, +0.2488, -0.5538, -0.5757, +0.0182, +0.1508, +0.0242,
+ +0.1205, +0.0480, +0.0230, +0.0396, +0.5233, -0.4589, +0.3359,
+ -0.2505, +0.0021, +0.1641, -0.1351, -0.2552, -0.2580, +0.0780,
+ -0.2114, -0.0661, +0.1573, -0.0167, +0.4415, -0.1601, +0.1631,
+ +0.2454, -0.1081, +0.0016, -0.4957, -0.0726, +0.0853, +0.2539,
+ -0.4234, -0.0471, +0.2212, -0.2625, +0.1045, +0.1269, +0.1261,
+ +0.1722, +0.1526, -0.1199, -0.1990, -0.3317, -0.3490, -0.1991,
+ -0.8123, -0.1331, -0.2023, -0.4781, -0.0670, +0.1621, -0.4527,
+ -0.0136, -0.5296, +0.1699, -0.2776, -0.4615, +0.0328, +0.3221,
+ +0.0832, +0.0988, +0.0501, +0.0616, -0.1198, +0.0369, -0.2673,
+ +0.1644, -0.1164, -0.7414, +0.2164, -0.2900, -0.2164, +0.1668,
+ -0.2093, +0.0993, -0.1886, -0.3224, -0.3970, +0.1618, -0.2486,
+ -0.5561, -0.2513, +0.0465, -0.0900, +0.0689, -0.3624, -0.5229,
+ +0.0975, -0.1538
+ ],
+ [
+ -0.2350, -0.0645, -0.3615, -0.0227, -0.5530, +0.1408, -0.0817,
+ -0.2408, -0.1138, -0.1513, +0.3608, +0.4338, -0.1659, +0.6428,
+ -0.0378, +0.3013, -0.1392, -0.3619, -0.8423, +0.3682, +0.3757,
+ -0.0121, +0.4504, +0.0619, -0.6040, -0.6458, -0.5900, -0.1712,
+ +0.4316, +0.0350, +0.3142, -0.7079, +0.0091, +0.4126, -0.4210,
+ -0.0609, -0.1032, -0.3058, -0.1821, +0.3230, -0.3882, -0.9278,
+ +0.0894, -0.0269, -0.6832, -0.7596, +0.3437, -0.7062, -0.6884,
+ -0.2122, -0.0652, +0.1604, -0.0175, +0.3662, +0.4354, +0.3192,
+ -0.2377, +0.1625, +0.1337, +0.0469, -0.0486, +0.2694, -0.5156,
+ +0.0278, +0.2552, -0.4929, -0.9727, -0.1039, -0.1098, -1.2475,
+ +0.1701, -0.2273, -0.7669, -0.5180, +0.1835, +0.1097, -0.4413,
+ -0.4020, -0.3054, -0.3705, -0.8869, +0.2093, -0.3340, -0.1148,
+ -0.3528, -0.1682, -0.1487, -0.4372, -0.4378, +0.1359, -0.0848,
+ -0.7216, -0.6878, -0.2174, -0.4028, -0.2557, +0.0784, -0.1654,
+ -0.1174, +0.3619, -0.1810, -0.0099, -1.1576, -0.0002, -1.0263,
+ -0.3744, +0.2061, -0.8543, -0.8111, -0.4431, +0.1512, +0.2831,
+ +0.1916, +0.4312, +0.5064, +0.0385, -0.0675, -0.1375, +0.2126,
+ +0.0130, +0.4966, +0.2362, +0.0904, -0.7148, +0.0392, -0.1645,
+ +0.1844, -0.7697
+ ],
+ [
+ +0.0220, -0.0428, +0.0276, +0.3503, +0.2144, -0.1321, +0.3869,
+ -0.1202, -0.1374, +0.0744, -0.4690, -0.1239, -1.0280, +0.3670,
+ -0.1420, -0.1227, +0.1930, -0.1847, +0.3942, +0.2043, -0.5067,
+ -0.1962, -0.6377, -0.3575, -0.0448, +0.1373, +0.0288, +0.3011,
+ -0.0772, +0.0266, -0.2126, +0.4098, +0.0688, +0.2684, +0.0468,
+ -0.7170, +0.5634, -0.1395, +0.4975, -0.1992, +0.0157, -0.3145,
+ +0.1247, -0.2183, +0.1947, -0.0192, +0.0535, -0.2897, +0.2576,
+ -0.0970, +0.0374, +0.1809, -0.2987, -0.1980, -0.0604, -0.2548,
+ +0.3602, -0.0131, +0.2217, -0.4366, +0.3172, -0.4558, +0.3201,
+ -0.6872, +0.1945, +0.1090, +0.0402, +0.0382, -0.1878, -0.1224,
+ -0.0817, +0.1835, -0.9401, +0.0475, -0.0883, +0.2037, -0.0891,
+ +0.1447, -0.2684, +0.1187, +0.2925, +0.0545, -0.6845, +0.1526,
+ -0.1610, -0.2451, +0.0026, +0.1057, +0.0704, +0.1843, -0.2590,
+ -0.0985, -0.2079, -0.7211, +0.0775, +0.2452, -0.3347, +0.2375,
+ -0.0090, -0.2547, +0.1042, -0.0516, -0.0689, +0.3129, +0.1685,
+ +0.0748, -0.2181, -0.3170, -0.1933, -0.0852, +0.5291, +0.0392,
+ -0.0554, -0.1644, -0.2692, -0.2711, +0.1414, +0.2713, -0.4879,
+ +0.0969, -0.1078, -0.0405, -0.4846, -0.1335, +0.0573, +0.0358,
+ +0.1098, -0.1402
+ ],
+ [
+ -0.1117, +0.1986, -0.7761, -0.3040, +0.3357, -0.3474, +0.1743,
+ +0.1902, +0.3739, -0.2314, +0.0653, -0.1791, -0.2269, -0.5653,
+ +0.2996, +0.1259, -0.2694, +0.2773, -0.1439, -0.1760, -0.1470,
+ -0.2581, -0.4101, +0.0351, -0.3246, +0.2160, +0.1913, +0.2079,
+ +0.2030, -0.0556, +0.3580, +0.0021, +0.1484, +0.2643, +0.1736,
+ -0.2415, +0.0955, +0.0201, -0.0134, -0.0322, +0.3084, -0.4807,
+ +0.1081, -0.5020, +0.2811, +0.0917, -0.2092, +0.0043, +0.1168,
+ +0.4111, -0.0706, -0.2049, +0.0966, -0.2413, -0.0175, +0.3128,
+ -0.3217, -0.5673, -0.1846, -0.2971, -0.1817, -0.2797, -0.3498,
+ +0.0397, +0.3490, +0.0587, +0.0955, -0.1578, -0.4743, +0.1826,
+ +0.4050, +0.3482, +0.1023, +0.0652, -0.1641, -0.2173, -0.4869,
+ +0.0762, -0.0708, +0.2776, +0.0441, +0.3667, -0.5101, -0.5287,
+ -0.2622, -0.2233, +0.1004, +0.2117, +0.1264, -0.0336, +0.0162,
+ +0.4209, +0.3222, +0.3265, -0.3533, +0.1657, -0.3463, -0.7502,
+ -0.2849, +0.1964, +0.2663, +0.1315, -0.0235, -0.1738, -0.3701,
+ +0.1235, -0.3071, -0.1384, +0.1270, +0.5121, +0.2657, -0.4361,
+ -0.0806, +0.3179, +0.2078, +0.1773, -0.0158, +0.4612, -0.0097,
+ +0.0344, +0.4431, -0.0293, +0.2263, -0.3492, +0.0373, +0.3111,
+ -0.3341, +0.3314
+ ],
+ [
+ -0.2234, +0.3046, +0.0611, -0.2822, +0.0183, +0.0652, -0.4832,
+ +0.2223, -0.1448, +0.0276, +0.1012, +0.3600, -0.1284, -0.6043,
+ -1.2978, -0.8725, -0.0866, +0.1470, +0.4283, +0.0699, +0.0635,
+ +0.5191, -0.0263, +0.0685, -0.0539, +0.3351, -0.1752, +0.3458,
+ -0.4523, -0.2304, -0.1956, -0.0134, -0.1779, -0.1767, -0.1972,
+ -0.1104, -0.0667, -0.2914, -0.9693, +0.2018, +0.0919, -0.3138,
+ +0.0910, +0.2717, +0.1102, +0.0138, -0.5037, +0.0832, +0.0590,
+ -0.3267, -0.0313, +0.1724, -0.3492, +0.2826, -0.0482, +0.0152,
+ +0.1023, -0.7773, -0.0515, -0.2389, +0.0211, -0.0255, -0.0368,
+ +0.5986, +0.0725, -0.2325, -0.5902, -0.1262, -0.0356, +0.1307,
+ -0.4985, -0.1194, -0.1714, +0.0975, -0.3656, +0.3823, +0.0281,
+ +0.0863, -0.1686, -0.2519, +0.2029, -0.0693, +0.0241, +0.4671,
+ -0.0035, +0.1302, -0.6907, -0.2194, +0.1807, -0.7022, -0.1678,
+ -0.0593, -1.0474, -0.3847, -0.3561, +0.0089, +0.3198, +0.1647,
+ +0.1293, +0.0437, +0.2253, -0.0569, +0.3280, -0.3060, +0.3071,
+ -0.0946, +0.2558, +0.1250, -0.3373, -0.7435, +0.0748, -0.1516,
+ -0.1449, +0.2877, -0.1991, +0.0102, +0.2082, +0.3499, -0.3268,
+ +0.1190, +0.3183, +0.0166, +0.3925, +0.3659, -1.3411, +0.3606,
+ -0.0859, +0.1691
+ ],
+ [
+ -0.4373, +0.5870, -0.2470, -0.4369, -0.5017, -0.7323, -1.2199,
+ -0.2451, -0.2447, -0.1360, +0.2145, -0.4427, -0.3696, +0.1239,
+ +0.3161, -0.1466, +0.0734, -0.0463, +0.0277, -0.3268, -0.1238,
+ +0.0240, +0.0479, -0.0531, -0.3103, +0.4964, +0.0494, -0.0860,
+ -0.5420, -0.1102, -0.5141, +0.2544, +0.0141, +0.1847, -0.3437,
+ +0.2420, -0.0345, -0.1352, -0.2411, +0.0601, -0.1543, +0.2220,
+ -0.0458, -0.0342, +0.0031, +0.3370, -0.0459, -0.3162, +0.3164,
+ -0.2459, -0.3363, +0.0468, -0.0645, +0.5785, -1.0524, +0.0431,
+ -0.2120, -0.1114, +0.1165, -0.0978, +0.0010, +0.1229, +0.0559,
+ -0.4454, +0.6569, -0.1128, +0.0485, -0.3288, -0.1035, -0.1959,
+ -0.6063, +0.2157, -0.1107, -0.0526, -0.0856, -0.6510, +0.1339,
+ +0.5464, -0.2989, +0.5216, -1.2263, -0.0108, +0.2021, -0.1379,
+ +0.7368, -0.3330, -0.1118, +0.0816, -0.3946, -0.7703, +0.1186,
+ +0.0387, -0.2798, -0.4680, -0.1312, +0.5733, +0.0175, -0.8109,
+ -0.7925, +0.2221, -0.3326, +0.1711, -0.3284, +0.5274, -0.6371,
+ +0.3497, -0.2010, +0.3155, -0.2545, -0.1489, +0.3425, +0.1253,
+ +0.4334, -0.4114, +0.0696, +0.1568, -0.1666, +0.3577, +0.0306,
+ -0.6268, -0.6966, -1.0236, -0.4172, -0.5622, -0.1003, -0.5679,
+ +0.1524, -0.3371
+ ],
+ [
+ -0.2767, +0.0972, -0.5547, -0.2201, -0.1170, -0.1576, -0.1602,
+ +0.1382, -0.0808, +0.2028, -0.3989, +0.0158, -0.1357, -0.3024,
+ -0.2257, -1.2166, -0.2502, -0.5230, -0.4460, -0.1411, -0.1846,
+ -0.4805, -0.0032, -0.4232, -0.4742, -0.5456, -0.1574, -0.3298,
+ +0.0333, -0.0440, -0.2283, +0.0253, -1.1936, +0.2652, -0.0474,
+ -0.0169, -0.0632, +0.3591, -0.2793, +0.0314, -0.6320, -0.8212,
+ -0.1199, -0.3018, +0.1836, -0.1475, -0.8715, -0.3799, +0.1702,
+ -0.2543, -0.5776, -0.0772, +0.3332, +0.2767, -0.2859, +0.2075,
+ -0.7332, +0.4793, -1.5267, +0.1474, -0.2003, +0.0032, -0.0866,
+ -0.4733, -0.2157, -0.5489, -0.8860, +0.0229, -0.3014, +0.0358,
+ -0.0763, -0.0744, +0.0927, -0.5832, +0.2188, +0.1248, -0.2539,
+ -0.6919, -0.0873, -0.4554, +0.0821, +0.2124, +0.0322, -0.0390,
+ -0.2129, +0.2774, +0.2383, -0.2737, -0.2540, -0.8198, +0.1893,
+ -0.2351, -0.0728, +0.4741, -0.4950, -0.3812, +0.1700, -0.8968,
+ +0.0391, +0.3027, -0.0014, +0.0654, -0.2479, +0.0851, +0.1058,
+ +0.4011, -0.0536, -0.6038, -0.2781, -0.0519, +0.2117, -0.4242,
+ -0.4415, -0.3171, +0.1510, -0.0039, -0.4738, -0.1233, -1.2393,
+ -0.0213, -0.1457, +0.0515, -0.2666, +0.0735, +0.3065, -0.2219,
+ -0.3103, +0.1352
+ ],
+ [
+ -0.1894, -0.3178, -0.2146, -0.0917, -0.3281, +0.3759, -0.3827,
+ +0.2162, -0.2736, -0.5178, +0.1408, -0.1238, -0.0214, -0.0124,
+ -0.3949, -0.3133, -0.1027, +0.0348, +0.2293, -0.1680, -0.6537,
+ -0.2278, -0.2112, +0.2586, +0.1426, +0.0794, +0.0601, +0.1368,
+ -0.2424, +0.1392, +0.0391, +0.1776, +0.3126, -0.4101, +0.1359,
+ +0.2845, +0.2675, +0.1771, -0.1543, -0.3432, +0.1683, +0.2882,
+ -0.1131, -0.1933, +0.1945, -0.3527, -0.2665, -0.0031, -0.8195,
+ +0.0226, +0.0603, -0.0813, +0.2884, -0.1688, -0.1183, +0.3030,
+ +0.2942, +0.2613, +0.0640, +0.1961, +0.0728, -0.1439, -0.3157,
+ -0.0657, +0.1147, +0.2127, -0.5807, -0.3566, +0.2828, -0.3506,
+ +0.0159, -0.3167, +0.1337, +0.1766, +0.2469, -0.0833, +0.2147,
+ -0.1919, +0.2639, -0.0558, -0.4039, +0.1532, -0.2222, +0.2294,
+ -0.1847, +0.1543, +0.0267, +0.3783, +0.4722, +0.1427, +0.2415,
+ +0.4090, -0.4329, -0.2182, -0.1861, +0.4997, +0.0788, -0.5247,
+ +0.1604, -0.1814, -0.3566, +0.2227, -0.0276, -0.1325, -0.4941,
+ -0.2409, +0.1634, +0.2456, +0.3919, +0.1564, -0.3376, -0.0926,
+ -0.0169, +0.0950, -0.1314, +0.0283, -0.3400, -0.4327, +0.0396,
+ -0.1139, -0.0001, +0.0763, -0.4060, +0.3790, -0.1646, -0.7353,
+ +0.0369, -0.0515
+ ],
+ [
+ -0.2086, -0.1809, -0.0925, -0.3050, -0.2023, -0.3849, +0.0063,
+ +0.3838, -0.0679, -0.4047, +0.1106, -0.2605, -0.1714, -0.0836,
+ +0.3509, -0.1618, -0.6817, -0.5073, +0.0951, +0.0166, -0.0730,
+ -0.3489, +0.4669, +0.0451, +0.0663, +0.3284, -0.0380, -0.3944,
+ -0.4299, -0.1957, -0.6752, +0.1119, -0.4006, +0.0351, +0.0977,
+ +0.3906, +0.3201, -0.3789, +0.4969, +0.0857, -1.0318, -0.0316,
+ +0.0653, +0.1053, -0.4342, -0.5321, +0.2690, +0.2056, +0.2295,
+ -0.0461, -0.1716, -0.9352, +0.0156, +0.0124, -0.4358, -0.0842,
+ -0.1229, +0.5391, -0.3714, -0.0735, -0.2581, -0.2032, -0.3048,
+ -0.4434, -0.3753, +0.4077, +0.4080, +0.0238, +0.0651, +0.1965,
+ +0.5052, -0.2532, +0.1327, -0.5991, -0.3155, +0.1131, -0.3228,
+ -0.1098, -0.4889, -0.3557, +0.0582, -0.8156, +0.0351, +0.0854,
+ +0.1539, -0.0416, +0.0878, +0.5755, -0.1741, +0.3042, +0.3049,
+ -0.1249, -0.0155, -0.0495, -0.1473, -0.0890, +0.0657, -0.4408,
+ -0.2135, +0.1564, +0.1787, -0.3268, -0.1219, +0.1648, +0.3581,
+ -0.0800, -0.4765, +0.2241, -0.3060, +0.1448, -0.6599, +0.1232,
+ -0.5561, +0.2646, -0.1117, -0.0416, -0.2256, -0.0567, +0.2988,
+ -0.1756, -0.2153, -0.2089, -0.1916, -0.1445, +0.4029, +0.5686,
+ -0.8428, -0.3141
+ ],
+ [
+ +0.4546, -0.2401, -0.8765, +0.1447, -0.3474, +0.2069, +0.0291,
+ -0.3461, -0.5166, -0.2007, +0.2375, +0.0309, +0.1591, +0.2316,
+ -0.3278, +0.0879, -0.1175, +0.1829, -0.3574, -0.0183, +0.0943,
+ -0.8221, -0.0635, +0.1241, +0.2995, -0.4990, -0.1297, -0.0750,
+ +0.0564, +0.3013, -0.3528, -0.0187, -0.6252, -0.0760, -0.0297,
+ -0.3231, +0.2837, +0.0155, -0.1604, -0.0188, -0.0737, +0.1051,
+ +0.2268, -0.8192, +0.0854, -0.4684, -0.0896, -0.1865, -0.2881,
+ +0.2112, +0.1710, +0.1251, -0.1999, -0.2006, +0.0150, +0.2386,
+ -0.2525, -0.2776, +0.0791, -0.1655, +0.2221, -0.6359, -0.4413,
+ +0.0507, +0.0245, -0.1480, +0.0307, -0.4909, -0.2057, -0.5612,
+ -0.2967, +0.0754, +0.0988, -0.4456, +0.4071, -0.3079, -0.5466,
+ +0.1572, -0.0346, -0.5972, -0.1862, +0.0957, -0.8404, +0.3361,
+ -0.0397, +0.1259, -0.0430, +0.4487, -0.1305, -0.0816, -0.4018,
+ +0.0301, +0.0845, -0.3938, +0.0034, -0.1890, +0.1008, -0.2038,
+ -0.0580, +0.0037, -0.3044, -0.2627, +0.2022, +0.0591, -0.0465,
+ -0.3806, +0.5580, +0.0273, +0.3072, -0.0389, -0.3435, -0.2277,
+ +0.1378, -0.0317, -0.0693, +0.2321, +0.4751, -0.1210, +0.2986,
+ +0.1641, +0.0845, +0.1088, -0.0719, +0.0558, -0.0499, +0.1624,
+ +0.3028, -0.0444
+ ],
+ [
+ +0.3694, -0.0619, -0.0750, -0.4331, -0.4578, -0.2562, -0.2689,
+ +0.2755, -0.2460, -0.0051, -0.7781, -1.0708, +0.2076, +0.3512,
+ +0.2633, -0.0265, -0.3566, -0.2862, -0.6983, -0.1114, +0.1958,
+ +0.0863, -0.6004, +0.1575, +0.3171, -0.1933, +0.0496, +0.6272,
+ +0.0932, +0.2021, +0.1328, -0.5198, -0.6713, -0.0838, -0.3921,
+ -0.2568, -0.3613, -0.1204, +0.0601, -0.6830, +0.4960, -0.2160,
+ -0.0535, -0.3319, -0.3293, +0.2971, +0.3285, -0.0228, +0.0649,
+ -0.4740, +0.7016, -0.4892, -0.2840, +0.2251, -0.2327, -0.8171,
+ +0.4519, -0.1815, -0.1825, -0.7546, -0.5589, -0.1238, -0.1216,
+ +0.0837, -0.2976, -1.7269, -1.0251, +0.1344, +0.4895, +0.1124,
+ +0.0124, -0.6756, -0.1620, +0.1031, -0.2471, -0.6356, +0.5671,
+ +0.4402, -0.5158, +0.0154, -0.2029, +0.3559, +0.4752, +0.4763,
+ -0.0111, -0.0330, -0.1440, -0.5386, -0.0265, -0.8968, +0.1154,
+ -0.2805, -0.3890, -0.5239, -0.0655, -0.3710, -0.1921, -0.2713,
+ +0.3029, -0.0201, +0.0902, +0.0504, -0.2419, +0.3148, +0.7004,
+ +0.0841, +0.5304, -0.1880, +0.2689, +0.0060, -0.7380, +0.2010,
+ -0.0502, -0.4943, -0.0261, +0.1489, -0.6708, -0.1913, -0.7632,
+ +0.0502, -0.3367, +0.1165, +0.0408, +0.1340, -0.4637, -0.4536,
+ -0.9485, -0.3013
+ ],
+ [
+ -0.1725, -0.1858, +0.0331, +0.3456, -0.1368, +0.2509, +0.2902,
+ -0.2707, +0.3620, -0.4504, +0.2074, -0.3254, -0.3116, +0.1972,
+ -0.2880, -1.5750, +0.1065, +0.2296, -0.3981, -0.6005, -0.0860,
+ -0.1587, +0.1138, -0.0057, +0.1169, +0.1022, +0.0771, -0.5353,
+ +0.2160, +0.2135, +0.0991, -0.0715, -0.2361, -0.5277, -0.3601,
+ +0.1271, -0.8232, -0.9594, -0.1746, +0.2128, -1.2460, +0.0310,
+ -0.3488, +0.0794, -0.8006, -0.0880, +0.2133, +0.1811, -0.1658,
+ -0.1150, -0.9967, +0.0063, +0.0494, -0.8586, -0.2293, -0.2535,
+ +0.0954, +0.3826, -0.7305, -0.5031, -0.1241, -0.4392, -0.9065,
+ -0.0479, -0.2143, -0.5246, -0.2355, -0.4192, -0.0020, -0.1630,
+ +0.0590, -0.1096, -0.0354, +0.1383, -0.4181, -0.1156, -0.9471,
+ -0.5348, -0.0057, -0.9101, -0.0550, -0.8399, +0.2349, +0.0682,
+ +0.1741, +0.3622, -0.2623, -0.3513, +0.1216, -0.1540, +0.0167,
+ +0.0928, +0.2289, -0.5268, -0.5032, -0.5759, -0.2395, +0.1103,
+ -0.2771, -0.3320, -0.1327, +0.0540, -0.1549, +0.5291, -0.0706,
+ +0.0489, -0.3762, +0.0153, -0.0167, -0.4286, -0.6423, +0.8254,
+ +0.0893, -0.5137, -0.0482, -0.1103, +0.0620, -0.0734, -0.2348,
+ -0.2156, -0.4396, +0.8179, -0.1603, -0.0299, -0.6343, -0.8946,
+ -0.3538, -0.3519
+ ],
+ [
+ -0.2354, -0.0994, -0.0970, -0.1210, -0.5758, +0.2825, +0.0853,
+ -0.0817, +0.3374, +0.3253, -0.1718, +0.2518, -0.1108, -0.4627,
+ +0.1909, +0.0746, -0.1913, -0.4916, -0.1558, -0.2477, +0.2525,
+ -0.0559, +0.0598, +0.0704, -0.1778, +0.2072, -0.1712, -0.0083,
+ -0.2989, -0.1084, +0.0435, -0.2145, +0.0225, +0.6034, +0.1502,
+ +0.1591, -0.3021, -1.0728, -0.5351, +0.0799, +0.1981, -0.0034,
+ +0.6635, -0.2042, -0.0471, +0.2838, +0.1760, -0.4701, +0.4796,
+ +0.1516, +0.0430, +0.6459, +0.0252, -0.3035, -0.6315, -0.1916,
+ -0.2847, -0.6922, +0.2426, -0.2787, +0.1770, +0.1493, -0.4729,
+ +0.3312, -0.8047, -0.3841, +0.4028, -0.1849, +0.0628, +0.1960,
+ +0.1757, -0.1554, -0.1836, -0.2858, +0.2676, +0.2611, +0.0566,
+ -0.9536, -0.0094, +0.0276, -0.0257, -0.1097, +0.0644, +0.1793,
+ +0.0124, +0.0730, -0.1807, +0.0420, -0.2505, +0.2622, +0.1184,
+ -0.5243, +0.2392, -0.2308, +0.1152, -0.2640, -0.3274, -0.0795,
+ +0.3790, +0.3166, +0.0136, -0.4956, -0.1574, +0.2242, -0.0071,
+ +0.1597, -0.1925, -0.3563, -0.0431, +0.4689, -0.5352, +0.1372,
+ +0.0079, -0.4182, +0.0542, +0.0660, +0.1484, -0.0518, +0.3963,
+ -0.1329, -0.9245, -0.2170, +0.8141, -0.2753, +0.1995, -0.8927,
+ +0.2048, -0.9033
+ ],
+ [
+ +0.1385, +0.2524, +0.2341, -0.0525, +0.0286, -0.1349, +0.1474,
+ +0.1847, -0.0895, -0.2732, -0.0785, -0.3748, +0.4309, -0.1217,
+ -0.1987, +0.1887, -0.1932, +0.0054, +0.0628, +0.3407, +0.3116,
+ -0.1444, +0.0419, -0.1252, +0.2750, +0.1297, +0.0635, -0.2700,
+ +0.3252, -0.4535, +0.1030, +0.0394, -0.4224, -0.1120, -0.3679,
+ +0.0162, -0.2485, -0.2971, -0.0216, +0.1285, -0.2827, +0.0020,
+ -0.0438, +0.0292, +0.1771, +0.1373, -0.0630, -0.4031, -0.1995,
+ -0.0976, +0.1109, +0.2382, -0.1350, -0.0708, -0.3023, +0.0379,
+ +0.2145, -0.2867, -0.5431, -0.0735, -0.3522, -0.4424, -0.4257,
+ -0.7687, -0.1674, +0.3218, -0.2861, -0.5267, -0.1729, -0.4813,
+ -0.4816, -0.4595, -0.2712, -0.2190, +0.2677, -0.1222, -0.3066,
+ -0.1060, +0.2256, -0.0821, +0.0364, -0.5062, +0.0821, +0.1147,
+ +0.1934, -0.4142, -0.1493, +0.2036, -0.3093, -0.0189, -0.2693,
+ +0.2322, +0.1105, -0.3197, +0.2832, -0.1993, -0.2103, -0.6401,
+ -0.2555, +0.1762, +0.1250, -0.1426, +0.0233, -0.0284, -0.0694,
+ +0.2206, -0.0664, +0.3228, +0.1130, -0.2081, +0.1334, +0.0279,
+ -0.2022, +0.3889, +0.1545, -0.3145, -0.6417, -0.2156, -0.0909,
+ +0.1342, -0.0219, -0.5034, -0.4547, +0.0030, +0.2268, -0.6860,
+ +0.0075, +0.1278
+ ],
+ [
+ -0.2374, +0.0805, +0.2663, +0.1124, +0.0258, -0.3193, +0.3090,
+ -0.0598, +0.3276, +0.0092, -0.5305, -0.0264, -0.1383, -0.3224,
+ -0.0795, -1.0162, -0.1734, +0.0706, +0.3049, -0.4068, +0.1737,
+ -0.7058, +0.2571, +0.1217, -0.2815, -0.5398, +0.1680, -0.3644,
+ -0.5849, +0.1535, -0.2410, -0.0299, +0.4319, -0.4040, +0.1864,
+ -0.4186, +0.1141, -0.0188, -0.8473, -0.4871, +0.0764, -0.6763,
+ -0.4378, -0.3592, +0.1187, +0.4060, -0.2282, -0.0395, +0.1306,
+ -0.0833, -0.3435, +0.0764, -0.5312, -0.0791, +0.1757, +0.0578,
+ -0.5238, -0.0140, -0.5122, -0.2480, -0.7816, -0.6827, -0.5802,
+ +0.1869, +0.2833, +0.2551, -0.6782, -0.1467, -0.3754, -0.0426,
+ +0.5844, -0.3302, -0.5216, -0.1696, +0.3585, +0.1013, -0.0017,
+ +0.1690, -0.0158, +0.1443, -0.0728, -0.2636, +0.0779, -0.3160,
+ +0.0778, -0.0808, +0.0080, -0.0362, -0.2650, +0.0755, -0.0979,
+ +0.3609, -0.3260, +0.0995, -0.3250, -0.4137, -0.2061, -0.5269,
+ -0.1452, +0.2401, -0.2095, +0.0808, -0.2633, +0.0889, +0.2723,
+ -0.3161, +0.1089, +0.2698, -0.3279, +0.2626, -0.0076, -0.2605,
+ +0.2754, +0.1855, +0.4763, -0.1059, +0.0752, +0.0249, +0.4125,
+ -0.4099, -0.5385, -0.0468, +0.1375, +0.1461, -0.1498, +0.0242,
+ -0.6608, +0.2718
+ ],
+ [
+ +0.3181, -0.0578, +0.2270, +0.2960, +0.3759, -0.0994, -0.0301,
+ +0.0580, +0.0580, -0.1176, -0.0211, -0.1902, +0.0512, -0.2255,
+ -0.8401, +0.0308, -0.1803, +0.0669, -0.0963, +0.4547, -0.1982,
+ -0.0926, +0.4024, +0.3177, -0.3376, -0.2049, +0.0444, -0.3649,
+ +0.2239, -0.0188, -0.1576, +0.0524, +0.3666, -0.1009, +0.0668,
+ +0.0819, -0.1313, +0.4450, -0.6085, -0.3848, -0.6414, +0.2856,
+ -0.1182, +0.0912, +0.0397, -0.5215, +0.3353, -0.2102, -0.5109,
+ +0.0882, +0.1674, +0.0885, -0.3224, +0.0901, +0.3159, +0.4244,
+ -0.4800, +0.1526, +0.0061, +0.1857, -0.0979, -0.2406, +0.0730,
+ +0.1405, -0.0050, +0.1824, -0.0160, -0.2087, -0.1628, -0.2413,
+ +0.2396, +0.6054, -0.6268, -0.0734, -0.1073, -0.1242, +0.2214,
+ -0.4174, -0.5380, +0.4581, +0.1509, -0.7234, -0.9114, -0.0332,
+ -0.2386, -0.0100, -0.2586, -0.2640, +0.0461, +0.1833, +0.1354,
+ -0.3236, +0.1699, +0.1157, -0.0966, -0.5738, +0.1736, -0.4470,
+ -0.5721, +0.3542, +0.4103, -0.3574, +0.4307, +0.0229, -0.1325,
+ +0.3490, -0.0651, +0.1874, -0.2291, +0.0530, +0.3738, +0.1955,
+ +0.1027, +0.1591, +0.2077, +0.2210, +0.1001, -0.3243, +0.2351,
+ -0.3068, -0.1417, -0.0853, -0.3813, -0.3430, +0.1111, -0.3707,
+ -0.4524, +0.3608
+ ],
+ [
+ +0.0381, -0.3280, -1.5348, -0.2310, +0.1609, +0.2576, -0.2199,
+ +0.1194, +0.1368, +0.5134, -0.6136, +0.5420, -0.0032, +0.0184,
+ +0.0213, -0.6279, -0.6801, +0.2122, -0.1931, +0.0708, -0.4318,
+ -0.1370, -0.2482, -0.0169, -0.4338, -0.1085, +0.6117, -0.1325,
+ -0.1302, +0.4041, +0.3929, -0.0002, +0.1998, +0.0515, -0.3162,
+ +0.4465, -0.1745, -0.3913, -0.5087, -0.1100, -0.2249, -0.2461,
+ -0.2671, +0.1915, +0.0139, +0.0838, -0.3395, -0.1856, +0.2210,
+ -0.0315, +0.2527, -0.0433, -0.1347, +0.2930, -0.2082, +0.2286,
+ +0.0255, -0.2495, -0.3158, -0.3498, +0.3091, -0.0525, -0.1256,
+ -0.3423, -0.0553, -0.0529, +0.1197, -0.7197, +0.7501, +0.0290,
+ -0.0370, -0.6256, +0.0000, +0.0983, -0.4345, +0.0663, +0.1609,
+ +0.0146, +0.2122, +0.1216, +0.1759, +0.0309, -0.4094, +0.2527,
+ +0.0841, +0.4982, -0.1519, -0.1223, +0.0607, -0.1248, +0.2532,
+ +0.1901, +0.1263, -0.2375, -0.1312, -0.2293, -0.2532, +0.5176,
+ -0.2599, -0.0855, -0.1362, -0.5210, +0.0224, +0.3870, +0.2114,
+ +0.3244, +0.4654, -0.7012, -0.0922, -0.9771, -0.2505, +0.5230,
+ -0.5313, -0.5063, -0.0315, -0.5956, +0.0800, -0.0199, -0.1976,
+ -0.9358, -0.4071, -0.1917, +0.1467, -0.2294, -0.1170, +0.0695,
+ +0.1403, -0.4278
+ ],
+ [
+ +0.1029, +0.1445, +0.3256, -0.0877, +0.5028, -0.2229, -0.0061,
+ +0.0184, -0.3173, -0.1645, +0.6963, -0.0568, -0.6695, -0.3263,
+ -0.1246, -0.6652, -0.0307, -0.2701, -0.3961, +0.3665, -1.0864,
+ +0.1994, +0.3494, +0.1447, +0.2856, +0.1528, +0.2521, +0.0676,
+ -0.0895, -0.1963, +0.1029, -0.0675, +0.0657, -0.0773, -0.4179,
+ +0.1854, -0.9043, -0.3480, +0.0186, -0.0853, -0.3580, -0.6232,
+ +0.1994, -0.3973, +0.1558, -0.2424, -0.6349, +0.2492, +0.0654,
+ -0.4719, -0.6174, +0.2362, -0.4908, -0.0194, -0.0402, -0.0680,
+ -0.0284, -0.0382, -0.3183, +0.0208, -0.7145, +0.0223, +0.0710,
+ -0.5593, +0.3360, -0.0591, -0.3271, -0.2059, +0.4912, +0.3903,
+ -0.0288, +0.5235, +0.3245, +0.0820, -0.1104, +0.0020, -0.2973,
+ -0.7333, +0.1925, -0.1251, +0.1177, +0.4494, +0.1400, -0.5209,
+ -0.1851, +0.0925, +0.1926, +0.3427, -0.2087, +0.1852, -0.5303,
+ -0.7136, -0.2598, -0.3725, +0.3738, +0.6966, -0.7630, -0.4744,
+ +0.1341, -0.0536, -0.2411, +0.4594, +0.1060, +0.2383, -0.1521,
+ -0.0214, -0.0980, +0.0557, +0.4497, +0.1257, +0.0278, -0.0656,
+ -0.5980, -0.0110, +0.0955, +0.4506, -0.4515, +0.1015, +0.1491,
+ +0.0256, +0.0409, -0.2116, -0.1528, +0.1721, +0.4331, -0.5740,
+ -0.1334, -0.1490
+ ],
+ [
+ +0.2384, +0.1767, +0.1947, +0.0587, +0.0436, -0.4647, +0.0460,
+ -0.3978, +0.3851, -0.6429, -0.0757, +0.0771, +0.3342, -0.5142,
+ -0.0504, -0.0614, +0.1761, +0.2849, -0.0273, -0.2299, -0.0279,
+ -0.1199, -0.2008, +0.3238, +0.1584, +0.2584, +0.0005, -0.0247,
+ +0.1486, -0.0961, -0.2141, +0.0457, +0.2077, -0.4971, +0.2886,
+ -0.0251, +0.2316, -0.0343, +0.2933, +0.2489, +0.1717, +0.3198,
+ +0.1717, -0.0490, +0.0506, -0.7074, -0.2308, -0.2186, +0.1620,
+ +0.0328, +0.1614, +0.1332, -0.0487, -0.3712, -0.2751, -0.1583,
+ +0.2474, +0.0419, -0.4341, -0.2045, +0.1139, -0.0188, -0.3290,
+ -0.0657, +0.0096, -0.2058, -0.4276, -0.1128, -0.2121, +0.3103,
+ -0.1906, +0.0304, +0.1177, -0.0511, +0.1057, -0.7063, +0.3458,
+ -0.2067, -0.0213, +0.1076, +0.0151, -0.1120, -0.2189, +0.1475,
+ -0.0077, -0.3843, -0.2418, -0.6991, +0.1953, -0.4116, -0.1400,
+ +0.1521, -0.5215, -0.1150, -0.0251, +0.0277, -0.0684, -0.0070,
+ +0.2457, +0.2435, -0.0386, -0.0929, -0.0177, -0.2300, +0.0347,
+ +0.1269, -0.1599, +0.2427, -0.3234, +0.0156, -0.2406, -0.1611,
+ -0.2369, +0.1289, -0.1268, -0.1186, -0.2554, +0.1911, +0.3922,
+ -0.7103, -0.2174, -0.3823, +0.1010, +0.1203, +0.4065, -0.1545,
+ +0.3333, -0.1270
+ ],
+ [
+ +0.0320, +0.3374, -0.2328, -0.5468, +0.3057, +0.0867, +0.1920,
+ +0.3238, +0.0958, +0.0865, -0.0978, -0.9149, +0.3992, -0.7304,
+ -0.7107, +0.1157, +0.3527, +0.1362, -0.1631, -0.1291, -0.1038,
+ +0.0851, +0.2969, -0.1787, -0.1327, -0.0016, -0.3977, -0.2473,
+ -0.1113, -0.3001, +0.5036, -0.0856, +0.1597, -1.0896, +0.3766,
+ +0.1266, +0.0147, -0.7126, +0.2683, -0.3971, -0.2376, +0.1728,
+ +0.0654, +0.0889, -0.2988, +0.0767, +0.1215, -0.4817, -0.0649,
+ -0.0350, -0.6930, -0.2363, -1.2543, -0.0226, -0.2209, +0.0390,
+ +0.2717, -0.1385, -0.3073, -0.1550, -0.5586, -0.4812, +0.2852,
+ -0.0278, -0.2483, +0.0254, +0.4223, -0.1026, -0.3841, -0.1561,
+ +0.2930, +0.3772, -0.0625, -0.0882, +0.2467, +0.1206, -0.0632,
+ +0.2479, -0.1358, +0.0352, -0.0730, +0.1995, +0.1430, +0.0082,
+ -0.1685, -1.1753, -0.7206, -0.2929, -0.0186, -0.2444, +0.4176,
+ -0.7420, -0.0811, +0.1876, -0.1151, +0.1599, -0.1971, -0.5971,
+ -0.1488, +0.1225, +0.0460, -0.0519, -0.1219, -0.1250, -0.1093,
+ -0.2462, -0.2120, +0.1604, +0.1361, +0.2755, +0.0633, +0.2230,
+ +0.6084, +0.2955, +0.1139, +0.0836, -0.5077, +0.2327, +0.0441,
+ -0.7536, -0.2307, +0.0111, +0.2659, -0.3169, -0.3589, -0.0047,
+ -0.0293, -0.1917
+ ],
+ [
+ +0.1849, +0.4786, +0.1204, -0.3298, +0.2282, +0.3278, -0.1501,
+ -0.0854, -0.0439, -0.2816, -0.5327, +0.3156, +0.3149, -0.0344,
+ -0.1886, -0.4860, -0.1034, +0.0903, +0.0569, +0.1075, +0.0721,
+ +0.1677, -0.0501, +0.3348, -0.2958, -0.5643, -0.5416, -0.0616,
+ +0.0486, -0.2416, +0.0556, -0.1499, -0.1884, +0.0063, -0.0879,
+ +0.2615, +0.2102, -0.0322, +0.5728, -0.7324, -0.6729, -0.1240,
+ -0.0435, -0.2956, +0.3191, -0.2177, -0.0368, -0.0261, -0.0666,
+ -1.2822, -0.0419, -0.2362, -0.0318, +0.3002, +0.0324, -0.0798,
+ +0.2130, +0.1350, +0.0346, +0.2781, +0.3518, +0.3837, -0.2617,
+ -0.9864, -0.1951, +0.0896, +0.1452, -0.0149, -0.4673, -0.2097,
+ +0.2540, -0.3603, -0.2436, -0.5239, +0.0675, -0.2038, -0.4511,
+ -0.9040, +0.2373, +0.2649, -0.7154, -0.0777, -0.2655, +0.0074,
+ -0.6301, +0.3651, -0.2757, +0.0316, -0.1454, -0.0407, -0.5047,
+ -0.4833, -0.3325, +0.1745, +0.2487, +0.3029, +0.5754, +0.1331,
+ +0.2339, -0.5040, -0.7949, +0.3252, -0.3651, -0.0125, -0.1580,
+ +0.0285, -0.0523, -0.2012, -0.0764, -0.1872, +0.4235, -0.7683,
+ +0.5005, +0.1516, -0.1920, +0.3039, -0.3789, -0.1149, -0.4491,
+ +0.1532, -0.0276, -0.5430, -0.1058, +0.0728, -0.0873, -0.0693,
+ -0.2627, -0.4874
+ ],
+ [
+ +0.1766, +0.2027, +0.2184, -0.2155, +0.2002, -0.0767, +0.0247,
+ +0.0769, +0.1097, -0.5324, +0.0716, -0.6547, +0.1549, -0.3553,
+ -0.1583, -0.6442, +0.2656, -0.0242, -0.2430, +0.2241, +0.1981,
+ +0.1088, +0.0831, -0.5510, +0.1084, -0.6368, +0.1111, -0.5365,
+ -0.3738, +0.3743, -0.1497, +0.1148, -0.3921, +0.0518, -0.0321,
+ -0.2311, +0.2755, -0.7492, -0.4376, -0.2182, -0.6939, -0.8483,
+ -0.2843, -0.1963, -0.2650, -0.1096, -0.1861, +0.0298, +0.0037,
+ +0.1153, -0.3358, -0.3163, +0.0478, -0.3209, -0.0710, +0.3083,
+ -0.2630, -0.1924, -0.1803, -0.1369, -0.3061, -0.1886, -0.0521,
+ -0.0039, -0.4548, -0.3571, +0.1289, +0.0565, -0.3850, -0.1660,
+ +0.3697, +0.0093, +0.1096, -0.7151, -0.5122, -0.1048, -0.0407,
+ +0.1807, -0.2780, -1.1252, -0.0171, -0.0800, -0.1387, -0.5066,
+ -0.1341, -0.4523, +0.2285, +0.1949, +0.2985, -0.3676, -0.0402,
+ +0.3106, -0.1804, -0.1138, -0.1518, +0.0386, -0.1846, +0.4102,
+ +0.1630, -0.3054, +0.1310, -0.0050, +0.1931, +0.2023, -0.4601,
+ -0.4869, -0.1454, -0.7915, -0.8167, -0.1141, -0.0829, -0.5105,
+ -0.2998, +0.1506, +0.1659, -0.0161, +0.1262, -0.2265, -0.0906,
+ -0.1643, -0.0997, -0.7213, -0.4537, -0.1466, -0.3031, -0.1776,
+ -0.3410, +0.3465
+ ],
+ [
+ -0.0680, -0.5316, -0.5061, -0.0773, -0.3060, -0.2216, -0.6029,
+ -0.1825, -0.1359, +0.2300, +0.0623, +0.0920, +0.0022, -0.1120,
+ -0.1106, -1.1256, +0.0279, -0.3801, +0.0112, +0.1688, +0.1709,
+ -0.5387, -0.0696, -0.3568, -0.4497, +0.4913, -0.0399, -1.3545,
+ -0.2932, +0.1045, +0.3458, -0.4757, -0.0703, -0.1544, -0.6656,
+ +0.3997, -0.0279, +0.2120, -1.2224, -0.6230, -0.4677, -0.1049,
+ +0.2119, -0.1797, -0.4644, -0.1679, +0.2749, -0.1451, -0.4456,
+ +0.3104, -0.4102, +0.3043, +0.5440, -0.1511, +0.1171, +0.3151,
+ -0.0670, -0.1808, -0.5695, -0.5017, +0.0862, -0.3984, +0.0258,
+ -0.5704, +0.1754, -0.0489, +0.0302, +0.4248, -0.1910, -0.5007,
+ -0.2559, -0.0414, -0.1863, +0.1481, -0.0454, -0.3999, +0.0606,
+ +0.1871, +0.1180, -0.0014, -0.4116, -0.8299, +0.6789, +0.0242,
+ -0.2057, -0.3620, +0.0898, +0.4069, +0.0505, +0.1478, -0.2953,
+ -0.1294, +0.3536, -0.2027, -0.1965, +0.2124, -0.0305, -0.1242,
+ +0.3511, +0.0112, -0.1523, -0.2483, +0.1767, +0.0946, -0.0883,
+ -0.2642, -0.1009, -0.1412, -0.1936, -0.0337, -0.0854, +0.1496,
+ +0.1209, +0.1613, -0.2123, -0.5184, -0.5626, -0.1087, -0.1012,
+ -0.6158, -0.7041, -0.4685, -0.8154, +0.2760, -0.2103, -0.1968,
+ +0.0849, -0.3954
+ ],
+ [
+ +0.2532, +0.4208, -0.3291, -0.5551, -0.1859, -0.1518, -0.2786,
+ +0.0658, -0.6929, -0.2819, -0.2395, +0.1718, +0.0343, +0.0182,
+ +0.0734, -0.8299, -0.2525, +0.1285, +0.0562, -0.1593, -0.2454,
+ -0.1303, -0.2009, -0.2577, +0.2121, -0.4224, -0.4803, -0.2205,
+ +0.4951, -0.0603, -0.0738, -0.0561, +0.2528, -0.7239, +0.2362,
+ -0.1281, -0.2817, -0.0915, -0.3098, -0.3482, -0.1657, +0.1685,
+ +0.0365, -0.1210, -0.4351, +0.1768, -0.2815, -0.2552, -0.8653,
+ +0.2226, +0.4609, -0.5362, -0.1000, -0.5827, -0.6283, -0.1828,
+ -0.5187, -0.4818, -0.2862, -0.3698, -0.4264, +0.5897, +0.3011,
+ +0.1451, +0.1300, -0.6738, +0.1766, +0.4159, -0.1141, +0.4150,
+ -0.2877, -0.4758, +0.0208, +0.0290, -0.1260, -0.2702, -0.7108,
+ -0.0338, +0.2733, +0.0843, -0.0556, -0.0368, +0.0105, -0.3436,
+ +0.0248, -0.1892, -0.2123, -0.0928, +0.2068, -0.3971, +0.1089,
+ +0.3620, -0.1929, -0.5377, -0.1463, -0.1753, -0.1031, -0.2935,
+ +0.4052, +0.0367, +0.0097, -0.5875, +0.1436, -0.4216, -0.0872,
+ -0.2351, -0.3716, -0.1434, -1.0513, +0.2828, -0.1845, +0.1664,
+ -0.1173, +0.2712, +0.0878, -0.7084, -0.6339, -0.4937, +0.1035,
+ -0.2160, -0.4060, -0.2531, -0.6691, +0.1202, +0.2531, -0.0490,
+ +0.5874, +0.0633
+ ],
+ [
+ -0.6739, +0.0277, -0.9564, -0.5067, -0.5287, +0.0684, -0.5332,
+ -0.2934, +0.2182, +0.1192, -0.4239, -0.3156, -0.0208, +0.4953,
+ -0.3716, -0.3657, -0.4834, -0.1870, -0.1509, -0.3200, -0.0222,
+ +0.0546, +0.3764, +0.5946, -0.4095, +0.2046, -0.2208, +0.1072,
+ -0.4266, -0.7344, -0.1398, -0.3482, +0.1835, +0.0850, -0.2169,
+ -0.1673, +0.1917, -0.0598, -0.0835, +0.3213, -0.4629, +0.0055,
+ -0.0855, -0.0968, -0.6663, -0.4341, -0.3010, -0.5688, +0.2849,
+ +0.1352, -0.1461, +0.0679, +0.1243, +0.0837, +0.2299, +0.3890,
+ +0.3232, +0.8568, -0.3093, +0.1023, -0.1423, -0.0950, +0.3483,
+ -0.0398, -0.8729, +0.0589, -0.3755, -0.1726, -0.2203, -0.3867,
+ -0.0227, -1.0963, -0.0057, +0.0516, -0.2886, +0.1596, +0.2880,
+ +0.1165, +0.0612, +0.2892, -0.6804, +0.2979, +0.1742, -0.0116,
+ +0.2316, -0.0595, +0.0568, -0.5258, -0.2719, -0.4404, +0.1292,
+ +0.1016, +0.7038, -0.0262, +0.5274, -0.0229, +0.0430, +0.2201,
+ +0.1085, -0.0375, +0.1192, -0.0778, +0.0535, -0.5996, +0.3843,
+ -0.5089, +0.0677, -0.2134, -0.5909, +0.0015, -0.7516, +0.0565,
+ +0.0375, -0.5614, -0.1333, +0.2093, -0.0427, -0.4205, -1.4405,
+ +0.3511, -0.1710, -0.5402, -0.2186, -0.1229, -0.5740, -0.1826,
+ -0.0947, -0.2646
+ ],
+ [
+ -0.4790, -0.0459, -0.7397, -0.1887, -0.0117, -0.0881, -0.2339,
+ +0.4489, -0.2226, -0.2678, -0.4339, -0.5233, -0.4704, -0.2454,
+ -0.6791, +0.5416, +0.1632, +0.0939, +0.2976, +0.4227, -0.4494,
+ -0.5834, -0.0442, +0.0945, -0.4829, -0.1668, +0.1462, -0.0841,
+ +0.0265, -0.5589, +0.1268, +0.6885, +0.1927, -0.3751, +0.1673,
+ +0.2637, +0.1409, -0.2660, +0.0257, -0.0269, -0.2051, +0.4255,
+ -0.1496, +0.1084, -0.0217, -0.2359, -0.1428, -0.1115, -0.7085,
+ -0.6233, -0.0985, -0.1075, -0.1553, -0.2027, +0.1923, +0.0471,
+ +0.2331, -0.7869, -0.1220, +0.1538, +0.1171, -0.1364, +0.2306,
+ -0.3217, -1.2153, -0.2076, -0.1103, -0.3231, -0.6678, -0.4851,
+ -0.1963, -0.6715, -0.6025, +0.2298, -0.4343, -0.1760, -0.4037,
+ -0.2442, +0.2234, -0.1880, +0.2596, -0.1924, -1.0538, +0.1892,
+ -0.1999, -0.0033, -0.0755, +0.0571, -0.3725, +0.0816, -0.3538,
+ -0.3673, -0.1607, -0.7918, +0.1611, +0.4097, -0.2851, +0.3155,
+ +0.2837, -0.7129, +0.2556, -0.7155, -0.2264, -0.0045, +0.2039,
+ -0.0958, -0.3221, +0.1626, -0.3246, -0.3097, -0.1555, -0.0424,
+ -0.0175, +0.2186, -0.0899, -0.3513, -0.3811, -0.4246, -0.1244,
+ -0.1209, +0.1675, -0.5267, -0.0279, +0.4418, +0.0478, +0.1246,
+ +0.0393, -0.4219
+ ],
+ [
+ -0.3571, +0.0904, -0.8551, +0.4132, -0.0919, +0.3857, +0.2689,
+ +0.2051, +0.1931, -0.3377, -0.3208, -0.0723, -0.1699, +0.0462,
+ -0.1263, +0.0483, +0.1950, -0.1277, +0.0313, +0.2242, +0.0103,
+ -0.2061, +0.0631, +0.1930, -0.0647, -0.4123, +0.1690, +0.1474,
+ +0.1182, -0.5403, +0.3640, +0.0169, +0.3996, +0.2360, +0.2264,
+ +0.0977, -0.4711, +0.3267, -0.2800, -0.4045, -0.0261, -0.0814,
+ -0.1084, +0.0173, +0.0070, -0.1826, +0.1416, -0.3700, +0.1904,
+ +0.3461, -0.8709, +0.2058, -0.0601, -0.1735, -0.1307, -0.0786,
+ -0.0667, +0.0989, -0.1120, +0.5435, +0.2793, +0.3009, -0.1373,
+ +0.1923, +0.3372, -0.0255, -0.4204, +0.0504, +0.2350, +0.1833,
+ -0.0786, -0.2449, -0.0600, -0.1826, -0.6286, -0.0817, -0.2410,
+ +0.1011, +0.2879, -0.7720, +0.0685, -0.5338, -1.0387, -0.2374,
+ +0.0941, +0.2234, +0.1887, -0.6712, +0.0789, +0.0920, -0.1733,
+ +0.2348, +0.3533, +0.5173, -0.2887, +0.1298, -1.0297, -0.0811,
+ +0.3376, +0.4740, -0.3197, -0.1907, -0.1645, -0.5704, -0.1747,
+ +0.1463, +0.3165, +0.3489, -0.0581, -0.2501, +0.1131, -0.1146,
+ -0.2154, -0.1804, -0.2339, -0.2814, -0.5182, -0.3433, +0.3677,
+ +0.2729, -0.1904, -0.0585, -0.7208, +0.3472, -0.0146, +0.2520,
+ -0.2723, -0.5874
+ ],
+ [
+ -0.5168, -0.1916, +0.0044, -0.2001, -0.4914, -0.2367, +0.1037,
+ -0.3593, -0.2739, +0.0966, -0.4070, -0.6904, -0.6564, +0.0903,
+ -0.2040, +0.4127, -0.4820, +0.1590, +0.1689, -0.6444, +0.2427,
+ +0.0580, -0.2541, -0.0060, +0.1797, -0.7206, +0.0552, -0.2466,
+ +0.0206, +0.4403, +0.2936, -0.4458, +0.1578, -0.2735, +0.1138,
+ +0.3035, +0.3536, -0.0996, -0.1689, -0.0803, +0.0302, -0.0041,
+ +0.2768, +0.0295, -0.5365, -0.1148, +0.1867, +0.4169, +0.1963,
+ -0.1607, +0.4705, -1.0241, +0.4417, +0.1275, -0.7696, -0.2660,
+ +0.0380, -0.2972, +0.3949, +0.7762, -0.3281, +0.0599, +0.3288,
+ -0.4384, -0.1356, -0.1655, +0.0742, -0.2041, -0.1239, -0.1804,
+ +0.2637, +0.0942, -0.1011, -0.2973, -0.4499, +0.0090, +0.1412,
+ -0.2019, +0.0945, +0.1347, -0.1332, -0.3886, +0.1739, +0.1864,
+ +0.0391, -0.0350, +0.3963, -0.2367, +0.0131, -0.5565, -0.2354,
+ +0.3302, +0.1141, -0.2861, -0.4460, +0.4304, -0.1393, -0.4753,
+ -0.1158, -1.3481, +0.0292, -0.1015, -0.1453, +0.2802, +0.0700,
+ -0.3325, +0.0110, +0.2497, +0.0056, +0.3542, -0.2658, +0.2565,
+ +0.1598, -0.0339, -0.3039, -0.2208, -0.2119, -0.0196, +0.2157,
+ -0.3472, -0.3380, -0.0314, -0.3920, -0.3210, +0.3201, -0.8747,
+ +0.1812, +0.0732
+ ],
+ [
+ -0.5735, -0.1147, -0.1845, -0.0670, -0.3959, +0.0605, +0.0751,
+ -1.3236, -0.2729, -0.0563, +0.0870, -0.2487, -0.2976, -0.1418,
+ -0.0036, -0.3945, +0.2133, +0.1156, +0.0328, -0.2110, -0.0954,
+ +0.0828, +0.0342, +0.2200, -0.0155, -0.2676, +0.1296, +0.2238,
+ +0.3469, -0.4331, +0.3707, -0.0087, +0.2342, -0.1123, -0.2393,
+ +0.0042, -0.7079, -0.5531, -0.2589, -0.1329, -0.2473, -0.0557,
+ -0.1092, -0.1055, +0.3648, +0.0103, -0.2566, +0.0428, +0.3451,
+ -0.1363, -0.5322, -0.7636, -0.3877, +0.2084, +0.0500, -0.9000,
+ +0.0186, -0.6299, -0.6176, +0.2841, -0.6676, +0.1776, -0.3414,
+ -0.3621, -0.4323, -0.8091, +0.1711, -0.5524, -0.1845, -0.1440,
+ +0.2521, +0.3597, -0.2215, -0.0636, -0.1948, -0.0981, -0.0632,
+ +0.3646, -0.7443, -0.2697, +0.0858, -0.1100, -0.2158, +0.2193,
+ -0.1480, -0.7157, +0.0280, +0.1051, -0.2165, -0.0942, -0.0988,
+ -0.0529, +0.1711, +0.5135, -0.4368, +0.2158, -0.1203, +0.2175,
+ +0.0274, -0.1588, +0.0862, -0.2315, +0.2650, -0.4179, +0.0053,
+ +0.2025, +0.1570, -0.4194, +0.3459, -0.6148, -0.0766, -0.5666,
+ +0.1655, -0.1656, +0.0047, +0.1534, +0.0364, -0.1854, -0.0359,
+ -0.1716, -0.3132, -0.1275, +0.3301, +0.0841, +0.0211, -0.1663,
+ -0.1611, +0.3612
+ ],
+ [
+ -0.3046, +0.1990, +0.3593, -0.0441, +0.0111, -0.3952, +0.0887,
+ +0.2970, +0.0432, -0.3783, -0.1590, -0.1455, +0.0672, +0.3143,
+ -0.4494, -0.2105, -0.2141, -0.5621, -0.5350, +0.1795, +0.0950,
+ -0.6389, -0.1119, -0.3228, -0.1351, -0.0998, +0.1916, -0.6883,
+ -0.0802, -0.2211, -0.4179, -0.4322, -0.1921, +0.2114, -0.3894,
+ +0.3510, -0.8963, -0.2446, -0.3355, -0.2554, +0.3715, -0.0832,
+ +0.3089, +0.1687, -0.4003, +0.2255, +0.0172, -0.0353, -0.3352,
+ +0.1071, -1.2214, -0.2593, +0.1820, -0.3545, +0.0520, +0.0625,
+ -0.3255, +0.0246, -0.9975, +0.5751, -0.1415, +0.1819, -0.1992,
+ +0.0300, -0.1407, -0.6492, +0.0380, -0.1231, -0.0581, +0.2151,
+ +0.2173, +0.0064, -0.1583, +0.0302, +0.0198, -0.1276, -0.3126,
+ -0.2499, -0.7244, -0.5974, -0.0122, -0.3023, -0.3659, +0.0236,
+ -0.8076, -0.0052, -0.4533, +0.1279, +0.1329, -0.4658, -0.5219,
+ -0.0994, -0.3155, -0.2044, -1.4585, -0.4960, +0.6144, -0.2893,
+ +0.0656, -0.3623, +0.0771, -0.0557, -0.3057, -0.0149, -0.1504,
+ +0.1180, -0.0191, -0.2747, +0.1425, -0.5355, -0.2589, -1.0663,
+ -0.0238, +0.2357, -0.0646, -0.8185, -0.0544, +0.0328, -0.0684,
+ -0.0288, -0.6393, +0.0760, -0.3438, -0.4502, -0.1043, +0.2516,
+ +0.2664, -0.2895
+ ],
+ [
+ +0.0107, -0.3197, +0.2582, +0.1588, -0.7646, -0.7069, -0.4099,
+ +0.1225, +0.2743, -0.3283, -0.0027, +0.1298, -0.1093, +0.4504,
+ -0.1028, -0.5416, -0.2146, +0.2392, -0.0145, +0.1768, +0.0453,
+ +0.1953, -0.8660, -0.5489, +0.0746, +0.3120, +0.1501, +0.0138,
+ -0.7171, +0.1558, -0.8054, +0.0637, -0.3851, -0.4554, -0.0707,
+ +0.0844, +0.1226, +0.0906, -0.6054, +0.5808, +0.0931, -0.4798,
+ -0.1459, -0.3292, +0.1951, -0.2652, -0.2279, -0.5004, +0.7729,
+ -0.2178, -0.6389, -0.2515, +0.1850, -0.6675, -0.0282, -0.3199,
+ +0.1368, +0.3026, -0.4689, -0.0329, +0.2913, +0.0254, -0.3636,
+ -0.1038, +0.1523, +0.1738, -0.1826, +0.0448, -0.0613, -0.0619,
+ +0.0614, -0.1873, -0.3742, +0.0553, -0.1018, +0.0197, +0.1035,
+ -0.2413, -0.4748, +0.2443, -0.1595, +0.1139, -0.2503, +0.3971,
+ -0.5707, -0.6110, +0.3676, -0.6585, -0.0983, -0.8527, +0.5715,
+ -0.5112, +0.0883, -0.1990, -0.1421, +0.5473, -0.0631, -0.3381,
+ -0.0705, +0.2045, -0.3428, -0.3719, +0.1965, -0.4464, -0.2206,
+ -0.0407, -0.3212, -0.0742, -0.0010, -0.0920, +0.0179, -0.1233,
+ -0.4241, +0.0697, +0.0483, -0.4507, -0.7664, -0.4521, -0.2175,
+ -0.3721, -0.3304, -0.2537, +0.1789, -0.2410, -0.0701, +0.3168,
+ -0.2336, -0.2128
+ ],
+ [
+ +0.1155, -0.0102, +0.4249, -0.0738, -0.5340, +0.0663, -0.0927,
+ +0.1452, -0.3015, -0.2405, -0.6384, +0.0373, -0.0334, +0.1594,
+ -0.0984, -0.3201, +0.3151, -0.3141, -0.0241, -0.2851, +0.0472,
+ +0.5239, +0.2989, +0.0661, +0.0884, +0.1384, +0.1193, +0.3296,
+ -0.3185, +0.2506, +0.1458, +0.1626, +0.2309, -0.3974, -0.0698,
+ -0.1044, +0.0031, -0.5501, +0.0439, -0.7990, +0.2289, -0.1844,
+ +0.3783, -0.4319, +0.1479, -0.1089, -0.0206, +0.0524, +0.2799,
+ +0.1135, -0.2630, -0.3034, -0.0279, -0.3430, -0.3194, +0.2728,
+ -0.2198, +0.0995, -0.5879, -0.0968, -0.6351, -0.2687, +0.2761,
+ -0.1994, +0.1186, +0.0766, -0.0157, -0.4284, +0.4550, +0.0266,
+ +0.1227, +0.1949, +0.0795, -0.1303, -0.0641, -0.2911, -0.2093,
+ +0.1755, +0.3525, +0.2074, +0.0776, +0.0871, -0.4309, +0.0466,
+ +0.2179, -0.7288, -0.3884, +0.0433, +0.0226, -0.5845, -0.3762,
+ +0.1555, -0.1571, +0.1242, -0.0361, +0.0694, -0.0607, -1.1456,
+ -0.2432, +0.2734, -0.0147, +0.0134, -0.1083, -0.1578, +0.2299,
+ +0.1616, +0.3512, -0.1246, +0.1847, -0.1015, +0.3420, +0.1070,
+ +0.0237, +0.1442, +0.0974, -0.0842, -0.0235, +0.2302, -0.1871,
+ +0.0759, -0.7443, +0.0672, -0.9173, -0.2906, +0.2102, -0.0130,
+ -0.7445, +0.2416
+ ],
+ [
+ +0.0570, -0.1107, -0.1294, +0.2502, -0.2984, +0.0134, +0.2178,
+ -0.2031, -0.0498, -0.9746, -0.1293, +0.3008, -0.2820, +0.2322,
+ +0.0366, +0.0613, -0.2685, +0.0761, +0.0324, +0.6167, -0.0038,
+ -0.3098, +0.1486, -0.2141, -0.1495, -0.0758, -0.0287, -0.1225,
+ -0.0489, -0.2928, -0.0031, -0.2655, -0.2361, +0.0487, +0.1637,
+ -0.0362, -0.6581, -0.2809, -0.2362, -0.3010, -0.2808, +0.1002,
+ +0.3643, +0.1101, -0.5130, -0.1977, -0.7063, +0.0310, -0.1288,
+ -0.0684, -0.2172, -0.9830, -0.9522, +0.2543, -0.2441, -0.2201,
+ -0.3622, -0.6192, -0.0511, -0.3572, -0.2073, -0.3067, -0.5459,
+ -0.8507, +0.1938, -0.8735, -0.1393, +0.1941, -0.5221, -0.2935,
+ -0.1622, +0.2692, -0.6518, -0.0784, -0.0032, +0.0453, +0.0612,
+ +0.0740, +0.0828, -1.5962, -0.0105, -0.2185, +0.1251, +0.2271,
+ -0.0830, -0.3206, +0.2678, -0.3253, +0.1302, -0.2226, -0.3965,
+ +0.0605, +0.2157, +0.0511, +0.1486, -0.0471, -0.7112, +0.1349,
+ +0.0479, -0.3281, +0.0545, -0.1693, +0.1596, +0.0366, +0.3659,
+ +0.4518, -0.5676, +0.0444, -0.4920, -0.4001, -0.3816, -0.3445,
+ +0.3152, +0.2686, +0.0873, -0.6441, -0.1246, +0.0525, -0.0302,
+ -0.6167, -0.3785, -1.3627, -0.6195, -0.2583, -0.0883, +0.0941,
+ -0.0932, +0.1709
+ ],
+ [
+ -0.0902, -0.0489, -0.5621, +0.1108, -0.0253, +0.2008, -0.0230,
+ -0.1481, -0.1891, -0.0729, -0.0272, +0.0692, +0.0149, +0.4408,
+ +0.5853, +0.1148, -0.5399, +0.1653, -0.0507, -0.0729, +0.0799,
+ -0.5047, +0.0211, +0.0545, -0.1527, -0.0146, +0.1207, +0.2242,
+ +0.5105, -0.1659, -0.3076, +0.0075, -0.0780, -0.0728, -0.9238,
+ +0.0010, -0.2337, +0.1043, +0.3628, -0.3925, +0.0371, -0.0933,
+ -0.1642, -0.4299, +0.1116, +0.3309, +0.1078, -0.1654, +0.1247,
+ -0.0723, +0.1428, -0.0070, +0.2646, -0.2366, -0.2596, +0.0486,
+ +0.1331, -0.3141, +0.2621, +0.1173, +0.1017, +0.3161, -0.3979,
+ +0.0467, -0.0058, -0.1483, -0.4923, +0.3230, +0.3847, -0.8560,
+ -0.1140, -0.2858, +0.0235, +0.0051, +0.2581, -0.1739, +0.0148,
+ -0.0270, -0.1098, -0.4381, +0.2964, +0.0043, -0.2012, +0.3487,
+ +0.0805, -0.3836, +0.3054, -0.2178, -0.1003, -0.8272, -0.8094,
+ -0.1763, -0.4160, -0.0718, +0.0883, -0.5837, -0.0250, -0.2355,
+ +0.2095, -0.3145, -0.4140, -0.1567, +0.1556, -0.1557, -0.0385,
+ +0.4225, -0.4201, +0.4154, -0.1397, +0.0064, -0.4551, +0.0587,
+ -0.3060, +0.2072, -0.1990, -0.6681, +0.4071, +0.1429, +0.1864,
+ +0.0583, +0.3094, +0.1376, -0.0151, +0.2482, +0.0534, +0.3590,
+ -0.0524, +0.0072
+ ],
+ [
+ +0.2165, -0.0784, +0.4527, -0.2131, -0.0842, -0.2151, +0.2852,
+ +0.3085, -0.0545, +0.0476, -0.3126, -0.1004, -0.3292, -0.3253,
+ -0.0299, -0.3426, -0.6258, +0.2322, +0.1995, -0.7055, -0.4208,
+ -0.2351, +0.5525, -0.0116, -0.1168, +0.3035, -0.4497, -0.0070,
+ -0.6314, +0.2021, +0.2401, -0.6943, +0.6166, +0.0522, -0.1277,
+ +0.0814, +0.1048, -0.1549, +0.0236, -0.0543, +0.1134, -0.1267,
+ +0.0161, +0.0846, -0.3257, +0.3672, +0.4620, -0.0554, -0.6860,
+ -0.5655, -0.0291, -0.0336, -0.0591, -0.0668, +0.4952, -0.6696,
+ -0.6313, -0.4199, +0.1644, -0.1448, +0.3275, +0.0785, +0.1629,
+ -0.3694, -0.0415, +0.3981, -0.3228, -0.4313, -0.2086, -0.3006,
+ +0.0319, -0.1707, -0.6463, +0.4033, -0.2931, -0.2915, -0.0374,
+ -0.5228, -0.0761, -0.0541, -0.0648, -0.4858, -0.3321, +0.0406,
+ +0.0690, +0.1793, +0.3161, +0.3441, -0.1787, +0.1655, +0.1323,
+ +0.0511, -0.5903, -0.4039, -0.5803, -0.0993, +0.0511, -0.4996,
+ -0.2091, -0.8687, +0.3873, -0.8987, -0.7894, +0.4019, +0.2001,
+ -0.0819, -0.2723, -0.1041, -0.0835, +0.3914, -0.1363, -0.0651,
+ +0.1017, +0.1881, -0.1245, +0.1765, +0.1574, -0.4187, -0.3413,
+ -0.4192, +0.0699, +0.2365, -0.2552, -0.6480, -0.2559, -0.0381,
+ -0.2464, -0.2568
+ ],
+ [
+ +0.1548, +0.0221, +0.3021, +0.0748, -0.0730, -0.3777, -0.0878,
+ +0.1624, +0.0181, +0.0029, -1.0661, -0.2232, -0.0371, +0.2084,
+ +0.0641, +0.3700, +0.2076, -0.1308, -0.6938, -0.0521, +0.3410,
+ -0.1052, +0.0010, +0.1400, -0.3497, -0.0732, +0.0856, +0.1817,
+ -0.3963, -0.3211, +0.1612, +0.0391, +0.1267, +0.1567, -0.8114,
+ +0.0540, -0.3109, -0.1081, +0.1441, +0.1741, -0.1098, +0.2501,
+ +0.1449, -0.0120, -0.1075, -0.2483, -0.7078, -0.2693, -0.0336,
+ +0.0171, -0.0570, +0.1460, +0.1243, -0.1844, +0.1645, -0.4268,
+ +0.0438, -0.2597, +0.0547, -0.1758, +0.0263, -0.8264, +0.0728,
+ -0.2166, -0.1181, +0.2654, -0.2549, +0.0277, +0.1403, +0.4358,
+ -0.0468, +0.0663, -0.5248, +0.2055, -0.2036, -0.2702, -0.7653,
+ +0.1719, +0.0243, +0.0066, +0.0388, -0.1156, -0.2506, -0.1971,
+ +0.1007, -0.0745, +0.0724, -0.1242, +0.0428, +0.0739, +0.1192,
+ +0.1407, -0.0524, +0.0955, -0.0253, -0.0342, -0.5003, +0.0988,
+ +0.4093, +0.0309, -0.1069, -0.4025, +0.0368, -0.0331, -0.0844,
+ +0.1159, -0.0163, +0.1731, +0.3613, -0.0142, -0.0990, +0.0854,
+ +0.0900, -0.1528, -0.1269, -0.3659, -0.0846, +0.1304, +0.0177,
+ +0.2548, +0.1939, -0.0656, -0.1266, +0.0675, +0.0898, -0.0352,
+ -0.0179, -0.0786
+ ],
+ [
+ -0.1477, -0.3154, +0.0705, +0.0553, -0.0120, -0.2545, -0.1162,
+ -0.0357, -0.0614, -0.1063, -0.1024, -0.2153, -0.2259, -0.0393,
+ -0.6030, -0.7395, +0.2510, +0.6092, -0.1453, +0.1808, +0.0889,
+ +0.0641, -0.1695, -0.1308, -0.7268, +0.1051, -0.3328, -0.5555,
+ -0.1323, -0.0470, +0.4817, -0.2015, -0.1558, -0.2925, -0.3102,
+ -0.1149, -0.1001, -0.2164, -0.1036, +0.3618, +0.3640, +0.0790,
+ +0.1367, +0.1737, -0.3290, -0.2891, +0.3472, +0.0828, +0.2550,
+ +0.0813, -0.2269, -0.5814, +0.4380, -0.3854, -0.1073, -0.3434,
+ -0.2344, -0.3333, -0.9712, +0.3074, -0.0863, +0.0101, +0.4935,
+ -0.4539, +0.2815, +0.4703, -0.1730, -0.4645, -0.0182, -0.6704,
+ +0.4409, +0.0128, +0.3440, +0.0742, -0.0970, +0.0381, -0.9197,
+ +0.1764, -0.3166, -0.5216, +0.1401, +0.1343, -1.0300, +0.0069,
+ +0.3072, +0.0852, -0.2241, -0.0990, -0.1649, -0.0966, -0.0429,
+ -0.0274, +0.0635, +0.3952, -0.1940, +0.1375, -0.3230, +0.6582,
+ +0.1195, +0.0523, +0.0047, -0.4729, +0.2348, -0.1884, +0.3227,
+ +0.0247, +0.1520, -0.4772, -0.0548, +0.1463, +0.2491, -0.0230,
+ +0.2104, -0.0490, -0.4887, -0.7157, +0.4019, +0.1893, +0.1334,
+ -0.3488, -0.0239, -0.6403, -0.5436, -0.3965, +0.0472, +0.0951,
+ +0.3826, -0.0119
+ ],
+ [
+ +0.2345, +0.0402, +0.3096, +0.1290, -0.0478, +0.1970, +0.0213,
+ -0.4571, +0.3814, -0.0410, -0.5314, -0.2755, -0.3864, -0.9906,
+ -0.6441, -0.0119, +0.5029, +0.0528, +0.1426, +0.1558, -0.3429,
+ +0.3553, -0.0140, -0.1257, +0.5183, -0.1416, +0.1306, -0.1761,
+ +0.4427, +0.1535, +0.0231, +0.2305, -0.1755, -0.5971, +0.3964,
+ +0.4374, -0.4033, -0.1754, +0.0906, -0.0307, -0.6401, +0.3662,
+ -0.0488, -0.0305, -0.1799, -0.9114, -0.6223, -0.6197, +0.1350,
+ -0.2145, +0.0602, +0.4021, -0.5092, -0.3139, +0.2932, +0.0838,
+ -0.2362, -0.0395, -0.5941, +0.0945, -0.0716, +0.2605, -0.4417,
+ +0.3200, +0.2494, +0.0426, -0.2447, -0.5307, +0.0455, -0.1078,
+ +0.2131, -0.2504, -0.3621, +0.1624, -0.1116, +0.1532, +0.1341,
+ -0.2960, -0.0485, +0.2547, -0.1497, +0.5129, -0.7462, -0.2898,
+ -0.2437, -0.3651, +0.2329, -0.0681, -0.0266, -0.5809, -0.3785,
+ +0.3757, +0.1572, -0.0039, -1.0997, -0.3780, -0.0220, -0.6294,
+ -0.5320, -0.0276, -0.1373, +0.4767, +0.0286, -0.6791, -0.1094,
+ +0.2245, +0.7109, +0.2029, -0.2408, +0.1082, +0.3360, +0.3084,
+ +0.0412, -0.0498, -0.0024, +0.0016, -1.4137, -0.2534, -0.1986,
+ -0.4153, +0.7093, -0.2851, -0.3148, +0.4090, -0.2257, -0.3811,
+ +0.0754, +0.1079
+ ],
+ [
+ +0.1737, -0.1012, +0.3843, -0.3052, +0.0454, -0.0999, +0.0607,
+ +0.5805, -0.0379, -0.1394, +0.1873, +0.2086, -0.0369, +0.2190,
+ -0.9182, -0.1614, +0.0378, +0.0651, -0.3026, +0.1249, -0.0495,
+ +0.7594, +0.2221, -0.1335, +0.4775, -0.3486, -0.3901, -0.2565,
+ -0.2424, -0.2014, -0.4993, -0.3226, -0.4516, -0.0422, -0.1739,
+ +0.2270, +0.2250, +0.2292, +0.5843, +0.3938, -0.8007, -0.1657,
+ -0.2410, +0.0172, -0.1222, +0.3231, -0.2751, -0.2512, +0.2162,
+ -0.6735, -0.1592, -0.5736, +0.3512, -0.1531, +0.0767, -0.1251,
+ -0.3526, +0.2640, +0.3694, +0.0025, -0.0883, -0.9067, +0.1201,
+ +0.0180, +0.1013, +0.1774, +0.0458, +0.1053, -0.1279, +0.1314,
+ -0.7170, -0.0099, +0.0331, -0.6149, -0.3880, +0.3317, -0.1987,
+ -0.1860, +0.2181, -0.2855, +0.0181, +0.1234, +0.0470, -0.4842,
+ +0.1452, +0.0126, -0.0338, +0.0576, -0.1719, +0.4222, +0.0425,
+ -0.1328, -0.2182, -0.3864, -0.2636, -0.4534, +0.3275, -0.4392,
+ -0.3175, -0.0483, +0.0194, -0.2320, +0.1536, -0.0455, +0.2573,
+ -0.3990, -0.7663, +0.0444, +0.2442, +0.2573, -0.4178, +0.0640,
+ -0.1134, +0.0385, -0.0557, -0.1481, -0.1792, +0.1467, +0.0214,
+ +0.0728, -0.3110, +0.2292, -0.8796, -0.1230, -0.3657, +0.3918,
+ +0.4578, +0.0213
+ ],
+ [
+ -0.0058, -0.0501, -0.1675, +0.2440, +0.0982, -0.3081, +0.2197,
+ -0.0078, +0.2634, +0.4613, +0.0454, +0.0953, +0.2481, -0.9030,
+ -0.5912, -0.1769, +0.3100, -0.0666, -0.4307, -0.2750, +0.0457,
+ +0.4329, +0.1131, +0.1623, -0.4575, -0.0464, +0.0587, +0.0037,
+ +0.1761, +0.1243, -0.3456, -0.1771, +0.1526, +0.1889, +0.0453,
+ -0.0169, +0.2543, -0.2468, -0.1749, -0.1054, +0.1356, -0.0753,
+ -0.2053, -0.5136, +0.1298, -0.3350, -0.3511, -0.6631, +0.1640,
+ +0.0080, -0.5760, -0.1730, -0.4837, +0.0082, -0.3955, -0.1565,
+ +0.1675, +0.3669, +0.4185, -0.1695, +0.6183, -0.4073, -0.2162,
+ -0.4735, -0.1205, -0.6054, -0.1156, +0.0477, +0.1337, -0.3585,
+ +0.0539, -0.3033, -1.1556, -0.6334, +0.2199, +0.1659, -0.5817,
+ +0.1128, -0.3548, -0.0180, -0.3140, -0.3119, -0.3624, +0.3207,
+ -0.1126, +0.2188, +0.1764, -0.2787, -0.6278, -0.0367, +0.4690,
+ -0.1529, +0.0098, -0.4824, +0.0185, -0.1893, -0.7196, +0.0138,
+ -0.7285, -0.1746, +0.2740, -0.6991, -0.8272, -0.0170, -0.2122,
+ +0.0546, -0.0070, +0.0135, -0.9043, -0.2043, -0.0655, +0.0533,
+ -0.2891, -0.3379, +0.1854, +0.0024, -0.4407, -0.4790, -0.6179,
+ -0.4374, -1.1258, -0.8652, -0.7400, +0.2832, +0.3050, +0.3432,
+ +0.1818, -0.3477
+ ],
+ [
+ +0.0421, +0.0760, -0.0937, -0.3289, -0.1264, -0.2004, +0.2442,
+ -0.7426, +0.1581, +0.1091, -0.2079, +0.1762, -0.2847, +0.2595,
+ -0.0436, +0.0309, -0.0391, -0.3279, +0.0869, +0.1888, +0.2382,
+ -0.1285, +0.0044, -0.0093, +0.1621, +0.0545, +0.3107, -0.0062,
+ +0.4497, +0.2697, +0.1220, -0.3746, +0.2347, +0.1905, -0.2530,
+ -0.0934, -0.3307, -0.2066, -0.0438, +0.1751, -0.2122, -0.2497,
+ +0.1197, +0.3855, -0.0690, -0.0119, +0.1714, -0.1429, +0.2048,
+ +0.3442, -0.0357, -0.3776, +0.2283, +0.1940, -0.0545, -0.3471,
+ -0.0467, -0.4649, +0.0441, +0.0288, -0.0065, +0.0178, -0.0776,
+ -0.2727, +0.3306, -0.4464, +0.1174, +0.1001, +0.0399, +0.0524,
+ -0.0003, -0.1412, -0.0648, -0.2413, -0.4105, -0.0880, -0.1160,
+ +0.1251, +0.1382, -0.0681, +0.4072, -0.1640, -0.2284, +0.1872,
+ -0.0280, +0.2319, -0.2080, +0.0299, -0.3826, -0.1097, +0.1318,
+ -0.1643, -0.0302, -0.5179, +0.2203, -0.0162, -0.6722, -0.0071,
+ -0.5593, +0.1680, +0.0923, -0.1145, -0.2368, -0.0590, +0.3251,
+ -0.3777, -0.2606, -0.3314, -0.1094, -0.2820, -0.1278, +0.1683,
+ -0.2518, +0.1133, -0.1676, +0.0311, +0.2705, +0.2880, +0.1390,
+ -0.0344, +0.2985, -0.0291, -0.6771, -0.3216, +0.1436, -0.3997,
+ +0.1744, -0.0892
+ ],
+ [
+ +0.2227, -0.2971, -0.3469, +0.4666, -0.0545, +0.1139, +0.1211,
+ -0.3773, +0.0639, +0.3880, -0.3827, +0.1726, -0.3401, -0.2897,
+ -0.4629, +0.1177, +0.0280, -0.3550, -0.5237, +0.0578, +0.0203,
+ -0.4134, -0.2219, -0.1620, +0.1527, -0.3433, -0.0286, +0.1367,
+ -0.4098, -0.0532, +0.0170, -0.1500, -0.2434, -0.1257, +0.1599,
+ +0.3132, -0.4962, +0.0203, -0.1200, -0.3780, -0.0548, -0.1382,
+ +0.0468, -0.2005, -0.2922, +0.0412, -0.3139, -0.2190, -0.1921,
+ -0.3008, -0.1326, +0.1474, -0.0546, -0.3791, +0.2720, -0.4730,
+ +0.2390, -0.2128, -0.1345, -0.3941, +0.2550, -0.3516, +0.0163,
+ +0.2963, +0.0107, -0.0940, -0.5645, -0.3014, -0.0069, +0.2026,
+ -0.0785, +0.4574, +0.1301, +0.2480, -0.0485, -0.2237, -0.0629,
+ -0.2352, +0.0711, +0.2740, -0.1476, +0.3646, +0.3072, -0.2861,
+ -0.1857, -0.0471, +0.0310, -0.3897, +0.0805, +0.0024, +0.0570,
+ +0.3988, -0.0309, -0.0894, +0.2665, -0.3530, +0.1016, +0.2017,
+ +0.4422, -0.0812, -0.0641, -0.4382, -0.0046, -0.3735, -0.1861,
+ +0.2945, +0.0989, +0.1345, +0.0340, +0.0190, -0.2118, +0.0686,
+ -0.3836, +0.1731, +0.1700, -0.2080, +0.2979, -0.5672, +0.0529,
+ +0.1361, -0.1965, -0.1959, -0.1695, +0.0855, -0.2045, -0.1573,
+ -0.3586, -0.1811
+ ],
+ [
+ -0.2061, +0.1187, -0.4152, +0.3454, +0.3325, -0.4535, +0.0175,
+ -0.1316, +0.1508, +0.0567, -0.3291, +0.0792, -0.3860, -0.6880,
+ +0.0831, +0.0106, -0.2324, -0.1728, -0.2045, +0.5967, +0.1797,
+ -0.7193, -0.1522, +0.4142, +0.2647, -0.1462, +0.2758, +0.2446,
+ +0.0061, -0.0743, +0.2720, +0.1632, -0.1003, -0.2277, -0.5311,
+ -0.1379, +0.1877, +0.0882, -0.1241, +0.0654, +0.0969, +0.0503,
+ +0.1742, -0.0763, +0.1149, -0.1509, -0.2626, -0.0685, -0.0073,
+ +0.5289, -0.0256, +0.3609, +0.1023, -0.4789, -0.3071, +0.2803,
+ +0.0987, +0.0184, -0.2751, +0.0439, +0.7189, -0.4512, -0.6046,
+ +0.3523, +0.2981, -0.1774, +0.3571, -0.2574, +0.0502, +0.2503,
+ -0.2745, -0.2874, +0.1629, -0.2583, -0.0399, -0.2499, +0.0662,
+ -0.0962, -0.1815, -0.4266, +0.1113, -0.8154, -0.3679, +0.0954,
+ +0.0696, -0.2440, -0.1968, -0.3760, +0.0211, -0.5700, +0.2556,
+ -0.3801, -0.0156, +0.0770, -0.4611, +0.0781, -0.1871, -0.1328,
+ -0.0320, -0.7022, -0.3862, -0.0156, +0.3554, -0.2388, +0.1465,
+ +0.1270, -0.1418, +0.1951, -0.4408, -0.5125, -1.0156, +0.4492,
+ -0.6887, +0.2781, +0.1575, -0.3814, -0.2889, +0.2475, -0.1107,
+ +0.0171, -0.3111, -0.2021, +0.2899, +0.1741, -0.3082, +0.0318,
+ -0.1960, +0.3964
+ ],
+ [
+ +0.0908, -0.0992, -0.5574, -0.1475, +0.0634, -0.2495, -0.1826,
+ +0.3553, +0.0084, +0.2624, +0.0450, -0.1352, -0.0266, +0.0049,
+ -0.2243, -0.0175, -0.2538, -0.0782, -0.6108, -0.1035, +0.2119,
+ -0.2691, -0.0323, +0.0551, -0.0377, +0.3972, -0.4437, -0.7321,
+ +0.0651, -0.1293, -0.0490, +0.1585, -0.0975, -0.1757, -0.2343,
+ -0.0055, +0.1740, +0.0048, -0.6559, +0.0373, +0.3460, -0.9263,
+ +0.1879, -0.0669, +0.3651, +0.5088, -1.0274, -0.3409, -0.0143,
+ +0.2722, +0.2818, -0.1034, -0.6006, +0.4080, -0.1925, -0.1793,
+ -0.3323, -0.5531, -0.1189, +0.1274, +0.1319, -0.4859, -0.2834,
+ -0.5362, +0.2529, -0.0815, -0.8830, -0.1149, +0.4302, +0.3286,
+ -0.8478, +0.3274, +0.1833, -0.8509, +0.0124, +0.1571, -0.3137,
+ +0.2163, -0.2620, +0.3702, +0.0263, -0.8892, -0.3077, -0.5872,
+ -0.2785, -0.0548, +0.6223, +0.1073, +0.2722, +0.1667, -0.7687,
+ -0.3004, -0.1409, +0.0977, -0.6361, +0.0895, +0.2523, -1.1700,
+ -0.1937, -0.0640, -0.5124, -0.2828, +0.0786, +0.1680, +0.1903,
+ -0.0973, +0.0276, -0.2992, -0.1459, -0.5329, -0.5601, -0.3211,
+ -0.4753, -0.5864, +0.1028, -0.3598, -0.0670, -0.2731, +0.4096,
+ -0.2266, +0.3978, -0.0444, -0.2637, +0.2951, -0.5427, -0.2461,
+ -0.5261, +0.0949
+ ],
+ [
+ +0.1618, -0.4905, +0.3258, -0.1014, -0.0287, +0.5747, +0.0951,
+ -0.1661, -1.0580, -0.0250, -0.1151, +0.1218, +0.0448, +0.0009,
+ -0.2375, +0.1923, -0.0808, -0.1496, -0.4040, -0.0011, +0.1566,
+ -0.0025, +0.0013, -0.1833, -0.4217, -0.1717, +0.0899, -0.1539,
+ -0.0715, +0.2257, -0.0181, +0.3481, +0.1751, +0.1634, -0.5412,
+ +0.0892, -0.2702, +0.1308, -0.4672, -0.3700, -0.2379, +0.1514,
+ +0.3748, +0.0297, +0.0131, +0.2860, +0.0202, -0.4741, -0.3178,
+ -0.2200, +0.0164, +0.0544, +0.2424, -0.3790, +0.0947, +0.0634,
+ +0.1048, -0.5026, -0.4402, -0.2208, -0.1970, +0.2420, -0.2852,
+ +0.1045, +0.0041, +0.1532, -0.2748, +0.2220, -0.1802, -0.1195,
+ -0.0320, +0.0941, +0.0821, +0.1148, +0.2390, +0.3889, +0.0018,
+ -0.3051, -0.0233, -0.0228, -0.3145, -0.0425, +0.4689, +0.1950,
+ +0.1288, -0.6089, +0.2982, +0.1527, +0.1825, +0.1216, +0.4530,
+ +0.1668, -0.3275, +0.1676, -0.2089, -0.0556, -0.6145, -0.0445,
+ -0.8699, -0.2688, +0.3719, -0.7730, -0.1762, +0.0905, -0.3222,
+ +0.3221, +0.4203, -0.0613, +0.1184, +0.2110, +0.2703, +0.0339,
+ -0.1625, +0.2663, +0.1400, +0.0936, -0.3175, -0.3469, -0.0820,
+ -0.0730, -0.0210, +0.1526, -0.0458, -0.0371, +0.1708, -0.1264,
+ -0.4222, +0.2816
+ ],
+ [
+ -0.1449, -0.4340, +0.3384, +0.1579, -0.1091, -0.2229, -0.7007,
+ -1.1185, -0.1052, +0.1772, -0.3176, -0.0954, -0.3036, -0.3146,
+ +0.2082, -0.6706, +0.0364, +0.1425, +0.3943, -0.2101, +0.0523,
+ -0.2765, +0.0090, -0.0655, -0.2401, +0.4830, -0.2957, +0.0572,
+ +0.0692, -0.1737, +0.4769, -0.4658, +0.0137, +0.0588, -0.5256,
+ +0.3810, -0.0043, +0.0705, -0.7742, -0.2515, +0.4426, +0.0385,
+ -0.0394, -0.0789, -0.1381, +0.2169, +0.0898, -0.4948, -0.4634,
+ -0.0958, -0.1589, -0.4759, +0.2111, -0.2565, +0.0694, +0.0705,
+ +0.0388, +0.1178, -0.0762, -0.4617, -0.8680, -0.2346, +0.2338,
+ -0.7045, +0.3175, -0.1283, -0.1354, -0.4054, +0.2363, -0.0522,
+ -0.0029, +0.1389, +0.1709, +0.3458, -0.1531, +0.1611, -0.4193,
+ +0.1833, +0.2374, +0.6556, -0.0475, +0.3806, +0.4965, -0.2974,
+ -0.0217, +0.2118, -0.0464, +0.3696, -0.0580, -0.8348, -0.7580,
+ +0.0611, +0.1105, -0.1347, -0.0760, +0.1793, -0.3194, -0.6205,
+ +0.4345, +0.0319, +0.0245, +0.3281, -0.2088, -0.8847, +0.1012,
+ +0.1181, +0.0141, -0.4330, -0.0720, +0.3774, +0.2740, -1.0438,
+ +0.1583, +0.0846, -0.1631, +0.3802, -0.0777, +0.1888, -0.3915,
+ +0.2461, -0.8871, +0.0106, +0.0323, -0.0571, -0.1533, -0.4462,
+ -0.1460, -0.3907
+ ],
+ [
+ -0.2878, -0.0615, +0.2505, +0.1581, -0.6736, +0.2485, -0.3433,
+ -0.5456, -0.5950, -0.1342, +0.1008, -0.0716, -0.0541, +0.1849,
+ -0.3383, +0.2208, -1.0103, -0.3722, -0.0319, -0.0332, -0.4669,
+ -0.1479, -0.0878, -0.1468, -0.3543, +0.5402, +0.1786, -0.0781,
+ +0.0761, -0.5135, +0.5701, +0.1104, -0.0162, +0.2412, +0.0370,
+ +0.0211, +0.0297, +0.2620, -0.0827, -0.6327, +0.0140, +0.0513,
+ -0.0192, -0.2413, -0.5702, -0.0003, +0.4197, -0.3194, +0.1597,
+ -0.2770, -0.5649, +0.1293, -1.0851, -0.4333, -0.3866, -0.8689,
+ -0.1534, -0.1899, -0.1301, -0.2131, +0.1348, -0.1494, -0.3751,
+ +0.3482, -0.0373, -0.1306, -0.2304, +0.5142, +0.1681, -0.5262,
+ -0.3565, -0.2431, -0.2511, +0.4271, +0.2971, -0.3514, -0.1895,
+ -0.0938, +0.3170, -0.0274, +0.1666, -0.2795, -0.5762, -0.3793,
+ -0.1089, +0.1886, +0.5871, -0.2598, -0.3023, -0.8249, +0.2772,
+ +0.1765, +0.0883, -0.0666, +0.1009, +0.2339, -0.0881, -0.3906,
+ +0.1244, -0.1059, +0.0345, +0.1081, -0.3789, -0.3119, -0.3382,
+ -0.3980, -0.2057, +0.0522, -0.4197, +0.2586, -0.0300, +0.1536,
+ +0.2187, -0.0763, +0.0302, +0.3941, +0.6030, -0.6882, -0.1713,
+ -0.2873, +0.4185, +0.3159, +0.2026, +0.1525, -0.4530, -0.0410,
+ -0.0349, +0.2280
+ ],
+ [
+ -0.6061, -0.0909, -0.0550, -0.2184, -0.4677, -0.4432, -0.2260,
+ +0.1602, -0.3579, -0.2434, -0.3035, -0.3499, -0.4640, -0.0961,
+ -0.8689, -0.3364, -0.5608, -0.2340, -0.3993, -0.4102, +0.2083,
+ +0.0047, -0.1841, -0.8708, +0.2682, -0.2035, +0.0297, -0.1514,
+ -0.3664, +0.0290, -0.3759, +0.3887, -0.3711, -0.5360, -0.2174,
+ -1.1284, -0.5156, -0.1612, -0.0737, -0.4903, -0.4929, -0.1873,
+ +0.0404, -0.1258, +0.4220, +0.2427, -0.0421, +0.4974, +0.0100,
+ +0.3258, -0.3710, -0.0276, -0.6241, -0.2282, -0.2343, +0.5713,
+ -0.1646, -0.3397, +0.2585, +0.0450, -0.1207, -0.1081, +0.2005,
+ -0.5321, -0.3488, +0.0880, +0.1172, +0.1975, -0.2884, -0.3175,
+ +0.1191, +0.1787, -0.4443, -0.2308, -0.1809, +0.1833, +0.3746,
+ -0.1612, -0.1746, +0.1444, -0.1684, +0.1569, -0.5966, +0.0297,
+ -1.1438, -0.3301, -0.0267, +0.1739, -0.1595, -0.7382, -0.8372,
+ -0.2308, -0.3466, -0.4795, -0.2313, -0.7824, +0.1980, +0.2107,
+ -0.6244, -0.0962, -0.1942, +0.2395, -0.3016, -0.1821, +0.4167,
+ -0.0695, -0.2468, +0.0869, -0.5590, -0.2276, -0.4163, +0.2860,
+ +0.1813, -0.0321, -0.2457, -0.0202, -0.1410, +0.1888, -0.0146,
+ -0.7551, -0.0123, +0.1800, -0.2752, +0.0198, -0.0279, -0.4698,
+ -0.4623, -0.3625
+ ],
+ [
+ -0.0845, -0.0307, +0.2515, +0.0145, +0.1197, +0.3987, -0.4345,
+ -0.3723, +0.0691, +0.1694, -0.3358, -0.0540, -0.0187, +0.5110,
+ +0.1727, -0.1340, +0.0335, -0.1176, -1.2247, -0.0016, +0.2501,
+ -0.1295, -0.3627, +0.2087, -0.0750, -0.0229, -0.1075, -0.4822,
+ +0.1749, +0.2224, +0.2493, -0.8074, -0.3120, -0.1274, -0.7827,
+ +0.0645, -0.1956, -0.1618, +0.1351, -0.2641, -0.0409, +0.2512,
+ +0.1865, +0.1569, -0.3542, -0.1335, -0.9144, -0.3099, -0.0042,
+ +0.0161, -0.5852, -0.4469, +0.1677, -0.5367, +0.5580, +0.0745,
+ +0.0027, -0.1883, -0.4742, -0.3860, -0.5103, +0.4660, -0.8256,
+ -0.7132, -0.0312, -0.3823, -0.1519, +0.2287, +0.2300, +0.1152,
+ +0.1736, +0.2429, -0.1806, +0.2374, -0.3979, +0.1320, -0.5556,
+ +0.2660, -0.8979, -0.6503, -0.0790, +0.1668, -0.4129, -0.4282,
+ +0.3145, -1.3375, -0.1544, +0.1570, +0.1358, -0.4562, -0.5580,
+ -0.0270, -0.0299, -0.2310, -0.3223, -0.2773, -1.2287, +0.0719,
+ +0.1664, -0.1294, +0.0616, -0.1551, -0.1501, -0.1315, -0.0196,
+ -0.1675, +0.0702, -0.1678, +0.0950, -0.2934, -0.1290, +0.0739,
+ +0.0199, +0.1733, +0.0355, -0.7176, -0.2725, -0.2942, -0.3444,
+ -0.3210, -0.2305, +0.0826, +0.2586, -0.2365, +0.0963, +0.0902,
+ +0.1406, +0.0500
+ ],
+ [
+ -0.1641, +0.1803, +0.0176, -0.0164, -0.1597, -0.1098, +0.1263,
+ -0.3531, +0.2009, -0.2688, +0.2281, +0.0484, +0.0412, +0.4032,
+ +0.0177, -0.7202, -0.1029, +0.2414, -0.3872, +0.4367, +0.0134,
+ -0.3715, -0.1411, -0.0280, -0.3206, -0.0946, +0.1634, -0.5124,
+ -0.0615, -0.1953, -0.2134, -0.3191, +0.2202, +0.0565, -0.0890,
+ -0.2060, -0.4671, +0.2055, -1.1555, -0.0669, +0.1648, -0.1441,
+ -0.1714, -0.1822, +0.2035, -0.7000, +0.0695, +0.0956, +0.0437,
+ -0.0890, -0.1878, +0.2828, -0.2674, +0.1618, +0.2366, +0.0729,
+ +0.3175, +0.0306, -0.5201, +0.0188, +0.3739, -0.5527, -0.3397,
+ +0.0665, +0.3225, -0.2450, -0.3998, -0.1282, +0.3574, -0.2880,
+ +0.2108, -0.1360, -0.0243, +0.0996, -0.4179, -0.2257, -0.4723,
+ +0.4179, -0.1489, -0.0351, +0.3217, -0.4655, -0.5597, +0.2265,
+ +0.0331, +0.1609, -0.0233, +0.3688, +0.2562, -0.0856, -0.3728,
+ -0.0548, +0.4144, +0.1663, -0.5262, +0.3334, -0.1203, -0.0692,
+ +0.1855, +0.0311, +0.0978, +0.0475, -0.0780, +0.3128, -0.0074,
+ -0.6474, +0.1366, -0.2251, +0.0069, -0.0087, +0.0467, +0.0438,
+ +0.0939, +0.4966, -0.1934, -0.6285, -0.2758, +0.1596, +0.0895,
+ -0.2190, -0.8005, -0.2677, -0.3218, +0.3237, +0.0888, -0.2617,
+ +0.0320, +0.1497
+ ],
+ [
+ -0.1253, -0.0350, -0.0856, -0.0467, +0.1283, +0.2748, +0.1479,
+ +0.2745, +0.1078, -0.3786, -0.3089, +0.0064, -0.1175, +0.0248,
+ +0.2094, -0.2929, -1.4566, +0.2682, +0.0442, +0.3729, +0.2005,
+ -0.5589, +0.1468, +0.4390, -0.8793, +0.2898, +0.3577, -0.6922,
+ +0.0979, +0.3569, +0.0792, +0.1176, -0.2124, +0.1861, -0.0484,
+ -0.0443, +0.2162, +0.0916, -0.2512, +0.0367, +0.0633, +0.0470,
+ +0.0792, +0.0034, -0.1414, +0.3856, -0.1245, -0.1696, -0.1526,
+ +0.1365, +0.3263, -0.0325, +0.3004, +0.2138, +0.1553, +0.2231,
+ -0.1920, -0.5498, -1.3362, -0.0097, -0.1920, +0.2219, -0.2937,
+ -0.2273, -0.2927, +0.2756, -0.1875, -0.1068, -0.3225, +0.0928,
+ +0.5012, -0.3023, -0.1227, -0.5252, -0.3104, -0.5777, +0.0303,
+ -0.2129, -0.6370, +0.4402, -0.4292, -0.2224, -0.0492, -0.2785,
+ +0.2249, -0.3533, -0.2766, -0.1833, -0.1814, -0.9459, -0.2622,
+ -0.6534, -0.2456, +0.3434, -0.0585, +0.0774, -0.1196, -0.2611,
+ +0.3853, +0.1695, +0.1012, +0.0691, -0.0476, +0.0520, -0.2332,
+ +0.0186, -0.1382, +0.3594, -0.0141, +0.3252, -0.3512, -0.0661,
+ +0.1478, +0.4440, +0.0711, -0.1353, -0.2475, -0.0257, +0.5104,
+ +0.1134, -0.1690, +0.0288, -0.4795, -0.1104, +0.0961, -0.1073,
+ -0.6397, +0.0654
+ ],
+ [
+ -0.1892, +0.0568, -0.2412, -0.6013, +0.3256, +0.2101, +0.1802,
+ -0.2477, +0.0262, -0.4132, -0.1172, +0.1311, +0.2263, +0.1451,
+ +0.3181, -0.1332, +0.1379, -1.1694, -0.3646, -0.1916, -0.4726,
+ -0.4236, -0.0609, -0.0810, -0.0390, -0.0253, +0.2483, +0.4296,
+ +0.0255, -0.9403, +0.3116, -0.8595, +0.2039, -0.3203, -0.0686,
+ -0.2876, -0.7740, -0.4882, +0.2804, +0.1530, -0.3647, -0.2899,
+ -0.1928, +0.0574, -0.9411, +0.2955, +0.5295, -0.1495, -0.2544,
+ -0.0502, -0.6493, -0.0688, -0.2562, -0.0072, +0.0258, +0.2712,
+ +0.4828, -0.0741, +0.0550, -0.1493, +0.0222, -0.0950, -0.1410,
+ -0.0260, -0.0008, -0.2603, +0.0681, +0.0436, +0.1496, -0.0550,
+ -1.4449, +0.2512, -1.1742, -0.6389, -0.1976, -0.2944, -0.3775,
+ +0.2221, -0.0417, -0.0980, +0.0640, +0.0496, -0.1026, +0.2860,
+ -0.6115, +0.0723, -0.0295, +0.1601, +0.0567, +0.2533, -0.5541,
+ +0.4440, +0.2326, -0.3252, +0.1586, -0.2256, -0.6957, +0.0371,
+ +0.3295, +0.4163, +0.1884, +0.0308, -0.9381, +0.1548, -0.1683,
+ -0.1657, -0.3450, -0.0012, +0.2329, +0.3270, +0.2418, -0.0308,
+ +0.2985, -0.2371, -1.1584, -1.2930, -0.0451, +0.1693, +0.2680,
+ +0.4843, +0.1023, +0.0457, +0.2715, -0.0179, -0.3231, -0.0171,
+ -0.0038, -0.2308
+ ],
+ [
+ -0.4185, +0.0518, -0.0622, +0.1876, -0.0893, +0.0031, -0.1216,
+ -0.8492, -0.5659, +0.2852, -0.2889, -0.1508, +0.2531, -0.0835,
+ +0.0111, +0.0087, -0.3572, +0.2532, +0.0334, -0.3784, -0.1595,
+ -1.3338, -0.3168, -0.3062, +0.5036, -0.3661, +0.4044, +0.3749,
+ +0.1713, +0.0696, -0.2597, -0.2785, -0.1862, -0.0663, -0.1889,
+ +0.3290, +0.1240, +0.5744, +0.2029, +0.6920, -0.0658, -0.2106,
+ -0.2397, -0.7892, +0.3586, +0.2038, +0.2659, +0.0079, +0.0883,
+ +0.1599, -0.1192, +0.3185, +0.0724, -0.1714, -0.1568, +0.1129,
+ +0.5232, +0.2673, +0.0950, +0.2312, -0.2412, -0.4621, -0.9121,
+ +0.0927, -0.2441, -0.0055, -0.3084, +0.0480, +0.2937, -0.5931,
+ -0.1304, -0.1331, -0.0718, -0.4675, -0.2199, -0.4012, -0.7162,
+ -0.0440, +0.3202, +0.0727, -0.0885, +0.2881, -0.2546, +0.2202,
+ -0.0740, +0.0747, +0.3164, +0.1560, +0.1748, -0.1047, +0.0710,
+ -0.1201, -0.0498, +0.1716, +0.2840, -0.2102, +0.1068, +0.0459,
+ +0.1061, -1.3161, -0.0708, -0.6666, -0.0305, +0.0622, -0.3030,
+ +0.0992, -0.4008, +0.1789, +0.0664, +0.1021, -0.1184, +0.2772,
+ +0.2421, -0.6209, -0.4482, -0.6124, -0.0749, -0.0634, +0.4178,
+ -0.0745, -0.5763, +0.3940, -0.2924, -0.4282, -0.2118, -0.5264,
+ -0.8030, +0.1691
+ ],
+ [
+ -0.0243, +0.1186, +0.1214, -0.7917, -0.0578, +0.0656, +0.1574,
+ -0.4321, -0.8055, -0.0509, +0.2256, +0.1686, -0.0946, -0.1584,
+ +0.1417, +0.1943, -1.2738, +0.0080, -0.1580, -0.5160, +0.2872,
+ +0.0854, +0.1843, -0.0101, -0.0975, -0.1252, -0.3296, -1.1518,
+ -0.1937, -0.0913, +0.1553, -0.3593, +0.7464, -0.2383, -0.8537,
+ +0.0278, -0.0484, +0.1455, +0.0117, -0.0073, -0.5213, +0.0542,
+ -0.3462, -0.4633, +0.1424, -0.0178, -0.0359, -0.8284, -0.5606,
+ -0.0482, +0.3423, +0.2033, +0.3398, -0.2188, +0.0563, +0.4824,
+ -0.7406, -0.2805, +0.2481, +0.0907, +0.1630, -0.2325, -0.1028,
+ -0.0367, +0.1283, +0.1714, -0.4324, +0.3293, -0.4413, -0.3222,
+ +0.0196, +0.4370, +0.2912, +0.1991, +0.0462, +0.3073, -0.5100,
+ -0.0354, +0.0971, -0.6773, +0.1030, -1.0156, -0.3781, -0.3812,
+ +0.5229, -0.1198, +0.1014, +0.3792, -0.0822, -0.5402, +0.3907,
+ -0.4183, +0.2017, -0.2403, +0.1254, +0.1106, -0.2351, -1.0903,
+ +0.0545, -0.6915, -0.4463, +0.2522, +0.0548, +0.0415, +0.1845,
+ -1.2566, +0.3470, -0.1079, -0.1252, +0.3779, +0.2574, -0.1457,
+ +0.6287, +0.2764, +0.0868, -0.3796, +0.1852, +0.2793, -0.1176,
+ +0.0419, -0.3765, +0.2774, -2.0774, +0.1867, -0.3176, -0.0142,
+ +0.1466, -0.0167
+ ],
+ [
+ -0.2577, -0.3209, -0.2173, -0.9016, +0.1397, -0.0210, +0.0456,
+ +0.3509, -0.3827, -0.4699, +0.0811, +0.1087, +0.3465, -0.3480,
+ -0.0577, -0.1263, +0.1601, +0.1168, -0.3422, -0.1298, -0.8658,
+ -0.3096, +0.0007, -0.2192, +0.1675, -0.2581, +0.0042, -0.3348,
+ +0.2278, -0.3934, -0.1930, +0.1503, -0.1282, -0.0508, -0.1116,
+ +0.0845, -0.1293, -0.4505, -0.3138, +0.2516, -0.8298, +0.2572,
+ -0.2498, +0.0418, -0.4383, +0.1897, -0.0101, -0.0634, +0.4161,
+ -0.1021, +0.0685, +0.0620, -0.0885, +0.0695, -0.3611, +0.2575,
+ +0.0583, -0.3698, -0.0590, -0.0599, -0.0708, -1.1328, -1.4975,
+ -0.4391, -0.0188, +0.2601, -0.3437, +0.0091, +0.1288, -0.1438,
+ -0.7818, -0.5881, +0.1493, +0.1140, -0.2837, +0.0317, -0.3420,
+ -0.2077, -0.0265, +0.2358, -0.0638, +0.2327, +0.2399, +0.0046,
+ +0.3208, -0.2417, +0.1361, +0.1809, -0.1479, -0.2120, -0.0466,
+ -0.4996, +0.0346, +0.0137, +0.1121, +0.0929, -0.0005, -0.2860,
+ -0.8237, -0.1306, +0.3829, -0.0539, -0.4165, -0.1393, +0.0856,
+ +0.1007, -0.2190, +0.5631, -1.2789, -0.0171, -0.3736, -0.0174,
+ +0.0349, -0.4041, -0.0510, +0.1716, -0.6770, -0.0002, -0.3129,
+ -0.7005, -0.9493, +0.0616, -0.2887, +0.0076, +0.2085, -0.6462,
+ +0.1981, +0.1615
+ ],
+ [
+ +0.3304, +0.1152, -0.6717, +0.1143, +0.2115, +0.0698, -0.1820,
+ +0.1726, -0.0369, +0.0439, +0.1313, -0.1625, -0.0757, +0.0836,
+ +0.0388, +0.1446, +0.0832, +0.0089, -0.4948, -0.0825, -0.3839,
+ -0.4609, +0.1577, -0.0576, +0.0792, -0.0768, +0.1828, +0.3302,
+ -0.1742, -0.3798, +0.0916, +0.1784, +0.0494, +0.0835, +0.0700,
+ +0.1665, +0.3586, -0.6019, +0.2448, +0.6077, +0.1405, -0.1039,
+ -0.0866, -0.0915, -0.0754, +0.2220, -0.5158, -0.5315, +0.2973,
+ -0.0670, +0.0497, +0.2268, +0.1621, +0.0508, +0.0365, +0.3368,
+ +0.3022, +0.3330, +0.2109, -0.3269, -0.3239, -0.2013, +0.2996,
+ +0.1457, -0.2253, -0.3094, +0.1806, +0.1514, +0.2331, +0.0763,
+ -0.1444, -0.1580, +0.3315, -0.5235, +0.2613, +0.1944, +0.1859,
+ +0.3933, +0.4284, -0.2695, +0.1532, -0.0814, -0.6060, -0.1824,
+ -0.2279, -0.3816, -0.9168, -0.2387, +0.0473, +0.0513, -0.0929,
+ -0.2477, +0.0768, +0.4879, -0.5346, -0.4995, -0.2313, +0.0707,
+ -0.0713, -0.1675, +0.2942, +0.0147, +0.2039, +0.3673, -0.0179,
+ -0.4249, +0.0179, -0.4301, -0.2318, -0.0834, -0.3560, +0.1333,
+ -0.0454, -0.3471, +0.2927, +0.2090, +0.1567, -0.2355, +0.0565,
+ -0.2313, -0.0992, -0.4685, +0.0392, +0.0334, -0.4125, -0.0562,
+ +0.1348, -0.0555
+ ],
+ [
+ +0.2765, +0.2651, -0.1661, +0.0773, -0.1170, -0.0005, +0.1935,
+ +0.2157, -0.0871, -0.0412, +0.2278, +0.0088, +0.5312, +0.1020,
+ +0.4036, +0.1912, +0.1202, -0.2561, +0.0533, -0.3085, -0.3528,
+ -0.2470, +0.8043, -0.1908, +0.3315, -0.0677, -0.2639, -0.7734,
+ -0.0086, -0.8340, +0.1080, +0.3147, -0.0394, -0.1705, -0.6031,
+ +0.5434, -0.0039, -0.0621, +0.1619, +0.6574, -0.3513, +0.4419,
+ -0.0093, -0.3592, -0.3253, +0.2011, +0.3291, +0.4329, -0.2797,
+ -0.0186, -0.6435, +0.2140, +0.0672, -0.3524, +0.1114, +0.0474,
+ -0.7333, -0.2670, +0.1535, -0.8170, +0.3432, -0.4108, -0.1007,
+ +0.1650, -0.0829, -0.4034, -0.3486, -0.0583, +0.2539, -0.0878,
+ -0.9101, -0.2531, +0.2064, -0.3594, -0.1831, +0.2126, +0.4375,
+ -0.0240, +0.1841, -0.3827, -0.3310, -0.3788, +0.0986, -0.7037,
+ -0.1839, +0.2655, +0.0209, -0.1485, +0.3097, +0.1903, -0.0578,
+ +0.1213, +0.0722, +0.3004, +0.4606, +0.0119, -0.0622, +0.0207,
+ -0.6240, -0.2635, +0.3157, +0.1758, -0.3678, +0.3457, -0.3850,
+ -0.4129, -0.5109, +0.3018, -0.2841, -0.7261, +0.1670, -0.2980,
+ +0.0840, -0.0656, +0.2121, -0.0174, -0.1468, -0.6263, +0.2111,
+ -0.8132, +0.1847, -0.1166, -0.1332, -0.1358, -0.1872, -0.5252,
+ +0.0908, -0.3466
+ ],
+ [
+ -0.3072, +0.0593, -0.2193, +0.4342, -0.0824, -0.0014, -0.1008,
+ -0.2842, +0.0379, +0.2284, +0.0750, +0.1432, -0.2198, -0.2522,
+ -0.3912, +0.0649, -0.1187, +0.2494, -0.0734, +0.1627, -0.2980,
+ -0.2779, +0.3082, -0.2920, +0.5340, -0.1274, -0.2058, +0.0024,
+ +0.0237, +0.3097, -0.2613, +0.0268, +0.0602, -0.0818, +0.0302,
+ -0.7059, +0.1893, +0.1382, -0.3246, -0.9833, -1.0995, +0.0738,
+ +0.2231, -0.2223, -0.2500, +0.3808, +0.2266, -0.4070, +0.1142,
+ -0.6488, -0.1621, +0.2094, -0.2307, -0.4893, +0.0355, +0.0290,
+ -0.1048, -1.1536, -0.5460, -0.1715, -0.0416, +0.5042, -0.3416,
+ -0.1424, -0.0845, -0.0123, +0.2568, +0.1480, -0.8059, -0.6547,
+ +0.1523, -0.1598, -0.1313, -0.3420, +0.0431, +0.2401, -0.1837,
+ +0.1552, +0.1038, +0.1037, -0.2919, +0.0035, +0.0380, -0.1548,
+ -0.1816, -0.4945, +0.2192, +0.2169, +0.4100, -0.6803, -0.2764,
+ +0.3512, +0.0954, -0.2026, +0.2252, -0.2983, +0.2042, -0.5496,
+ +0.0732, -0.0592, -0.1785, -0.2568, +0.1295, -0.1812, -0.1574,
+ -0.1005, -0.1900, -0.2671, -0.2191, -0.1296, +0.3192, -0.0245,
+ +0.1966, +0.3232, -0.1156, +0.3218, +0.3045, +0.1002, -0.3261,
+ +0.3375, -0.1016, +0.1813, -0.5060, -0.0189, -0.0428, +0.0821,
+ -0.1383, -0.0483
+ ],
+ [
+ -0.0485, -0.0761, +0.2687, -0.3376, -0.0789, -0.3058, -0.1430,
+ -0.6755, +0.2649, +0.7666, -0.2482, -0.4595, -0.0853, -0.3108,
+ -0.1604, -0.1217, -0.4340, +0.2198, +0.0220, -0.3623, +0.6541,
+ -0.2147, -0.1381, -0.3438, -0.1808, -0.1435, +0.2867, -0.9132,
+ -0.2100, -0.6305, -0.3223, +0.0752, -0.0067, +0.0911, -0.0818,
+ -0.3216, -0.1769, +0.1011, -0.2282, +0.1190, -0.1974, -0.0207,
+ -0.3438, -0.0572, -0.2476, -0.2491, -0.1069, -0.4519, +0.1434,
+ +0.2403, -0.3082, +0.0892, +0.0322, +0.0599, +0.0814, -0.3499,
+ +0.0373, -1.0612, +0.0223, +0.1832, +0.0886, +0.0553, -0.0571,
+ +0.2441, -0.3607, -0.1565, -0.2459, -0.0615, -0.7580, +0.2557,
+ -0.9257, +0.0689, -0.0736, -0.2414, +0.1422, +0.2079, -0.4424,
+ -0.3469, -0.0933, +0.3856, -0.0750, -0.1159, +0.4371, +0.1831,
+ +0.1788, +0.0338, -0.0747, -0.4103, +0.3391, -1.0040, +0.4627,
+ +0.1272, +0.2411, -1.0926, -0.2224, -0.1995, +0.1803, -0.0627,
+ -0.6347, -0.1275, +0.2026, -0.0792, -0.0308, +0.1798, -0.0517,
+ +0.2374, -0.4876, +0.0377, -0.4819, -0.0827, -0.2996, -0.4329,
+ +0.3787, -0.1345, +0.1394, +0.3466, +0.1525, +0.3288, -0.0679,
+ -0.6395, +0.0492, +0.2418, -0.2533, +0.2143, -0.6310, -0.7643,
+ +0.3824, -0.5283
+ ],
+ [
+ -0.2216, -0.2724, -0.3635, -0.5285, +0.2326, -0.0175, -0.1538,
+ +0.0782, +0.6778, -0.3808, -0.1319, +0.1996, -0.1311, -0.3252,
+ +0.4766, -0.1242, +0.5385, -0.1809, -0.0201, -0.1445, -0.2975,
+ -0.3141, -0.0635, -0.1437, -0.1520, +0.2272, -0.1175, -0.6078,
+ -0.0450, +0.0698, -0.0833, -0.0208, -0.9297, -0.7583, -0.8347,
+ -0.2802, -0.1081, -0.2378, +0.0218, -0.3091, -0.3305, +0.0505,
+ -0.1155, -0.9380, +0.0521, +0.4455, +0.2421, +0.2943, -1.0620,
+ -0.1135, +0.1517, +0.2703, +0.1553, +0.1838, -0.0901, +0.4649,
+ +0.0869, +0.0020, -0.3046, -0.1267, +0.2966, -0.0340, +0.0251,
+ -0.0225, -0.4745, +0.1096, +0.4214, +0.0260, -0.9900, +0.1529,
+ +0.0409, +0.0435, +0.4192, +0.1484, +0.2290, +0.3483, +0.0416,
+ +0.0547, +0.2778, +0.0500, +0.1722, -0.2871, +0.1912, -0.1819,
+ +0.0170, -0.1954, +0.1159, +0.1133, +0.0251, -0.5399, +0.1444,
+ +0.2560, +0.2234, +0.0129, +0.1838, -0.0347, +0.1374, -0.3880,
+ +0.4386, -0.5715, -0.0648, -0.1808, -0.1905, +0.1060, +0.0285,
+ +0.0654, +0.1420, -0.3763, -0.3592, +0.1827, +0.0626, -0.0212,
+ -0.1470, -0.0439, +0.3878, -0.5607, -0.0129, +0.0216, +0.0846,
+ +0.2230, -0.8648, +0.0159, +0.3718, -0.0508, -0.5289, -0.7366,
+ -0.0457, +0.4186
+ ],
+ [
+ -0.0214, -0.0530, +0.0137, -0.2432, -0.0927, -0.2797, +0.0852,
+ -0.4463, -0.0110, +0.2777, -0.1540, +0.1232, +0.1111, +0.0501,
+ -0.0242, +0.3283, +0.1690, +0.7622, -0.3503, -0.2473, +0.0353,
+ -0.3887, -0.4612, -0.1503, +0.0814, +0.3865, -0.1694, +0.0120,
+ +0.4389, -0.0711, +0.1713, +0.3489, +0.0682, -0.2548, -0.2882,
+ -0.0319, +0.3242, -0.4394, +0.3936, +0.0420, +0.2637, -0.4346,
+ -0.2826, -0.1212, -0.2662, +0.0626, +0.1920, +0.1084, -0.1428,
+ -0.1077, +0.4388, -0.4603, +0.0879, -0.1445, +0.0940, +0.1186,
+ -0.0631, -0.5513, +0.2869, +0.0772, +0.3672, -0.6910, -0.0244,
+ +0.2878, +0.2721, +0.0819, -0.2527, -0.0537, -0.1003, +0.3021,
+ +0.1214, -0.0519, -0.1527, -0.1574, -0.0269, -0.1360, +0.1854,
+ +0.4206, -0.0306, -0.2780, -0.0115, -0.1752, -0.3788, -0.2699,
+ +0.1797, +0.1841, +0.1184, -0.1995, -0.2032, -0.0399, +0.0875,
+ -0.5725, +0.4417, +0.2053, +0.0468, +0.4927, +0.1521, -0.1696,
+ +0.0752, -0.3104, +0.5265, +0.1238, -0.2677, +0.0530, +0.2844,
+ +0.1389, -0.0011, +0.1489, -0.0156, +0.0328, -0.8756, -0.1634,
+ +0.3669, -0.4764, +0.2505, +0.4518, -0.2778, -0.0361, -0.2592,
+ +0.2754, -0.9665, +0.0985, -0.0931, -0.1472, -0.0249, +0.1736,
+ -0.0344, +0.4884
+ ],
+ [
+ +0.0076, -0.0792, +0.4573, +0.2103, -0.3263, +0.5124, -0.1254,
+ -0.3027, +0.4467, +0.1534, -0.0088, +0.0828, +0.1483, -0.0149,
+ +0.3330, -0.1840, -0.8589, +0.1954, +0.1535, +0.2053, -0.1536,
+ -0.3341, +0.2597, -0.6422, +0.0675, -0.2398, +0.3120, -0.7673,
+ +0.1112, -0.3301, +0.0317, +0.0886, +0.0414, -0.2466, -0.1473,
+ -0.7178, +0.4703, -0.4728, +0.1195, +0.4448, -0.3061, -0.6861,
+ -0.3048, -0.2956, +0.3244, +0.4717, -0.4695, +0.5288, -0.6678,
+ -0.0470, -0.0538, -0.1436, -0.9947, -1.1587, +0.0508, -0.2462,
+ +1.0473, +0.2293, +0.4339, +0.3946, -0.2774, +0.0805, +0.1161,
+ +0.6042, +0.4060, -0.2910, -0.5440, +0.1522, -0.3688, -0.9751,
+ -0.8646, -0.4894, -0.3640, -0.3734, +0.2146, +0.2350, +0.1571,
+ +0.2132, -0.0705, +0.0330, +0.1605, -0.0053, -0.1780, -0.9285,
+ +0.0206, -0.5987, -0.2628, +0.3601, +0.1762, +0.2956, -0.0877,
+ +0.1974, -0.0082, +0.5044, +0.2951, -0.1490, -0.5688, -0.4528,
+ -0.4916, +0.2803, +0.0985, +0.0523, -0.2049, -0.0192, +0.2865,
+ -1.0200, -0.1378, +0.1502, +0.4630, -0.1785, -0.2855, -0.5179,
+ -0.2046, +0.2921, +0.0592, +0.0598, -0.5597, +0.0560, +0.5616,
+ -0.0732, -0.0935, -0.0076, -0.0293, -0.0054, -0.5336, -0.0486,
+ -0.0284, -0.7210
+ ],
+ [
+ +0.0138, +0.1312, -0.5257, -0.4086, +0.0728, +0.1993, +0.1312,
+ +0.0431, +0.0887, -0.0362, -0.2398, -0.2054, -0.0455, -0.0584,
+ -0.2373, +0.2380, +0.2169, +0.0082, +0.2734, -0.1091, -0.4689,
+ +0.2916, -0.1617, -0.1124, -0.1273, +0.0680, -0.0110, +0.0820,
+ +0.0190, -0.2237, -0.2111, +0.0737, +0.1487, +0.1199, +0.3229,
+ -0.1435, -0.1576, +0.2985, -0.4750, +0.2688, -0.4223, +0.3317,
+ +0.1938, -0.0482, +0.2846, -0.1528, -0.1198, -0.3543, -0.1499,
+ +0.1163, +0.2298, +0.0175, +0.2827, +0.1979, -0.1932, +0.3102,
+ -0.0683, +0.1764, -0.0746, +0.0251, +0.2647, -0.3658, -0.4789,
+ +0.3222, +0.1481, +0.0715, +0.1229, +0.2837, -0.3743, -0.1212,
+ -1.3068, +0.1790, +0.3244, -0.2563, -0.2422, +0.2098, -0.2671,
+ +0.3374, -0.1205, -0.7220, +0.4286, +0.3452, +0.1179, +0.4031,
+ -0.3413, -0.6037, +0.2143, -0.2744, +0.2182, +0.4431, -1.0548,
+ +0.1050, -0.0165, -0.2962, -0.2426, -0.1212, -0.1963, +0.2281,
+ -0.6649, +0.0373, +0.0941, +0.1760, +0.1101, +0.0707, -0.6022,
+ -0.0103, -0.3880, -0.4686, +0.4758, -0.5176, +0.1639, -0.0607,
+ -0.6359, -0.2935, -0.1718, -0.2972, -0.3843, -0.0077, -0.7114,
+ -0.0130, -0.2512, -0.2410, -0.2260, +0.2555, -0.2789, +0.1600,
+ +0.1542, -0.1273
+ ],
+ [
+ -0.2428, +0.3061, +0.2298, -0.4761, -0.3310, +0.1217, -0.4854,
+ -0.0608, +0.0785, +0.0976, +0.0841, +0.0917, +0.3270, -0.5238,
+ +0.0938, -0.4166, -0.1472, -0.0707, +0.0508, -0.2121, -0.2691,
+ -0.3868, +0.3209, +0.1520, -0.3473, +0.3797, +0.1491, -0.0827,
+ +0.0303, -0.0662, -0.0583, -0.0114, -0.2137, -0.0716, -0.2505,
+ +0.0234, +0.1942, -0.2429, -0.1812, +0.2127, -0.3146, -0.0560,
+ -0.1975, -0.2884, +0.1577, -0.1066, +0.3612, -0.4182, +0.3614,
+ +0.1490, +0.2338, -0.1749, +0.1586, -0.1450, -0.3109, +0.0085,
+ +0.2919, -0.5191, -0.4061, +0.3164, -1.2844, -0.0685, -0.0588,
+ +0.0751, -0.3219, +0.4100, -0.0801, -0.3325, +0.1215, +0.2556,
+ -0.3045, -0.4596, -0.0324, +0.0205, -0.0232, +0.1530, +0.0951,
+ -0.2800, +0.0506, -0.5846, -0.1273, -0.0996, +0.2067, +0.1167,
+ +0.3611, -0.0991, -0.1651, -0.3704, -0.1254, -0.3887, -0.1392,
+ +0.2495, -0.1188, -0.5125, -0.7474, +0.2729, -0.2425, -0.3024,
+ +0.1678, -0.0371, -0.1116, -0.4206, -0.2825, -0.0830, +0.0164,
+ +0.3703, -0.5570, -0.2507, -0.2276, +0.3190, -0.4609, -0.1061,
+ +0.1248, -0.1382, +0.0740, +0.0562, +0.0275, +0.2151, -0.1987,
+ -0.6144, -0.0418, +0.2406, -1.1566, +0.1270, -0.4743, +0.0390,
+ -0.0635, -0.0234
+ ],
+ [
+ +0.1849, +0.2056, -0.8912, +0.1386, -0.2061, +0.2078, +0.0089,
+ -0.5197, -0.3154, -0.3073, -0.4449, +0.1493, +0.4017, -0.4632,
+ +0.0683, -0.0695, -0.2991, -0.1667, -0.8045, -0.2511, -0.2451,
+ +0.4418, +0.2032, +0.1380, -0.1905, -0.2897, +0.0508, -0.0452,
+ -0.0836, +0.1389, +0.1278, -0.0631, +0.0659, -0.0119, -0.4652,
+ +0.0809, -0.0130, +0.1559, -0.2362, -0.0178, +0.4270, +0.2486,
+ -0.0051, -0.1884, -0.2139, -0.6266, -0.2996, -0.6199, -0.1317,
+ +0.0074, +0.4751, +0.2395, +0.2592, +0.1341, -0.0190, -0.2331,
+ +0.2688, -0.7262, +0.2291, -0.1426, -0.0483, -0.0462, -0.1390,
+ +0.1052, -0.6746, +0.1354, -0.0905, +0.1046, -0.1011, +0.0623,
+ -0.6305, -0.6835, -0.2048, +0.0765, +0.2925, -0.0006, +0.4725,
+ -0.5182, -0.1838, +0.1910, -0.4000, +0.0748, -0.5708, -0.1253,
+ -0.1979, +0.4603, +0.2264, -0.1244, -0.1174, +0.1527, -0.0043,
+ -0.0938, -0.1171, -0.2813, +0.1696, -0.7883, +0.0192, +0.0551,
+ -0.6117, +0.1119, -0.5844, -0.5764, -0.0239, +0.0728, -0.0364,
+ -0.3200, -0.2571, +0.1682, -0.0850, -0.1715, -0.2180, +0.4132,
+ +0.1072, +0.3502, +0.2404, +0.0948, +0.0001, +0.0032, +0.0910,
+ -0.0538, +0.4683, -0.1478, -0.0923, +0.0925, +0.3624, -0.3939,
+ -0.1887, -0.0461
+ ],
+ [
+ -0.6513, -0.0528, -0.0799, +0.0180, -0.0639, +0.1353, +0.1291,
+ -0.4689, -0.1285, +0.0403, -0.0495, -0.2101, -0.0562, +0.0413,
+ +0.3756, +0.2829, -0.4205, +0.0386, -0.2373, +0.1858, -0.1519,
+ -1.2870, +0.0758, -0.0572, -0.0928, +0.0717, +0.2179, -1.3161,
+ +0.0086, -0.3917, -0.3191, -0.1952, -0.4163, +0.1665, +0.0394,
+ +0.1485, -0.3066, -0.5259, +0.0706, -0.1073, -0.7096, -0.3626,
+ -0.2640, -0.3450, -0.0300, -0.0195, -0.2554, +0.3610, -0.6629,
+ -0.0244, +0.0810, +0.1760, -0.1691, -0.0746, -0.1397, +0.2106,
+ -0.3880, -0.8769, -0.1162, -0.3865, +0.4369, +0.0547, -0.2496,
+ +0.2524, +0.2667, -0.1418, +0.0266, -0.3762, -0.0858, +0.0070,
+ +0.1271, +0.3415, +0.3415, +0.0483, +0.4017, -0.0354, -0.3031,
+ +0.3032, +0.1559, -0.0946, +0.3062, -0.2216, +0.1691, -0.0621,
+ +0.3155, +0.2635, +0.2077, +0.0959, +0.0565, +0.2541, +0.0393,
+ +0.0420, +0.1090, -0.3292, -0.2852, -0.1791, -0.3682, +0.3089,
+ -0.0278, +0.0165, -0.2482, -0.0125, +0.1965, -0.2145, +0.2043,
+ -0.7790, -0.2388, +0.1049, -0.0955, -0.0739, -0.3513, -0.7518,
+ -0.0023, -0.1168, +0.2432, +0.1824, -0.4548, -0.1216, +0.2842,
+ +0.0144, +0.1611, +0.1462, +0.4332, -0.4961, +0.0503, -0.1672,
+ -0.2520, +0.0050
+ ],
+ [
+ -0.4374, +0.0677, +0.1759, -0.0717, -0.5386, +0.0776, -0.0142,
+ -0.5765, -0.3650, +0.3188, -0.7733, -0.4377, -0.7963, -0.3026,
+ -0.2102, -0.8911, -0.4924, +0.3700, -0.0042, -0.4664, -0.1002,
+ -0.1016, -0.1787, +0.1152, -0.0962, -0.2385, -0.0872, -0.2961,
+ -0.1030, +0.1671, -0.2583, -0.2238, -0.1293, -0.0782, -0.4061,
+ -0.3127, +0.1150, +0.1069, +0.0334, +0.2424, -0.0779, +0.1749,
+ +0.1685, +0.4895, -0.4784, -0.5112, +0.3653, -0.3491, -0.0358,
+ -0.0161, -0.7627, -0.2534, -0.1499, -0.6884, +0.1699, +0.1398,
+ +0.0126, -0.6539, -0.5635, +0.3513, +0.0543, +0.4240, -0.0515,
+ -0.6213, -0.1297, +0.5964, +0.2096, +0.0586, -0.3029, +0.1138,
+ -0.5396, -0.2229, -0.8885, -1.1727, +0.0485, -0.2309, +0.2224,
+ +0.3499, -0.0101, +0.0408, +0.1950, +0.1235, -0.3856, +0.0873,
+ -0.3156, -0.1496, -0.0588, -0.2328, +0.2851, +0.3854, +0.1741,
+ +0.1355, +0.0666, -0.2230, +0.0363, +0.3607, -0.8664, +0.0231,
+ -0.1652, -0.2408, -0.2333, +0.1644, -0.5628, +0.2266, -0.0874,
+ -0.7965, +0.4027, +0.1313, -0.0736, +0.3931, +0.1241, -0.5326,
+ -0.1481, -0.2934, +0.3501, -0.5848, -0.3682, -0.0025, -0.0314,
+ +0.0481, +0.1469, -0.2880, -0.2509, +0.0841, -0.2406, -0.1403,
+ -0.3320, -0.1264
+ ],
+ [
+ +0.2835, -0.2385, +0.0157, -0.1775, -0.0661, +0.2835, -0.2914,
+ -0.0802, +0.0005, -0.9043, +0.3188, -0.0884, +0.1066, -0.4199,
+ -0.4391, -0.2280, -0.6856, +0.0331, -0.9060, +0.1107, +0.1094,
+ +0.2466, -0.1458, +0.0564, -0.8896, -0.7002, -0.1500, +0.3055,
+ -0.1778, -0.1791, +0.1248, +0.0839, +0.0610, +0.0625, -0.0862,
+ -0.0261, -0.1398, -0.1335, -0.6727, +0.2547, -0.7196, +0.1070,
+ +0.2992, +0.0814, +0.0297, +0.0174, -0.1268, -0.2557, -0.8446,
+ -0.0955, -0.1967, -0.1212, +0.1532, -0.5281, -0.1994, +0.1381,
+ +0.1805, -0.5466, +0.0128, -0.1981, +0.3126, +0.1236, -0.3552,
+ -0.0086, -0.4803, -0.1862, +0.0102, +0.0481, -0.3328, +0.1807,
+ -0.3255, -0.5793, +0.1044, +0.0913, +0.0427, -0.0351, -0.7696,
+ -0.1137, -0.0585, -0.0956, +0.2934, +0.1989, +0.4311, -0.3571,
+ +0.1281, +0.1825, -0.0877, +0.1746, +0.3465, -0.0489, -0.0920,
+ -0.1478, -0.2537, +0.0394, -0.2832, +0.1150, +0.1023, +0.0576,
+ +0.1433, +0.1745, +0.2718, +0.0142, +0.1164, -0.1714, +0.0859,
+ -0.1570, -0.0102, +0.3979, -0.4980, -0.0764, -0.5556, -0.3163,
+ +0.0547, -0.1635, +0.1372, +0.2434, -0.0717, +0.1115, +0.0103,
+ +0.2736, +0.1025, +0.3237, +0.1072, -0.1598, +0.2211, -0.9020,
+ -0.0138, -0.0541
+ ],
+ [
+ +0.5913, -0.1232, +0.4854, -0.9341, -0.0232, -0.2916, -0.0394,
+ -0.6606, +0.2191, +0.5984, -0.3938, -0.0504, -0.0565, -0.5473,
+ -0.1880, +0.7157, -0.0056, -0.4979, -0.2422, +0.0283, -0.0454,
+ -0.1495, +0.1372, -0.1654, -0.0747, +0.0656, +0.0167, +0.3254,
+ +0.2891, -0.4931, +0.0534, -0.2193, +0.0124, +0.0179, -0.2722,
+ +0.1878, +0.0150, +0.2374, -0.6084, -0.2652, -0.2618, +0.0132,
+ -0.0302, +0.0346, -0.1478, -0.6839, +0.0778, -0.3381, +0.2921,
+ -0.1248, +0.2446, +0.0116, -0.4571, -0.1960, +0.5189, -0.6623,
+ +0.2867, -0.5312, +0.5299, -0.0400, -0.3333, +0.3019, +0.7214,
+ -0.6399, +0.0920, +0.0674, -0.2953, -0.3731, -0.1957, +0.2722,
+ +0.5687, +0.1900, -0.1495, +0.2474, +0.5458, -0.0210, +0.3382,
+ +0.1387, +0.3749, -0.7159, -0.2116, +0.2044, +0.0299, -0.6997,
+ -0.0607, -0.1249, +0.4435, +0.1194, -0.3956, -0.3680, +0.7815,
+ -0.3192, -0.2005, +0.6671, +0.1049, +0.1786, -0.0453, +0.0361,
+ +0.3828, +0.1632, -0.2219, +0.0587, -0.0778, +0.2726, -0.1161,
+ -0.8251, -0.9922, -0.1238, -0.2244, -0.0043, -0.8359, -0.4257,
+ +0.3097, -0.0342, -0.6175, +0.1667, +0.2046, -0.4767, -0.5294,
+ +0.3274, +0.6918, -0.2039, +0.0763, -0.1972, +0.2738, -0.1745,
+ +0.3617, -0.1313
+ ],
+ [
+ +0.3985, -0.7089, -0.0332, +0.0505, +0.0036, -0.0961, -0.0241,
+ +0.2885, -0.2104, +0.0825, +0.2986, +0.1737, -0.1259, -0.6318,
+ -0.5804, -0.4030, -0.5987, -0.4087, +0.0740, -0.4228, +0.0196,
+ -0.0847, -0.1110, +0.1669, +0.2755, -0.6475, +0.1167, -0.0541,
+ +0.1044, -0.0361, -0.1183, +0.1291, -0.0599, +0.1331, -0.2997,
+ +0.2303, +0.1575, +0.3870, -0.1515, -0.4865, -0.6648, +0.1327,
+ +0.1144, +0.0974, +0.0034, -0.2743, +0.0202, -0.1749, -0.1239,
+ -0.3202, -0.3870, +0.0799, -0.1327, +0.0868, +0.3767, +0.1424,
+ +0.1184, +0.4465, -0.1336, -0.0741, -0.3882, +0.1285, -0.3939,
+ -0.7510, -0.6497, -0.2128, -0.4897, -0.1906, +0.2443, -0.0178,
+ +0.2300, +0.1188, -0.1663, -0.2625, +0.1943, -0.1735, +0.1914,
+ -0.3450, -0.7589, -0.1376, -0.2713, -0.5135, +0.1341, -0.1255,
+ +0.1950, +0.0079, +0.1064, +0.1392, -0.1342, -0.5934, +0.2223,
+ -0.7193, -0.3631, -0.0109, -0.6700, -0.0695, +0.3342, -0.3029,
+ -0.4486, -0.3059, -0.1220, +0.0722, +0.1273, +0.0583, -0.4831,
+ +0.1510, -0.1138, +0.0517, -0.1325, -0.2582, +0.2351, -0.1619,
+ -0.0685, +0.0409, +0.1921, -0.5289, -0.8433, -0.3236, +0.1013,
+ -0.0917, -0.4555, +0.2112, +0.5211, +0.0347, -0.0369, -0.0381,
+ +0.1335, +0.0780
+ ],
+ [
+ +0.3391, -0.1031, +0.5497, -0.0912, -0.0822, +0.0400, +0.0104,
+ -0.2520, -0.2326, -0.1946, +0.1817, +0.1504, -0.1373, -0.3782,
+ +0.2782, -0.0811, -0.1670, -0.0752, -0.0038, +0.0659, -0.1489,
+ +0.0530, -0.1602, +0.2660, +0.3501, -0.3531, +0.0742, +0.4502,
+ -0.1074, +0.3760, +0.3817, +0.3847, -0.0346, -0.2125, -0.3708,
+ +0.1074, -0.5406, +0.6945, +0.0836, +0.5442, -0.0731, +0.1704,
+ -0.2789, -0.2147, -0.1203, -0.4953, -0.2338, -0.6956, -0.2753,
+ -0.2008, +0.3548, +0.2988, -0.0777, -0.1839, +0.2720, -0.3387,
+ -0.0846, +0.2037, +0.1424, +0.1685, -0.0319, -0.2133, +0.2418,
+ -0.2023, +0.0885, -0.2266, -0.0139, +0.1143, +0.2558, +0.1364,
+ -0.0488, -0.3719, +0.1516, +0.0701, -0.0487, -0.1628, +0.6667,
+ -0.0374, -0.0616, -0.6835, +0.3366, +0.3745, +0.3795, -0.3324,
+ +0.0391, +0.1536, +0.4374, +0.3632, -0.1966, -0.3302, +0.0733,
+ +0.2078, +0.1054, -0.1593, -0.4613, -0.0141, -0.1862, +0.3851,
+ -0.3174, +0.1968, -0.2634, +0.0754, +0.0973, +0.4310, +0.0077,
+ +0.1042, +0.5596, +0.1151, -0.0996, +0.2052, +0.0175, -0.1184,
+ -0.0746, -0.0426, +0.1649, -0.1099, -0.1221, -0.8761, +0.1507,
+ +0.0753, -0.1373, +0.0390, +0.3692, +0.0726, +0.1944, -0.3016,
+ -0.0347, -0.0190
+ ],
+ [
+ +0.1592, -0.9045, -0.3388, +0.2854, -0.3764, -0.2765, -0.2451,
+ +0.2391, -1.0949, +0.0841, +0.3115, -0.3353, -1.3785, +0.1600,
+ +0.3432, +0.2445, +0.1564, +0.0087, +0.3491, -0.5923, -0.2462,
+ -0.4761, -0.4795, +0.1626, -0.1966, -0.2813, -0.1815, -0.1901,
+ -0.4001, +0.0344, -0.1321, +0.0140, -0.3800, +0.1196, -0.1599,
+ -0.2739, +0.0795, -0.2032, +0.3463, +0.0708, +0.2574, -0.0073,
+ -0.2222, -0.2274, -0.1679, +0.0262, +0.3934, -0.0947, +0.3593,
+ -0.0873, -0.4258, -0.1662, -0.2950, +0.0077, -0.0881, -0.3166,
+ -0.4573, -0.0139, +0.1009, +0.1217, +0.3329, +0.2159, +0.2382,
+ +0.0680, +0.2457, +0.0094, -0.1908, +0.4279, -0.4443, +0.0266,
+ +0.3519, +0.1389, -0.9522, -0.1226, +0.1761, +0.0645, -0.3624,
+ -0.0373, -0.6709, -0.6824, +0.0779, +0.4334, -0.1997, +0.2059,
+ -0.2751, +0.4227, +0.1345, +0.3756, -0.6810, +0.1684, +0.0572,
+ +0.0989, -0.7624, -0.0815, +0.0952, -0.1433, -0.1627, -0.0365,
+ -0.4531, -0.3340, -0.3930, +0.0047, -0.7260, -0.7704, -0.1741,
+ -0.6385, -0.2428, -0.2376, -0.2202, +0.3776, +0.3622, +0.3179,
+ -0.5478, -0.0946, -0.4054, -0.3539, +0.1668, -0.3799, -0.6982,
+ +0.2685, -0.1232, -0.1367, +0.1098, -0.0299, +0.2043, +0.4321,
+ +0.6063, -0.1830
+ ],
+ [
+ +0.0292, -0.0010, +0.2158, -0.4331, -0.0310, +0.0424, +0.3919,
+ -0.7883, +0.2159, +0.1283, +0.1814, -0.1074, +0.2870, +0.3619,
+ -0.0246, +0.1734, -0.2848, +0.0568, +0.2306, +0.1180, +0.3157,
+ -0.5900, -0.2666, -0.6148, -0.2705, +0.4858, +0.0142, -0.2339,
+ +0.3535, +0.3406, +0.0438, -0.1729, +0.1806, +0.1529, -0.3753,
+ +0.1985, -0.6612, -0.0589, +0.2622, +0.3362, -0.3548, +0.0882,
+ +0.0478, -0.0368, +0.1482, +0.2514, +0.1228, -0.1455, -0.1251,
+ +0.0611, +0.0816, +0.0377, -0.1065, +0.0500, -0.3750, -0.2686,
+ -1.3232, -0.3649, -0.5384, -0.3742, +0.1670, -0.3885, -0.0707,
+ +0.4238, -0.0005, +0.3778, -0.9734, +0.3905, +0.6022, -0.0947,
+ -0.7236, -0.1353, +0.0807, -0.8187, -0.0729, -0.3487, -0.1654,
+ +0.2132, +0.0264, +0.1123, -0.0456, +0.1316, -0.7286, +0.2312,
+ -0.2189, -0.0716, -0.3669, -1.2613, +0.1973, -0.5447, +0.1262,
+ -0.4810, +0.3795, -0.6663, +0.3199, +0.0797, +0.0648, -0.7192,
+ +0.3327, -0.3189, -0.0497, -0.3963, -0.2406, -0.2792, +0.0374,
+ +0.1829, +0.1853, -0.0994, -0.7060, -0.1172, -0.0547, -0.2612,
+ -0.9416, -0.3015, -0.0489, +0.0872, +0.2002, -0.5830, +0.0093,
+ -0.2521, -0.3983, -0.5610, -0.1444, -0.0213, -0.1840, +0.5584,
+ +0.1573, -0.0839
+ ],
+ [
+ -0.0054, -0.1552, +0.0445, +0.5473, +0.3489, +0.0942, +0.1283,
+ +0.1088, +0.2221, +0.0951, -0.2887, -0.3084, +0.0476, -0.6876,
+ -0.1634, -0.0490, +0.0768, +0.1582, -0.3275, -0.2437, -0.1178,
+ -0.0054, -0.2570, +0.1724, +0.0588, -0.8220, +0.3945, +0.3071,
+ +0.0125, +0.0827, +0.2293, +0.1611, -0.0184, +0.3169, +0.3854,
+ -0.1290, +0.3770, +0.0940, +0.0282, +0.1175, -0.1819, +0.0814,
+ -0.3593, +0.4649, +0.4170, -0.3505, -1.3469, +0.1904, +0.0756,
+ -0.4528, -0.1058, +0.0501, +0.1074, +0.0082, +0.0061, -0.3440,
+ -0.0304, -0.1088, -0.0586, +0.0032, -0.0331, -0.0033, +0.0723,
+ -0.3142, -0.1265, -0.0172, +0.1410, -0.0386, -0.2496, +0.1728,
+ +0.2118, +0.3957, +0.1726, +0.1006, -0.3493, -0.1489, -0.3966,
+ -0.2837, -0.0478, -0.0989, +0.1569, +0.0148, -0.0214, -0.0335,
+ -0.0149, +0.4945, -0.5369, -0.0122, -0.0322, +0.2602, +0.2476,
+ -0.1682, -0.4900, +0.1432, +0.0293, -0.3913, -0.0559, +0.1990,
+ +0.1417, -0.4177, +0.3085, -0.2313, +0.0765, -0.3012, +0.1796,
+ -0.5680, +0.3003, +0.1191, -0.1923, -0.1704, -0.2999, -0.4388,
+ -0.7674, -0.0022, +0.1210, +0.1297, -0.2887, +0.1796, +0.3751,
+ +0.2259, -0.0375, -0.0734, +0.3011, +0.1191, -0.0989, +0.0234,
+ +0.4871, +0.0155
+ ],
+ [
+ -0.2794, +0.4030, -0.8714, +0.1589, +0.3095, -0.2938, -0.5479,
+ -0.1597, -0.1159, -0.3491, +0.4800, +0.0262, +0.3959, -0.6992,
+ -0.7997, -0.1646, +0.2888, -0.8217, +0.1957, +0.2923, +0.0236,
+ +0.2229, +0.0514, +0.1859, -0.2631, -1.0410, +0.0539, -0.3402,
+ -0.0101, -0.2683, +0.3238, +0.0962, -1.0021, -0.0456, -0.9495,
+ +0.3728, -0.0316, -0.0075, +0.2809, +0.3721, -0.1940, +0.0839,
+ -0.5128, +0.3385, -0.0146, +0.0474, -0.7893, -0.0244, -0.4119,
+ -0.1384, -0.3560, -0.5578, +0.0636, -0.5752, -0.2949, +0.5623,
+ +0.1826, -0.2331, -0.2763, +0.1912, -0.1321, +0.0604, +0.1944,
+ -0.1728, -0.3342, +0.0470, -0.0843, +0.3187, -0.0226, +0.0507,
+ -0.2920, -0.9700, -0.0704, -0.3181, -0.1028, -0.3946, -0.3361,
+ +0.3495, +0.2483, +0.2804, -0.0085, -0.2937, -0.2936, -0.0616,
+ -0.0207, -0.4355, +0.1786, +0.2164, +0.1249, +0.3248, +0.2681,
+ -0.1227, +0.2755, +0.2102, -0.8579, -0.1426, -0.0127, +0.0146,
+ +0.3679, +0.1330, +0.2826, +0.1176, -0.0155, +0.4931, +0.1725,
+ +0.0041, -0.0312, +0.1938, +0.5592, -0.0589, +0.0588, -0.0504,
+ +0.1824, +0.1543, +0.2127, -0.1573, +0.0825, -0.1487, +0.0773,
+ -1.0069, +0.3602, +0.1695, -0.1658, -0.4918, -0.2411, -0.0045,
+ +0.1308, -0.0919
+ ],
+ [
+ -0.0144, -0.1173, -0.0091, -0.0784, +0.3286, +0.4062, -0.4460,
+ +0.0764, -0.0014, -0.2451, -0.3954, +0.1172, +0.1226, -0.0482,
+ -0.0108, -0.5943, +0.5661, +0.1431, -0.0304, +0.0496, -0.6318,
+ +0.0808, -0.1243, +0.2488, -0.3727, +0.1838, -0.1293, -0.5253,
+ -0.2261, -0.0610, -0.0719, -0.9734, +0.0533, -0.2570, +0.1856,
+ +0.1661, -0.0942, -0.4841, +0.3055, -0.3630, -0.3041, +0.3149,
+ +0.0270, -0.2742, -0.3865, -1.0538, -0.2327, +0.1288, -0.3333,
+ -0.0792, -0.1043, -0.0144, -0.4203, -0.2229, -0.1949, -0.1688,
+ +0.0234, +0.4592, -0.2843, +0.1205, -0.1586, -0.1057, -0.4400,
+ +0.2341, -0.0925, -0.0170, +0.6462, -0.0736, +0.2749, +0.4940,
+ +0.0412, +0.1284, -0.1656, +0.1447, +0.2860, +0.1238, +0.2212,
+ +0.1228, -0.2901, +0.2669, +0.2428, +0.4930, +0.3968, -1.0630,
+ -0.3707, -0.4179, -0.0529, +0.1792, +0.0515, -0.0135, -0.3825,
+ +0.0324, -0.3215, +0.0142, -0.6385, -0.3276, -0.2980, -0.3898,
+ -0.3575, +0.0054, +0.0518, +0.1864, +0.1134, -0.0957, +0.1494,
+ -0.0553, -0.4238, +0.0880, -0.0626, -0.4486, -0.7110, +0.0714,
+ -0.0491, +0.1992, -0.4954, -0.2394, -0.1724, +0.1084, -0.3245,
+ -1.6636, +0.2524, -0.6147, +0.0663, +0.3333, -0.1083, -0.7804,
+ -0.1384, -0.2598
+ ],
+ [
+ -0.2018, -0.5408, +0.0414, +0.1091, +0.3718, +0.2390, +0.4673,
+ -0.2912, +0.0094, -0.0723, -0.3211, -0.1889, -1.4788, +0.3892,
+ +0.1359, -0.1354, -0.0398, -1.3709, -0.2299, +0.2701, -1.3452,
+ -0.3284, -0.1971, -0.7869, +0.1948, +0.2171, -0.2420, +0.3016,
+ +0.4040, +0.6372, +0.0466, -0.6071, +0.3696, -0.0766, +0.1127,
+ +0.3249, +0.1572, +0.1858, +0.1178, +0.1339, +0.0237, -0.0347,
+ -0.0048, -0.1617, -0.7564, -0.1252, -0.0638, -0.1959, -0.4785,
+ -0.1408, -0.3030, +0.2420, -0.3357, -0.0812, -0.1504, +0.1962,
+ +0.1617, +0.0325, -0.2494, -0.1924, +0.2825, -1.0908, -0.5430,
+ -0.2254, -0.0517, -0.2560, -0.2175, -0.2357, -0.2966, -0.1681,
+ +0.2224, -0.1229, -0.9143, -0.3390, +0.1872, +0.0530, -0.0697,
+ -0.6127, -0.3514, +0.0880, -0.2166, -0.2539, +0.0688, +0.1428,
+ +0.2118, +0.1108, -0.0943, +0.1286, -0.3968, +0.1960, -0.0700,
+ +0.5808, +0.0374, -0.5084, -0.3881, +0.0575, +0.2369, +0.5628,
+ -0.2804, +0.4851, +0.1104, +0.0284, -1.1431, +0.1047, -0.3442,
+ +0.1048, -0.0653, +0.1550, +0.0134, -0.2567, +0.4448, +0.0309,
+ +0.1873, +0.2369, +0.0031, -0.3404, +0.3019, +0.1128, -0.1842,
+ +0.0481, -0.0884, +0.3235, -1.0687, -0.1321, +0.2978, -0.2362,
+ +0.0378, +0.1971
+ ],
+ [
+ +0.2535, -0.2242, -0.0908, +0.5499, -0.2328, -0.3475, +0.2398,
+ -0.1673, +0.1231, -0.6901, +0.0918, -0.0608, +0.0751, +0.2779,
+ -0.3674, -0.0832, +0.1389, +0.0036, -0.0265, -0.0870, -0.0760,
+ -0.3173, +0.0605, +0.2014, -0.3164, -0.0104, -0.0169, -0.3861,
+ -0.2773, +0.0635, +0.0945, -0.5024, +0.1406, +0.0821, -0.0719,
+ -0.1437, -0.3810, +0.2135, -1.1224, -0.0387, +0.1928, +0.1379,
+ +0.0183, -0.0645, -0.0482, +0.1046, -0.2203, +0.0935, +0.2519,
+ -0.2642, +0.1156, -0.3227, -0.1677, -0.2038, +0.0520, +0.0623,
+ -0.1027, +0.0175, -0.0584, +0.0420, +0.1626, -0.8398, -0.0657,
+ -1.0170, +0.0191, -0.9715, +0.0380, -0.1604, -0.6074, -0.0295,
+ -0.2755, +0.1088, -0.1964, +0.2977, -0.3666, -0.3127, +0.2279,
+ +0.0716, -0.5187, +0.1724, +0.1011, +0.0378, -0.5323, +0.0495,
+ -0.5084, +0.0564, +0.0451, +0.1388, +0.0659, -0.0164, +0.1866,
+ -0.4834, +0.0857, +0.0201, +0.1044, -0.0152, +0.1856, +0.4617,
+ +0.0526, -0.0806, -0.1098, +0.0640, -0.1741, -0.1642, -0.1463,
+ -0.2830, +0.0557, -0.3862, +0.4099, -0.3520, -0.0970, +0.2255,
+ +0.0056, +0.2791, -0.3706, +0.2901, -1.1393, +0.2312, -0.0597,
+ +0.1108, -0.1686, -0.3515, -0.0123, +0.6058, +0.0172, +0.1834,
+ +0.1619, +0.0642
+ ],
+ [
+ +0.1424, +0.2771, -0.4119, -0.4453, -0.0806, -0.0313, +0.0615,
+ +0.0926, -0.0154, +0.1544, +0.0413, -0.0090, +0.0009, +0.1263,
+ -0.5136, +0.1391, +0.1423, -0.2059, +0.3629, +0.0897, -0.2172,
+ -0.0581, -0.4607, -0.6676, +0.2999, +0.1044, -0.0923, +0.0546,
+ +0.1458, -0.0486, +0.0829, -0.4731, +0.0825, -0.4984, -0.2204,
+ -0.0278, +0.1608, +0.3046, +0.0612, +0.0308, -0.1741, -0.1062,
+ -0.1894, +0.3414, +0.3394, +0.2683, -0.5036, -0.4462, +0.1405,
+ -0.0271, -0.1875, +0.3876, -0.0901, +0.1749, +0.2442, -0.6949,
+ -0.3359, -0.3871, -0.1453, -0.6950, -0.1424, +0.1110, -0.0955,
+ +0.1216, +0.3672, -0.1412, -0.1766, +0.0060, -0.1309, +0.0924,
+ -0.0070, -0.0084, -0.7878, +0.0983, -0.2382, +0.3212, -0.0379,
+ -0.0494, -0.4345, -0.3754, +0.1283, +0.1056, +0.1202, +0.2826,
+ -0.2463, +0.2949, -0.3612, -0.0565, -0.1518, +0.1379, -0.4485,
+ -0.4255, -0.0535, -0.8579, +0.3174, -0.0837, -0.0182, +0.0520,
+ -0.1110, +0.1957, +0.4089, +0.0444, +0.1904, +0.0056, +0.1465,
+ +0.2565, -0.5486, -0.6667, -0.0006, -0.8126, -0.1335, -1.0578,
+ +0.1406, -0.3655, +0.1303, -0.0280, +0.3007, +0.2532, -0.0795,
+ +0.0004, -0.1005, +0.3299, +0.0909, -0.3170, +0.1544, +0.3338,
+ +0.0422, +0.0507
+ ],
+ [
+ +0.4021, -0.5260, +0.0290, -0.7127, +0.3292, +0.3961, -0.4303,
+ -0.1401, +0.1137, +0.1113, -0.2227, -0.2856, +0.1078, -0.5298,
+ -0.2920, -0.3745, -0.7590, +0.1277, -0.5133, -0.5365, -0.0345,
+ +0.3073, +0.0114, +0.5255, +0.2158, +0.2393, +0.2765, +0.0396,
+ +0.1927, -0.1368, +0.0504, -0.1286, +0.2574, -0.3011, +0.0240,
+ +0.1241, +0.0423, -0.2273, -0.0235, +0.0078, -0.6403, -0.3858,
+ -0.5220, -0.6192, +0.4249, -0.5309, -0.1737, +0.1826, -0.1282,
+ +0.5431, -0.0770, -0.3576, +0.1624, +0.0156, -0.4015, -0.5880,
+ -0.4772, +0.1299, +0.1412, +0.3017, -0.3183, +0.2800, +0.1079,
+ -0.3318, -0.3915, -0.0236, -0.2534, -0.0653, +0.0220, -0.5014,
+ -0.0448, +0.4895, -0.5066, +0.0322, -0.4296, +0.5146, +0.0200,
+ -0.5356, -0.0013, +0.0327, -0.3246, -0.2293, -0.2541, -0.4495,
+ -0.5473, +0.2847, -0.1901, -0.2312, -0.1694, -0.6842, -0.1511,
+ -0.1708, +0.1053, -0.5946, -0.3606, -0.2067, -0.1559, +0.0507,
+ -0.2181, -0.0979, -0.1372, -0.1785, +0.0791, -0.2753, -0.1703,
+ +0.0233, +0.2168, +0.4180, -0.4231, +0.0265, -0.0540, +0.1337,
+ -0.4377, -0.2039, -0.2325, +0.1548, -0.3411, -0.4092, -0.7270,
+ +0.5202, +0.1287, +0.2782, -0.1197, +0.1253, -0.0600, -0.5236,
+ -0.6407, -0.1578
+ ],
+ [
+ +0.2248, -0.0462, -0.8284, +0.3114, +0.1852, +0.1834, +0.2051,
+ +0.0036, +0.3927, +0.0424, +0.3012, +0.3949, -0.1332, -1.5290,
+ +0.1408, +0.1054, -0.7331, -0.1059, -0.2528, -0.3250, -0.0382,
+ -0.2839, +0.2565, -0.1068, -0.9446, +0.1441, -0.3193, -0.2635,
+ +0.0176, +0.0265, -0.0176, -0.2029, -0.0225, +0.1164, -0.1823,
+ -0.3814, +0.0164, +0.1373, -0.3667, -0.7848, -0.0255, -0.0129,
+ +0.1221, +0.1512, +0.1171, +0.1466, +0.5229, -0.6438, -0.0683,
+ +0.3447, -0.0477, +0.3481, +0.0824, -0.2259, -0.0708, -0.1149,
+ -0.0211, -1.2025, -0.1185, +0.0719, -0.1111, -0.1185, +0.2291,
+ -0.6489, -0.0429, -0.1608, -0.9844, -0.2071, +0.3207, -0.7894,
+ -0.4253, -0.2946, -0.1613, +0.0676, -0.2046, +0.0975, -0.1958,
+ +0.1665, -0.0771, -0.4754, -0.7693, +0.2628, +0.2711, +0.0761,
+ +0.0111, -0.2896, -0.1529, -0.2488, +0.4496, +0.1245, -0.4776,
+ -0.0319, -0.0583, -0.0840, +0.1204, +0.2630, -0.0326, +0.1000,
+ -0.2014, +0.1737, -0.3519, +0.0156, +0.1333, +0.6454, +0.0150,
+ +0.1053, -0.0615, +0.1535, -0.6005, -0.6815, +0.3927, -0.0731,
+ +0.2823, +0.1357, -0.1806, -0.1308, -1.2679, +0.2003, +0.2598,
+ -0.3577, -0.1103, -0.1210, +0.3821, +0.0155, +0.1079, +0.0055,
+ +0.1147, -0.2482
+ ],
+ [
+ -0.1591, -0.0014, +0.1338, -0.7125, -0.7493, -0.1707, +0.3043,
+ +0.1481, +0.1947, -0.5341, -0.3419, +0.2912, +0.2841, +0.0855,
+ +0.0824, -0.3565, +0.0561, +0.0377, +0.2687, -0.2008, +0.4876,
+ +0.1415, -0.7958, -0.1996, -0.4545, -0.0042, -0.3079, -0.1734,
+ -0.2051, -0.0527, -0.1679, -0.2587, +0.3030, -0.8262, -0.0625,
+ -0.4694, +0.2859, -0.0385, -0.3980, -0.5660, -0.5973, +0.3560,
+ -0.0174, -0.1013, +0.0510, +0.1240, +0.3538, -0.0418, +0.4386,
+ +0.2131, -0.0653, +0.1108, +0.1378, -0.0472, +0.2413, -0.2423,
+ +0.0077, -0.8678, -0.8777, -0.1584, -0.9594, -0.4108, +0.1470,
+ -0.6456, -0.0121, -0.3689, +0.1646, -0.9434, -0.4325, -0.2030,
+ -0.0612, +0.0111, -0.1285, +0.1007, +0.0899, +0.0277, -0.0589,
+ -0.0392, +0.1973, +0.0096, -0.2397, +0.4534, -0.1920, +0.1441,
+ +0.0410, +0.3059, -0.5382, -0.3187, +0.2552, -0.0264, +0.1063,
+ -0.2650, +0.1642, -0.0897, -1.0989, -0.3342, -0.7970, -0.3262,
+ +0.1747, +0.4497, +0.0286, +0.0872, -0.0096, +0.1537, -0.0268,
+ -0.1654, -0.2807, +0.0615, -0.5338, +0.2320, -0.1725, +0.0327,
+ -0.4462, -0.2303, -0.0239, +0.2228, -0.0059, +0.0378, +0.1797,
+ -0.5790, -0.3018, +0.0120, +0.2499, -0.0770, -0.7413, +0.1908,
+ -0.6291, -0.0909
+ ],
+ [
+ -0.1240, -0.4172, -1.2085, -0.3691, +0.0492, -0.1166, +0.1979,
+ -0.2357, +0.1683, +0.5632, +0.2264, +0.3212, -0.3016, -0.1201,
+ +0.2582, -0.1198, +0.0025, +0.1921, -0.2394, +0.4200, +0.6327,
+ -0.4111, -0.3970, -0.0531, -0.3382, +0.1123, +0.1504, -0.3475,
+ +0.1592, +0.1284, +0.2017, -0.2621, -0.3080, -0.0995, +0.1393,
+ -0.1166, +0.0436, -0.2743, -1.1490, +0.0053, +0.1106, +0.0826,
+ -0.0937, -0.0162, -0.2341, +0.0701, -0.2890, -0.1967, -0.3510,
+ +0.2121, -0.0558, +0.1720, -0.0741, -0.0036, +0.2633, -0.3739,
+ +0.0536, -0.1093, -1.3638, -0.0535, -0.1404, -0.1913, -0.1090,
+ +0.0445, -0.2999, +0.3621, -0.2209, -0.3109, -0.0994, -0.0474,
+ +0.2710, +0.0227, +0.0429, -0.0851, -0.1066, -0.0245, -0.1123,
+ +0.1840, -0.8776, -0.0159, -0.1842, +0.1612, +0.6969, -0.5558,
+ -0.5212, +0.2787, -0.1248, +0.1391, +0.1134, +0.1405, -0.5579,
+ +0.2416, +0.0664, +0.1687, -0.1130, -0.1811, -0.0078, -1.1484,
+ +0.3887, -0.3861, +0.1172, +0.3303, +0.3138, +0.1004, +0.2782,
+ -0.3874, -0.2019, -0.6500, -0.0303, -0.6276, -0.2639, -1.1029,
+ +0.1096, +0.2257, -0.3056, -0.4345, -0.0964, +0.0984, -0.1954,
+ +0.2322, -0.5411, +0.0700, -0.3115, +0.3259, +0.0910, +0.1975,
+ -0.2759, +0.0448
+ ],
+ [
+ -0.3904, -0.0199, -0.3537, -0.4832, -0.1628, +0.0043, -0.0414,
+ +0.1218, -0.2269, +0.2141, +0.3481, +0.0906, +0.0224, +0.2132,
+ +0.3279, +0.5876, -0.3077, -0.4872, -0.6630, -0.4332, +0.2724,
+ -0.3827, +0.1056, +0.2548, -0.5510, +0.4017, -0.1022, -0.4635,
+ -0.1546, -0.3860, -0.2522, -0.7110, -0.9669, +0.2434, +0.2342,
+ +0.3793, +0.1495, +0.6897, -0.1169, +0.2553, +0.0812, -0.0038,
+ -0.2082, -0.6254, -0.2263, +0.3667, +0.0377, -0.0467, +0.0525,
+ -0.4292, +0.3255, +0.1481, -0.3301, +0.1646, -0.0131, +0.3723,
+ +0.0310, +0.1258, +0.2263, +0.3037, -0.5007, -0.8377, -0.4179,
+ -0.1642, -0.3209, +0.0559, +0.5227, +0.2157, -0.3959, -0.2160,
+ +0.1486, +0.2303, +0.1043, +0.0733, +0.3248, -0.0592, +0.3219,
+ -0.2249, -0.0967, +0.1890, -0.1448, -0.4372, +0.4339, -0.4763,
+ +0.1388, -0.1501, -0.5580, -0.4443, +0.0384, +0.1303, -0.4852,
+ -0.2745, +0.2143, +0.5117, -0.1081, -0.0613, +0.0808, -0.1280,
+ -0.0541, +0.3160, +0.0524, +0.0024, -0.1632, +0.1957, -0.2029,
+ -0.0273, -0.6920, +0.1693, -0.3618, -0.6140, -0.1295, +0.1724,
+ -0.2306, +0.1818, +0.3156, +0.6412, +0.1616, -0.5177, -0.0959,
+ -0.1618, -0.0358, -0.3144, -0.2045, +0.0474, -0.5212, +0.1608,
+ -0.3414, +0.1889
+ ],
+ [
+ -0.1657, +0.0451, -0.3340, +0.3003, -0.0376, +0.2246, +0.3963,
+ -0.6580, +0.4921, +0.0738, -0.8389, -0.0540, +0.4077, +0.2517,
+ +0.1214, -0.0437, +0.2799, +0.1646, -0.1190, -0.0437, -0.0101,
+ -0.4510, -0.1197, +0.4256, +0.4241, +0.2016, -0.2480, -0.2848,
+ +0.0910, -0.3252, +0.0920, +0.1780, +0.1210, -0.2491, +0.4193,
+ +0.0180, -0.2447, +0.1820, +0.4304, -0.6427, -0.0964, -0.4044,
+ -0.1593, +0.3301, -0.1972, +0.1570, +0.1535, +0.2956, +0.0852,
+ +0.5078, -0.2621, +0.0667, +0.3003, +0.1874, -0.4642, +0.0619,
+ -0.1780, -0.0325, +0.0594, -0.0962, +0.0029, -0.0338, -0.6791,
+ +0.0143, +0.2036, -0.6389, -0.3388, -0.3286, +0.2323, -0.3636,
+ +0.0878, -0.1679, +0.3731, -0.6431, -0.0756, -0.0599, -0.0401,
+ +0.3496, -0.3530, +0.0650, +0.1341, -0.2022, -0.6015, -0.3657,
+ +0.1225, -0.1339, -0.0863, -0.2255, -0.0403, -0.1262, -0.0083,
+ +0.3607, +0.4136, +0.4825, +0.2525, -0.1267, +0.2066, -0.0973,
+ +0.1031, -0.0115, -0.2364, +0.2755, +0.0984, -0.4746, -0.1369,
+ -0.0256, +0.1211, -0.1850, +0.1281, +0.0125, -0.4228, -0.1674,
+ +0.0763, +0.1332, -0.1609, +0.2957, -0.0578, -0.1904, +0.2217,
+ +0.4961, -0.1120, -0.0485, +0.0111, -0.3721, -0.2940, -0.2656,
+ -0.0420, -0.0380
+ ],
+ [
+ -0.0861, +0.1449, -0.6769, +0.0344, -0.2920, +0.1292, -0.2751,
+ +0.1184, +0.3807, -0.3596, -0.7922, +0.0296, +0.6053, -0.8649,
+ -0.6145, -0.9584, -0.1484, -0.2938, +0.5678, -0.1980, +0.9455,
+ +0.1873, -0.4021, -0.0092, +0.1739, +0.0755, -0.2697, -0.5705,
+ -0.1806, -0.4981, -0.9201, -0.2681, -0.5527, -0.5562, -0.2761,
+ -0.1184, +0.0279, +0.0548, +0.2510, +0.1212, +0.2111, -0.2896,
+ +0.0753, -0.1386, -0.3318, +0.4249, -0.4348, -0.6503, -0.9838,
+ -0.0485, +0.1144, +0.7076, -0.1162, -0.0505, +0.1097, +0.1913,
+ +0.1892, -0.0247, +0.0125, -0.2954, -0.0785, -0.7718, -0.6086,
+ -0.0690, +0.5044, +0.0031, +0.0960, +0.2154, +0.3533, +0.5952,
+ -0.1162, +0.5624, -0.2424, +0.0859, -0.2930, -0.1793, +0.7442,
+ +0.0831, -0.1739, +0.2988, -0.7403, +0.6559, -0.8099, -0.1913,
+ +0.1954, -0.3384, +0.0240, +0.2432, -0.3941, +0.2698, -0.2234,
+ +0.1533, -0.0102, +0.0815, +0.3778, +0.1553, +0.2522, +0.2298,
+ +0.1750, +0.3060, -0.3154, -0.9199, +0.1745, +0.4966, -0.1204,
+ +0.0371, -0.9282, -0.1539, +0.2182, -0.2074, -0.5206, +0.4416,
+ -0.6532, -0.0871, -0.1050, -0.0336, +0.0717, -0.0583, +0.0276,
+ -0.7181, +0.2044, +0.2626, -0.1477, -0.1966, +0.5259, -0.2208,
+ +0.1887, -0.3999
+ ],
+ [
+ +0.3951, -0.1828, -0.5690, -0.4359, +0.1588, -0.0299, -0.0165,
+ +0.1315, +0.1514, +0.0204, -0.0711, +0.4348, +0.1533, -0.5613,
+ +0.1055, +0.1061, +0.0002, +0.0874, +0.1442, +0.1372, -0.2141,
+ -0.2999, +0.1639, +0.0992, -0.1852, -0.2600, +0.0525, +0.4053,
+ -0.2276, +0.1156, -0.1959, -0.2561, +0.1651, +0.2641, +0.0408,
+ -0.2071, -0.3731, -0.1776, +0.2279, +0.2284, -0.0525, -0.2135,
+ +0.2042, +0.1038, +0.0338, +0.0044, -0.1703, -0.2930, +0.3392,
+ +0.3723, +0.3568, +0.1010, -0.6759, +0.1756, -0.0830, -0.0264,
+ -0.3639, +0.2400, +0.1893, -0.7797, -0.2049, +0.6765, -0.9135,
+ +0.1923, -0.4428, -0.2858, +0.1698, -0.0717, -0.0732, -0.1378,
+ +0.1252, -0.3311, +0.3699, +0.2626, -0.1844, +0.2205, +0.1067,
+ +0.2054, +0.1633, -0.0336, +0.1384, +0.2030, -0.4712, +0.1841,
+ +0.1662, -0.4934, +0.2673, +0.1616, -0.1415, +0.1551, +0.1830,
+ -0.7949, -0.1026, -0.0908, -0.2148, -0.0862, -0.3247, +0.2256,
+ +0.4064, +0.0255, -0.2503, -0.1194, +0.0556, +0.2649, -0.1426,
+ -0.3441, -0.4780, -0.0587, +0.1581, +0.0628, -0.9718, +0.4334,
+ +0.0918, +0.0179, -0.2611, -0.2913, +0.0065, -0.3420, +0.1218,
+ +0.0496, +0.4038, -0.2304, +0.3929, +0.2798, +0.0511, -0.0994,
+ -0.1512, +0.0164
+ ],
+ [
+ -0.6535, -0.3824, +0.4637, +0.5439, +0.0985, +0.2432, -0.1147,
+ -0.4929, -0.4969, -0.3765, +0.3427, -0.1913, +0.1222, +0.5814,
+ -0.0775, -0.0383, -1.3698, -0.0067, +0.1913, -1.1719, -0.2135,
+ -0.6633, +0.1711, -0.2446, -0.9635, +0.1336, +0.2132, +0.6358,
+ -0.1220, -0.0156, +0.4911, +0.6260, -0.4446, +0.2189, -0.4621,
+ -0.6081, +0.2439, +0.0313, -0.3464, +0.2112, -0.2890, -0.0802,
+ -0.5375, +0.0254, +0.6150, -1.0068, +0.3383, +0.0250, +0.0761,
+ -0.0716, -0.1940, +0.0720, -1.4718, -0.4669, +0.2584, -0.3336,
+ -0.1380, -0.7112, +0.1706, -0.2030, -0.3693, +0.5311, -0.3647,
+ +0.3416, -0.6086, +0.5480, -0.5410, -0.3621, -0.0866, -0.2212,
+ -0.0025, -0.6617, +0.0389, +0.3139, +0.3728, +0.2861, +0.5063,
+ +0.0971, -0.8710, +0.0632, +0.0308, +0.9254, -0.0867, +0.0167,
+ +0.2415, -0.0486, -0.3985, +0.0814, +0.3215, -0.5556, -0.5459,
+ -0.5135, -0.7426, -0.1787, +0.1893, +0.1558, +0.3495, -0.1245,
+ -0.3737, -0.4077, -0.0901, -0.0731, -0.3761, -0.0108, +0.0373,
+ -0.4581, -0.4615, -0.7974, +0.0734, -0.2704, -0.7788, -1.6055,
+ -0.0438, -0.0669, -0.5751, -0.1561, +0.2110, -0.4103, +0.1436,
+ -1.0879, -1.3066, -0.4354, -0.8070, -0.1949, +0.1103, -0.1615,
+ -0.6326, -0.1823
+ ],
+ [
+ -0.2145, +0.0256, -0.1075, -0.8793, -0.6322, +0.3680, -0.5028,
+ +0.6511, +0.1314, -0.2389, -0.4655, -0.4032, -0.5368, +0.1693,
+ +0.2421, +0.1469, +0.1714, -0.0657, +0.1218, +0.2696, -0.5204,
+ -0.0782, -0.1420, -0.1775, +0.2941, -0.5320, -0.0746, +0.1977,
+ +0.3242, -0.4141, +0.1552, +0.1736, +0.4251, +0.3324, -0.3292,
+ +0.1409, -0.3070, -0.4303, +0.1468, +0.0513, -0.4863, +0.2182,
+ -0.4064, +0.1852, -0.4060, -0.1219, -0.8666, -0.8484, -0.4552,
+ +0.0625, +0.2701, -0.2608, +0.1336, +0.3453, -0.1685, -0.8681,
+ +0.0575, -0.0430, +0.4210, +0.4562, -0.2986, -0.5420, +0.2249,
+ -0.0550, -0.8807, -0.3987, +0.1510, +0.0237, +0.2368, -0.1508,
+ -0.2971, -0.4406, -0.1031, -0.8893, -0.0671, -0.0399, +0.3169,
+ +0.6297, +0.0355, -1.3984, +0.0138, -0.0887, -1.0362, -0.6752,
+ +0.1021, +0.2615, +0.2444, -0.1559, -0.3158, +0.0953, +0.3399,
+ -0.0697, +0.0909, +0.3761, +0.1800, -0.2838, -0.6784, +0.1379,
+ -0.5262, -0.0328, -0.0282, -0.1017, -0.1234, +0.1816, -0.0022,
+ -0.1195, +0.3849, -0.5240, -0.2758, -0.5856, +0.1173, +0.4278,
+ -0.2713, -0.2139, +0.3127, -0.4888, -0.5226, -0.1098, +0.1856,
+ +0.1307, +0.3204, +0.1158, -0.2220, -0.1268, -0.0441, +0.3987,
+ -0.0886, +0.0944
+ ],
+ [
+ +0.4614, -0.0341, -0.3127, -0.3417, +0.1270, -0.2438, +0.1256,
+ +0.2616, +0.1769, +0.2554, +0.0401, +0.4384, -0.3171, +0.1049,
+ -0.6874, -0.8721, -0.2163, -0.0291, +0.2594, +0.0246, +0.0724,
+ +0.2490, +0.0425, +0.0459, +0.2011, -0.5738, -0.1479, -0.3346,
+ -0.0266, +0.2086, -0.0040, +0.0719, -0.2202, -0.2643, -0.2547,
+ +0.1521, -0.3104, -0.2468, -0.1023, -0.3194, +0.2488, -0.0491,
+ +0.3947, +0.1225, -0.2908, +0.1780, -0.0005, +0.1691, -0.2036,
+ -0.2187, -0.1570, +0.1058, -0.2051, -0.3514, -0.1599, +0.2463,
+ +0.1237, -0.0981, +0.2591, +0.4577, -0.3913, -0.0632, +0.2139,
+ -0.1243, -0.2953, -0.2283, -0.6659, -0.1692, -0.1968, -0.0003,
+ +0.0315, -0.0684, +0.1006, +0.1359, +0.1536, -0.3270, -0.0839,
+ -0.2444, -0.3855, -0.4013, +0.1105, -0.0854, +0.2298, +0.0779,
+ -0.1536, -0.1694, +0.1131, +0.1775, -0.6872, +0.5421, -0.0455,
+ +0.3147, +0.0818, -0.1207, +0.3427, +0.1563, +0.1190, -1.2023,
+ -0.7227, -0.3360, +0.2061, -0.2620, +0.2675, -0.3546, +0.1095,
+ +0.3345, -0.7043, -0.0666, -0.7135, +0.1534, -0.5890, +0.0591,
+ -0.3491, -0.2425, +0.2764, +0.3161, -0.6132, +0.1511, -0.3858,
+ -0.2196, -0.0678, -0.0624, -0.3383, +0.0621, -0.0103, -0.0182,
+ +0.0191, +0.0176
+ ],
+ [
+ +0.3280, -0.6080, +0.1045, +0.0185, -0.3494, +0.1962, -1.1529,
+ -0.1475, -0.2069, -0.0661, -0.1141, +0.0642, -0.3862, +0.2403,
+ +0.1153, +0.1199, +0.2059, -0.4460, -0.1596, +0.1914, +0.4296,
+ -0.2750, -0.0871, -0.1282, -0.1870, -0.0862, -0.1798, -0.2860,
+ -0.8532, +0.0651, +0.2535, -0.5395, -0.3260, +0.1887, -0.1736,
+ +0.0770, -0.0835, +0.2064, +0.0084, +0.1442, +0.2413, +0.0272,
+ +0.3630, +0.1719, -0.2559, -0.3920, -0.4000, +0.0806, +0.0958,
+ -0.1785, -0.1645, -0.1561, -0.0642, +0.0036, -0.2139, -0.1258,
+ +0.8286, +0.1008, -0.0724, -0.4328, -0.3329, +0.1013, -0.2245,
+ -0.1468, -0.7493, -0.0072, -0.1338, -0.2106, -0.2979, +0.0908,
+ +0.0397, -0.1220, +0.2189, +0.3704, -0.0164, -0.2005, +0.1434,
+ -0.5151, +0.0326, -0.1560, -0.3458, -0.1486, +0.2803, +0.0808,
+ +0.2556, -0.1591, -0.0879, +0.2555, +0.0905, +0.3518, -0.3664,
+ -1.1826, -0.2343, +0.1236, -0.2352, -0.1818, +0.1976, +0.3657,
+ +0.1101, -0.0302, +0.1046, +0.3013, -0.4328, +0.5137, +0.3280,
+ -0.3893, -0.4061, +0.2101, -0.1510, +0.1469, -0.0312, -0.1720,
+ +0.1547, +0.2162, +0.0479, -0.2715, -0.1427, -0.2122, +0.0937,
+ +0.3623, +0.5012, -0.3414, +0.3632, +0.0504, +0.1106, +0.1535,
+ -0.3803, +0.0121
+ ],
+ [
+ -0.4640, -0.1327, -0.0716, +0.0056, +0.2762, -1.1126, +0.0626,
+ -1.0688, +0.2330, -0.2329, +0.5559, -0.1453, -0.5149, +0.0023,
+ +0.1085, -0.4709, -0.5074, +0.0952, +0.1463, +0.2491, -0.0619,
+ +0.0158, -0.0328, -0.5344, +0.1023, -0.0300, -0.2085, +0.1359,
+ +0.0592, -0.2524, -0.1559, -0.0085, +0.0068, -0.0124, +0.3539,
+ +0.2308, +0.0371, -0.1474, +0.0236, -0.5550, +0.0501, +0.1425,
+ -0.5211, -0.4661, -1.4098, +0.0612, +0.2326, -0.0758, -0.0272,
+ -0.0956, +0.0071, -0.4600, -0.2366, -0.0167, -0.5775, -0.5638,
+ -0.0820, -0.4716, -0.5335, -0.2214, -0.3552, +0.2573, -0.2350,
+ +0.4470, -0.7306, +0.4852, -0.2049, -0.3014, -0.2232, +0.3578,
+ +0.1289, -0.2788, -0.4551, -0.3855, -0.4936, -0.1730, +0.0164,
+ -0.1968, -0.1534, -0.3116, +0.0401, -0.2093, -0.0669, -0.1232,
+ +0.6732, +0.0041, -0.1624, +0.1671, -0.3598, -0.2023, -0.7892,
+ +0.3155, -0.1869, -0.3023, -0.4224, +0.4675, -0.1488, -0.6090,
+ -0.7404, -0.2382, +0.2172, -0.7886, -0.5513, -0.1992, -0.7805,
+ -0.1544, -0.0783, -0.2322, +0.2890, +0.0905, -0.0698, +0.4080,
+ +0.3539, +0.0809, +0.4526, +0.4208, -0.0471, -0.2460, -0.6651,
+ +0.1086, -0.4729, -0.5561, -0.4785, -0.4709, -0.1186, -0.6847,
+ +0.0113, -0.2090
+ ],
+ [
+ +0.1128, +0.2196, +0.0491, +0.0871, -0.0427, -0.1228, -0.1325,
+ -0.0775, +0.0799, -0.4258, -0.4283, +0.0695, -0.4842, -0.7364,
+ -0.3856, -0.5542, +0.1488, -0.0655, +0.1610, +0.2014, -0.0839,
+ -0.0175, -0.1677, -0.4381, -0.3510, -0.3124, -0.1308, -1.4672,
+ +0.0946, -0.4583, -0.6771, -0.2482, +0.0564, -0.0899, -0.3302,
+ +0.3769, -0.2056, +0.1952, -0.7006, -0.0171, +0.0339, -0.7665,
+ -0.2355, -0.4328, +0.4867, -0.9649, -0.7657, -0.2226, -0.0585,
+ -0.0788, -0.1219, +0.2336, +0.0329, -0.1373, -0.0480, -0.4672,
+ +0.1248, -0.3234, -0.0123, -0.0402, -0.7285, +0.1463, -0.2133,
+ -0.3333, -0.3750, -0.3789, +0.2528, +0.2849, -0.2088, -0.1508,
+ -0.0521, -0.2693, -0.0864, -0.2134, -0.0674, -0.0502, +0.0965,
+ +0.1491, -0.0258, -0.8792, +0.0514, +0.2205, +0.1569, +0.1199,
+ +0.0771, -0.2032, -0.1334, +0.1342, +0.4965, -0.3000, +0.4028,
+ -0.4422, +0.3067, -0.2638, +0.0714, +0.0542, -0.0185, +0.0883,
+ -0.4793, +0.0931, -0.1196, +0.2565, +0.1506, -0.2275, -0.0765,
+ -0.0661, +0.0736, +0.5985, -1.2571, -0.4318, +0.0778, -1.4763,
+ +0.0302, -0.0896, +0.0087, -0.1240, -0.1418, -0.4563, -0.2404,
+ -0.2635, +0.0763, -0.3100, -0.1861, -0.0644, -0.0371, -0.0219,
+ +0.3791, -0.3473
+ ],
+ [
+ +0.4353, -0.0027, -0.1405, -0.4122, -0.3522, +0.0526, -0.1707,
+ -0.0385, -0.1975, +0.2925, -0.4776, -0.0418, +0.0446, +0.2244,
+ +0.1293, +0.3907, -0.9109, -0.0468, +0.0137, -0.0460, +0.4094,
+ +0.0427, +0.2939, -0.1557, +0.0021, -0.1208, -0.1217, +0.4177,
+ -0.3536, +0.0166, -0.1902, -0.2393, +0.0345, +0.0799, -0.7020,
+ -0.1663, -0.5196, +0.1123, +0.2173, -0.3454, -0.1350, -0.2988,
+ -0.4965, -0.3230, +0.1591, -0.0365, +0.1462, -0.2123, -0.0619,
+ -0.1740, +0.0770, -0.2098, -0.0199, +0.0795, -0.3884, +0.1162,
+ -0.2321, -0.4210, -0.6708, +0.0618, +0.0358, -0.1079, +0.2677,
+ +0.1349, +0.2558, -0.1510, -0.2075, -0.0258, -0.2588, +0.0050,
+ -0.1894, -0.1519, -0.1532, -0.3941, -0.0508, +0.1084, +0.1652,
+ -0.1217, -0.1805, -0.5194, -0.2663, -1.1767, -0.1488, -0.1212,
+ +0.0229, +0.3766, -0.5909, +0.2650, +0.2342, -0.2097, +0.2822,
+ +0.5491, +0.3619, +0.0758, +0.2908, +0.3512, +0.2550, +0.0763,
+ -0.7615, -0.0578, +0.1206, +0.2908, -0.2384, +0.0054, -0.1382,
+ -0.1125, -0.0447, -0.2442, +0.1242, -0.0534, +0.0024, +0.1971,
+ -0.1923, -0.0621, -0.3769, +0.1903, +0.1829, -0.1082, -0.1367,
+ -0.0554, -0.7187, -0.4493, +0.2949, +0.0883, -0.3279, +0.2849,
+ +0.1060, +0.3663
+ ],
+ [
+ -0.6415, -0.3939, -0.5202, -0.1639, -0.4648, -0.1451, +0.4356,
+ -0.6945, +0.3483, -0.5865, -0.3782, -0.0060, -0.0677, +0.1958,
+ -0.2324, -0.1777, +0.0295, +0.5604, +0.0249, -0.2261, -0.2063,
+ -0.0416, -0.0950, -0.2548, +0.0042, -0.3812, +0.2529, +0.0167,
+ +0.0483, +0.3357, +0.1415, +0.0178, -0.1509, -0.0159, -0.2740,
+ +0.0397, -0.0819, +0.1141, -0.3993, +0.0913, -0.2224, -0.7560,
+ -0.2634, +0.3233, +0.0027, +0.3794, +0.2278, +0.6810, -0.7867,
+ -0.0823, -0.0451, -0.3029, -0.0513, -0.4509, +0.4310, +0.1516,
+ -0.4726, -0.1546, -0.3385, +0.1362, +0.3105, +0.0986, -0.7286,
+ -0.1418, +0.0951, +0.1071, -0.1305, -0.0904, -0.9688, -0.3975,
+ +0.0978, +0.4764, -0.2437, +0.1659, +0.3128, +0.1478, +0.2060,
+ -0.8387, +0.0795, -0.3924, +0.3558, -0.5638, -0.5464, +0.3735,
+ -0.3795, +0.3854, -0.2423, +0.0661, -0.3528, -0.1318, -0.2049,
+ -0.5105, +0.5074, +0.0987, +0.4461, -0.8709, -0.2308, +0.5754,
+ -0.1341, -0.9593, -0.0423, +0.0077, -0.0788, +0.0913, -1.0023,
+ -0.2929, -0.7491, +0.1581, -0.1464, +0.2154, +0.2309, -0.2193,
+ -0.2466, -0.5195, +0.1740, -1.0865, +0.0758, -0.3392, +0.1485,
+ -0.0161, -0.6096, +0.0713, -0.1700, -0.1644, -0.3517, -0.1076,
+ -0.6289, -0.0868
+ ],
+ [
+ -0.0279, -0.1180, -0.2685, -0.4734, +0.4130, +0.2278, +0.2734,
+ -0.1383, -0.1294, -0.2393, -0.2655, -0.2045, +0.1723, -0.1902,
+ -0.0720, -0.1001, +0.0693, -0.2959, +0.4904, -0.4231, -0.6569,
+ -0.5207, +0.0924, -0.2339, +0.1349, -0.0989, +0.2269, -0.5261,
+ +0.0686, +0.2270, -0.1708, -0.7268, +0.0170, -0.8337, +0.1631,
+ -0.1823, -0.1832, +0.4833, +0.2301, +0.2152, -0.1013, +0.1557,
+ +0.1638, -0.1074, +0.0427, -0.0506, -0.2892, -0.2381, +0.2450,
+ +0.2302, -0.3176, +0.0832, +0.1322, -0.4486, +0.4323, -0.5670,
+ +0.0120, +0.1856, -0.0379, +0.1852, -0.0068, -0.4816, -0.5400,
+ -0.5379, -0.1145, -0.6362, -0.2237, +0.0393, -0.2324, -0.1508,
+ -0.5168, +0.1399, -0.8280, +0.0271, +0.0271, -0.1355, +0.3420,
+ +0.0033, -0.0524, -0.0132, -0.0686, -0.2197, -0.2397, +0.4131,
+ +0.3879, +0.1894, -0.0590, -0.2728, +0.2001, -0.5037, -1.1579,
+ -0.1231, +0.1030, +0.3018, -0.1117, +0.2328, -1.1153, +0.2872,
+ -0.8792, +0.1519, -0.0997, +0.3196, -0.4409, +0.3572, -0.1474,
+ +0.0191, -0.4200, -0.3569, +0.0807, -0.5480, -0.5429, +0.1992,
+ -0.0004, -0.7959, -0.6011, +0.0583, +0.1194, -0.1493, +0.1473,
+ -0.6284, -0.2466, -0.5721, -0.0804, -0.0444, +0.2544, +0.0155,
+ -0.0306, -0.3982
+ ],
+ [
+ +0.5828, -0.1462, -0.2782, +0.0690, -0.1789, -0.1596, +0.0840,
+ -0.4970, -0.2908, -0.3823, -0.8830, -0.0833, -0.4294, +0.3447,
+ +0.4591, -0.1768, -0.4054, -0.2783, +0.0228, +0.2754, -0.3646,
+ +0.3944, -0.0349, -0.1119, +0.0405, -0.7938, -0.1085, -0.1693,
+ +0.3024, -0.5234, +0.1899, +0.1598, -0.0956, -0.0660, +0.8926,
+ +0.0428, -0.1308, -0.9002, -0.1008, +0.0826, -0.0661, +0.2094,
+ -0.2457, +0.0941, -0.1031, +0.0496, -0.6188, +0.3200, +0.3472,
+ -0.1994, +0.0598, -0.6498, -0.3135, +0.1850, -0.3448, -0.5044,
+ -0.0509, -0.9147, +0.2559, +0.0753, +0.0753, +0.0294, -0.3612,
+ -0.0921, -1.4746, +0.4441, +0.3017, +0.1874, -0.4263, +0.4468,
+ +0.2712, +0.0128, -0.0261, +0.3705, -0.4319, -0.0988, -0.0705,
+ -0.4702, +0.1396, -0.3963, +0.0893, -0.2172, -1.2196, -0.6357,
+ -0.1207, +0.1123, -0.2076, -0.1591, -0.1512, -0.0582, -0.3533,
+ -0.5694, -0.2883, +0.2884, -0.0825, +0.0193, -0.2499, -0.5041,
+ +0.2356, -0.0106, +0.0655, +0.1411, +0.1246, -0.5655, +0.0270,
+ -0.5696, +0.1255, -0.0826, -0.0638, -0.5297, -0.9973, +0.2699,
+ -0.2058, -0.0949, -0.3804, -0.1981, +0.0273, -0.1266, +0.0663,
+ +0.2089, +0.1680, -0.1503, -0.1509, +0.1122, -0.7540, +0.2932,
+ -0.8315, -0.3090
+ ],
+ [
+ +0.1706, +0.0610, -0.5838, -0.0865, -0.0213, -0.2678, +0.0303,
+ +0.3113, -0.3995, +0.3783, -0.5923, +0.1832, +0.1734, +0.0254,
+ -0.3922, +0.3137, -0.3262, +0.0790, -0.0224, +0.0657, -0.0827,
+ -0.9136, +0.1583, -0.0134, +0.0211, -0.0033, +0.0590, +0.0649,
+ +0.0960, -0.3352, +0.0149, -0.8295, +0.2650, +0.2434, -0.0466,
+ +0.1953, -0.3053, -0.4421, +0.0103, -0.0617, -0.4838, -0.0559,
+ +0.1233, +0.0918, -0.3375, +0.0673, +0.1396, -0.4121, +0.0399,
+ +0.1877, -0.9721, +0.0536, -0.4329, -0.0968, -0.0310, -0.0441,
+ -0.1357, -0.2994, -0.1415, +0.3444, +0.0769, -0.1848, -0.8968,
+ +0.2653, +0.1815, -0.0268, +0.4176, -0.0595, +0.1591, -0.1656,
+ -0.0402, +0.0691, -0.7454, -0.3123, -0.4003, +0.0267, -0.0143,
+ +0.2760, +0.2060, -0.7292, -0.2153, +0.2515, -0.2929, +0.0335,
+ +0.0227, -0.4146, -0.1046, -0.0436, -0.3568, -0.0046, -0.1406,
+ -0.0310, +0.3112, -0.5021, -0.0665, +0.2722, -0.2953, -0.1284,
+ +0.4788, +0.0499, -0.1760, -0.5210, -0.4396, -0.0102, -0.1382,
+ +0.1617, -0.1325, -0.6286, -0.2559, +0.2053, +0.0603, +0.1821,
+ +0.0275, -0.4626, +0.0678, -0.1890, -0.0034, -0.2487, +0.1380,
+ -0.1140, -0.0490, -0.0591, +0.2868, +0.2875, -0.2210, +0.1894,
+ +0.1656, -0.2314
+ ],
+ [
+ +0.1326, +0.1445, -0.4052, -0.2978, +0.5537, +0.1333, +0.3951,
+ -0.2189, -0.2499, +0.1027, -0.1314, -0.2956, -0.4292, +0.1320,
+ -0.5522, -0.3736, -0.1077, -0.3843, -0.6754, -0.2406, +0.2837,
+ -0.7301, -0.1675, -0.2725, +0.0578, -0.6014, +0.2112, -0.0551,
+ -0.0484, -0.3406, -0.0537, -0.5426, -1.5375, +0.2983, +0.3546,
+ +0.1420, -0.0795, -0.4401, -0.4079, -0.3726, +0.3343, -0.2322,
+ -0.2032, +0.2038, -0.1928, -0.3805, +0.0599, +0.0578, +0.4813,
+ +0.2921, -0.1916, -0.0337, -0.2057, +0.1114, +0.0827, +0.1672,
+ -0.0961, -0.0529, -0.2337, +0.0616, +0.1257, -0.8919, +0.1716,
+ -0.1828, -0.3268, -0.1773, -0.3308, -0.8293, -0.8749, -0.4553,
+ -0.2627, -0.1717, +0.0148, +0.1005, -0.0882, +0.0134, -0.3633,
+ -0.1698, -0.3961, -0.0632, -0.8008, +0.0911, -0.5091, +0.0745,
+ +0.0184, -0.5566, +0.0934, -0.1507, -0.3232, +0.1291, -0.9442,
+ +0.3393, +0.1318, -0.0475, -0.6027, -0.4318, +0.0814, +0.0791,
+ -0.4565, -0.6858, -0.5338, -0.5991, +0.3650, +0.1171, -0.2716,
+ -0.1989, -0.6467, +0.3248, -0.0296, +0.1573, -0.8836, -0.1377,
+ -0.1053, -0.0780, -0.2601, -0.2829, -0.2949, -0.0864, -0.0371,
+ -0.1057, +0.2542, -0.0073, +0.0424, +0.2498, +0.0555, +0.4797,
+ -0.3376, -0.4506
+ ],
+ [
+ -0.0255, -0.1650, -0.2974, +0.0178, +0.0392, -0.0186, +0.1872,
+ +0.0655, -0.1296, +0.2720, -0.1809, +0.3607, -0.2829, -0.7414,
+ -0.0197, +0.4503, +0.1493, -0.0222, -0.6118, -0.1622, +0.4015,
+ -0.0279, +0.0294, -0.2557, +0.0963, +0.1893, +0.0614, -0.4798,
+ +0.0077, -0.0389, +0.2097, +0.0587, -0.0738, +0.2764, +0.4512,
+ +0.3174, -0.1535, -0.2276, -0.7275, -0.3815, -0.7228, +0.0201,
+ +0.1117, -0.0261, -0.2577, +0.0478, -0.1840, +0.3085, -0.1759,
+ -0.0425, -0.4142, +0.0371, -0.0894, +0.4119, +0.0659, -0.2694,
+ +0.1903, -0.8607, -0.6496, -0.0941, +0.2064, -0.0151, +0.5710,
+ +0.5431, +0.1864, -0.0135, -0.0710, -0.4110, -0.2441, -0.5753,
+ -0.4009, +0.2134, +0.2212, +0.2904, -0.2814, -0.3143, -0.5441,
+ +0.1319, -0.1148, -0.2074, +0.0995, -0.0569, -0.2905, -0.0324,
+ -0.4356, -0.3295, +0.1332, +0.0101, -0.1996, +0.3176, -0.6325,
+ +0.3636, -0.2449, -0.1157, +0.0073, -0.3086, -0.2715, -0.0547,
+ -0.2606, -0.1449, +0.2044, -0.0712, +0.2225, -0.2971, +0.1239,
+ -0.0524, -0.1557, -0.4880, +0.3417, -0.2688, +0.2402, -0.7468,
+ +0.1165, +0.0455, +0.0083, +0.0263, +0.1152, +0.4319, -0.2114,
+ +0.2163, -0.0243, +0.4918, +0.1440, +0.5037, -0.2096, -0.1679,
+ +0.1048, -0.0869
+ ],
+ [
+ +0.1235, +0.3844, -0.2685, -0.0345, +0.0650, +0.3062, -0.1378,
+ -0.2978, -0.2188, -0.0771, +0.2667, +0.0304, -0.0427, +0.5494,
+ -0.1444, -0.2129, +0.5117, -0.6419, +0.0324, -0.0905, -0.1562,
+ -0.4267, -0.0232, -0.5619, -0.5693, -0.5975, -0.4708, +0.0807,
+ -0.2655, -0.4244, -0.0705, -0.2516, -0.2843, -0.6295, -0.4559,
+ -0.1688, +0.0422, +0.6803, -0.4978, -0.2812, +0.0619, -0.4478,
+ +0.0157, -0.4996, -0.3075, -0.3749, +0.1362, +0.0591, -0.1556,
+ -0.4341, +0.6123, -0.0788, +0.7977, -0.3591, -0.9098, -0.1948,
+ -0.2681, -0.2196, +0.5037, +0.5002, -0.2051, -0.4643, +0.0398,
+ -0.5385, -0.1953, +0.0785, -0.6677, -0.1378, -0.9210, -0.4328,
+ -0.2015, -0.4793, -0.1423, +0.0203, +0.1207, -0.7935, -0.0970,
+ +0.0853, -0.6163, -0.0491, +0.4021, +0.1865, +0.4280, -0.0037,
+ -0.4592, -0.2485, +0.1351, -0.2844, -0.6598, +0.3015, +0.2235,
+ -0.9861, -0.3646, +0.3393, -0.3452, +0.3539, -0.5701, -0.4908,
+ +0.5699, -0.4017, -0.1102, -0.2180, +0.1905, +0.4240, -0.2312,
+ -0.2970, -0.4595, +0.2174, +0.1782, +0.0243, -0.0901, +0.4517,
+ -0.0867, +0.3470, -0.2287, -0.2463, -0.1592, -0.3746, -0.0036,
+ -0.3122, +0.1140, -0.4486, -0.8497, -0.1085, +0.9101, +0.2038,
+ -0.2062, -0.0823
+ ],
+ [
+ +0.2463, +0.5707, -0.4433, +0.2201, -0.0199, -0.6071, +0.2050,
+ +0.0493, -0.2200, -0.4677, +0.0629, +0.0493, -0.0842, +0.1211,
+ -0.3605, -0.0976, -0.7993, +0.0483, -0.1064, +0.2877, -0.6253,
+ -0.2183, -0.3741, +0.0682, -0.0970, +0.5666, -0.0419, -0.8218,
+ +0.1176, -1.4321, +0.0578, -0.1302, +0.1870, +0.3711, -0.5058,
+ +0.3670, -0.1283, -0.1262, +0.0613, -0.2924, -0.4785, -0.1313,
+ +0.1151, -0.1354, +0.3046, +0.1120, +0.0943, -0.5687, -0.6528,
+ -0.1993, -0.8543, -0.3318, +0.1341, -0.1301, +0.2574, +0.0046,
+ -0.1438, -0.0989, +0.0297, -0.1477, -0.0582, -0.2912, +0.1454,
+ +0.2671, -0.4703, -1.3141, -0.1180, +0.1261, +0.0528, +0.1643,
+ -0.4553, -0.0406, -0.4539, +0.0511, +0.1268, +0.2252, -0.0132,
+ +0.0196, +0.7711, -0.0122, +0.1204, -0.5035, -0.0164, -0.0501,
+ +0.4662, -0.2951, -0.1318, -0.1211, -0.2753, -0.0345, +0.0149,
+ -0.3875, -0.1881, -0.1405, +0.1532, +0.1554, -0.0673, -0.2962,
+ +0.1869, +0.2242, -0.5578, -0.0057, -0.3872, +0.1012, +0.1592,
+ -0.5527, -0.1771, +0.2545, +0.1549, -0.0110, -0.5167, +0.1115,
+ -0.0596, -0.5712, +0.3191, -0.3316, -0.0618, -0.7255, -0.0035,
+ -0.5352, -0.0360, +0.0610, -0.6326, -0.2177, -0.5042, -0.5355,
+ -0.1681, -0.1498
+ ],
+ [
+ +0.1926, -0.0685, +0.3304, -0.3787, +0.0300, -0.2676, +0.0136,
+ -0.3297, -0.1434, +0.2152, +0.1500, -0.0552, -0.3526, -0.0323,
+ +0.2272, -0.1979, -0.4169, -0.3634, -0.8873, -0.1784, +0.0721,
+ -0.5226, +0.1625, -0.5973, -0.2882, -0.2884, -0.0342, -0.7191,
+ -0.1038, +0.2307, -0.3793, -0.2169, -0.4917, +0.1231, -0.2788,
+ -0.0933, +0.0867, +0.1352, -1.5252, +0.3475, -0.2924, -0.6522,
+ -0.2583, -0.2580, +0.0162, -0.1497, -0.2728, -0.0223, -0.2669,
+ +0.1925, +0.3857, -0.3332, +0.1178, -0.5367, +0.0528, -0.0169,
+ -0.5829, -1.0664, -0.5824, -0.1038, +0.1126, -0.7621, -0.4332,
+ -0.0314, -0.1815, +0.1829, -0.6382, +0.1326, +0.0845, -0.4755,
+ -0.2206, -0.3449, +0.0764, -0.0900, -0.5230, -0.0539, -0.4122,
+ -0.7988, -0.1538, +0.2325, +0.1030, -0.1607, +0.0113, -0.1478,
+ +0.2353, +0.1148, -0.0807, -0.1881, -0.4861, -0.2848, +0.2721,
+ -0.7730, -0.4613, +0.6028, +0.2487, -0.1225, -0.2896, -0.2808,
+ -0.1185, -0.7210, +0.0897, +0.1085, +0.3445, -0.1611, -0.0695,
+ +0.2044, -0.1024, -0.2478, -0.0785, +0.3137, +0.5408, -0.3994,
+ -0.4764, -0.2766, +0.2133, +0.1204, -0.9959, +0.3333, +0.1227,
+ +0.2426, -0.4202, -0.3578, -0.1248, -0.1090, -0.2104, -0.3860,
+ +0.2306, -0.0728
+ ],
+ [
+ -0.3248, +0.0159, -0.0667, -0.0756, -0.0663, +0.3394, -0.2182,
+ -0.2663, -0.1528, +0.1880, -0.5628, +0.2296, -0.0234, -0.0294,
+ -0.2945, +0.1946, -0.3773, -0.0458, -0.3226, -0.4340, -0.0176,
+ +0.3101, +0.1491, +0.3488, +0.3136, +0.1758, +0.3119, +0.4763,
+ +0.1465, -0.0397, -0.3957, -0.3768, +0.1163, -0.4517, +0.3269,
+ -0.0506, +0.2071, -0.3858, +0.4534, -0.2441, +0.5120, -0.5391,
+ -0.2332, -0.6894, -0.0485, -0.2305, -0.0612, +0.1359, +0.0151,
+ -0.3765, +0.3468, -0.3807, +0.5106, -0.2714, -0.7264, -0.8902,
+ -0.3425, -0.1253, -1.0046, +0.2819, +0.0902, +0.2295, +0.2070,
+ -0.6132, -0.0471, +0.1733, -1.1173, -0.4534, +0.5652, -0.0742,
+ +0.1592, -0.1147, -1.0578, -0.7389, +0.1167, -0.3078, -0.0317,
+ -0.1373, -1.1162, -0.1009, -0.4260, -0.0209, -0.6846, -0.2091,
+ +0.4688, +0.1684, +0.5514, -0.1581, -0.4061, -0.2237, +0.1754,
+ -0.4694, +0.0851, -0.6308, -0.2750, -0.3957, -0.5867, +0.2913,
+ -0.4755, -0.2140, -0.3601, +0.3739, -1.1790, -0.0693, -0.2330,
+ -0.5800, -0.1498, -0.5219, -0.1689, +0.1537, -0.1052, +0.6002,
+ +0.0727, -0.2849, -0.4114, -0.0390, -0.0276, -0.2993, -0.0610,
+ -0.1966, -0.0580, +0.2800, -0.0033, +0.4452, +0.2182, -0.9645,
+ +0.0513, +0.0884
+ ],
+ [
+ -0.3226, +0.1336, +0.6645, -0.4503, -0.1672, -0.0602, -0.5145,
+ -0.2136, -0.2340, +0.2906, -0.0673, -0.1477, +0.2186, +0.1079,
+ +0.0486, +0.2164, -0.5336, -0.1297, -0.0875, +0.2970, -0.3045,
+ +0.4400, +0.5784, -0.4019, -0.3110, -0.9414, -0.3346, +0.2523,
+ -0.0274, -0.4475, -0.2102, +0.0897, +0.0419, +0.0503, +0.1835,
+ -0.0535, +0.0689, +0.0691, -0.1349, -0.6753, +0.3090, -0.5637,
+ +0.0200, +0.3919, -0.2876, -0.3861, +0.2904, +0.2580, +0.1847,
+ -0.4541, +0.2357, -0.0827, -0.9218, -0.0946, -0.1218, -0.1566,
+ -0.0611, -0.1368, -0.1764, -0.5379, -0.0988, +0.0806, -0.4375,
+ -0.0130, -0.1357, -0.0778, -0.7153, +0.0455, -0.4599, -0.4328,
+ +0.1127, -0.3466, +0.2376, -0.0922, -0.4810, +0.3056, -0.7828,
+ +0.0528, -0.1335, +0.5371, -0.2253, +0.1008, -0.3593, -0.4297,
+ -0.0838, -0.2490, -0.2259, -0.1838, -0.0699, -0.2224, -0.2921,
+ -0.1630, +0.0722, -0.1825, -0.8208, -0.1545, +0.6346, +0.0748,
+ +0.0044, -0.4955, -0.1173, +0.2172, -0.0944, -0.7999, -0.5529,
+ -0.1711, +0.1271, +0.0247, -0.5756, -0.4206, -0.3636, -0.4627,
+ +0.2299, +0.0614, -1.0937, -0.5468, +0.0510, -0.7410, -0.8884,
+ +0.3174, -0.4159, -0.4072, -0.8816, -0.1527, -0.1486, +0.3125,
+ -0.2283, +0.2177
+ ],
+ [
+ +0.0039, +0.0103, -0.1755, -0.7996, -0.0968, +0.0277, +0.1732,
+ -0.3424, -1.4968, -0.1753, -0.0114, +0.2941, +0.1342, +0.2813,
+ -1.7341, -0.5349, +0.0842, +0.3819, -0.5440, +0.0967, +0.0900,
+ -1.4831, +0.3267, -0.0945, +0.1357, -0.3697, -0.1469, -0.4575,
+ +0.1818, -0.6642, -0.0056, -0.1976, +0.0797, -0.1708, +0.1934,
+ +0.2915, -0.1422, -0.0404, -0.2522, +0.0745, -0.5222, +0.1857,
+ -0.1054, -0.4258, -0.1111, -0.3788, -0.0603, -0.3986, -0.5091,
+ -0.0344, +0.3817, +0.2383, -0.1576, +0.2485, +0.3856, +0.0202,
+ +0.0191, -0.5266, -0.1806, -0.1136, +0.1925, -0.5746, -0.9777,
+ -0.3512, -0.0246, +0.0901, -0.5217, -0.0677, +0.0909, +0.2601,
+ +0.9345, -0.3394, -0.0119, -0.0092, -0.4497, +0.3786, +0.0784,
+ +0.0421, +0.0792, -0.3989, -0.0075, -0.0954, +0.1185, -0.1363,
+ +0.0989, -0.1078, +0.1155, -0.0391, -0.1252, -0.2695, -0.0459,
+ -0.2948, -0.3355, -0.5704, -0.0559, -0.2500, +0.4076, +0.0663,
+ +0.2311, -0.0617, -0.0548, -0.0475, +0.4303, -0.0794, -0.2073,
+ -0.7073, -0.0176, -0.0955, -0.0993, -0.5084, +0.0248, -0.0866,
+ -0.8128, +0.0065, -0.0581, +0.3117, +0.0263, -0.1558, -0.0008,
+ +0.2365, -1.1693, +0.4167, -0.1065, +0.4104, -0.2010, +0.0968,
+ +0.0552, -0.0371
+ ],
+ [
+ +0.2534, -0.0501, -0.2594, +0.1478, -0.7236, +0.2802, +0.0805,
+ -0.1607, +0.2090, +0.1263, +0.1884, -0.1083, -0.4125, -0.3225,
+ +0.1190, -0.2326, -0.2595, -0.2029, -0.3719, +0.0625, -0.1373,
+ +0.2389, +0.3014, +0.0892, +0.3054, -0.2101, +0.0070, +0.1154,
+ -0.0347, -0.1208, +0.0531, +0.1513, +0.2507, -0.0510, -0.1456,
+ +0.0580, +0.0154, +0.1996, -0.0832, +0.1442, +0.0221, -0.0928,
+ +0.0884, +0.1552, +0.0532, -0.7460, -0.2394, +0.0967, +0.1723,
+ -0.2659, +0.2287, -0.0556, +0.2908, +0.4469, -0.1458, +0.1577,
+ -0.2041, -0.0583, +0.3994, +0.5170, -0.7670, +0.3433, -0.0383,
+ -0.0670, -0.3647, -0.1440, -0.2584, +0.4074, +0.3214, -0.1794,
+ +0.3010, -0.2413, +0.0558, -0.5349, -0.5052, +0.0807, +0.0558,
+ -0.4087, +0.1186, -0.3845, +0.1390, +0.0359, +0.2994, -0.2928,
+ -0.0573, -0.1539, -0.2161, -0.0756, -0.1941, -0.3361, -0.4123,
+ +0.1537, -0.0709, +0.2274, -0.5642, -0.2887, -0.4241, +0.3842,
+ +0.3369, +0.1526, +0.1065, -0.2747, -0.1502, +0.0964, -0.0100,
+ -0.0807, -0.6731, -0.7413, -0.1946, -0.4019, -0.3018, +0.0907,
+ -0.0809, -0.3277, +0.2652, +0.0611, +0.0838, -0.1097, -0.6041,
+ +0.1028, +0.1933, -0.2961, -0.0032, +0.0196, +0.0418, -0.0965,
+ +0.3258, +0.0426
+ ],
+ [
+ -0.6308, -0.0501, -0.0838, -0.1519, +0.3868, +0.0165, -0.0647,
+ +0.2359, -0.7684, +0.2470, -0.1684, +0.0552, -0.0439, -0.5137,
+ -0.0342, -0.1471, -0.2033, +0.0010, +0.5120, +0.2452, -0.3707,
+ -0.4031, +0.1284, -0.0031, +0.2168, -0.2880, -0.1485, -0.0316,
+ +0.1138, -0.0230, -0.3823, -0.2558, +0.2216, -0.8283, +0.1104,
+ +0.2202, +0.1233, -0.5009, -0.3594, -1.0594, +0.1320, -0.1490,
+ +0.0831, +0.6580, -0.2022, -0.3214, -0.0493, -0.4918, -0.1414,
+ -0.3596, -1.2959, +0.0334, -0.0096, -0.0637, +0.1090, +0.2714,
+ +0.2888, -0.4400, -0.9489, +0.0081, -0.0942, +0.1463, -0.1739,
+ -0.6975, +0.2816, -0.8516, -0.3003, +0.1234, +0.3339, -0.1227,
+ -0.2146, -0.7996, -0.2116, -0.0534, -0.3831, +0.1300, -0.6559,
+ -0.2496, -0.3875, -0.6497, -0.4172, +0.1083, +0.3429, +0.1460,
+ -0.6197, +0.0890, +0.4016, -0.0499, +0.0776, -0.1099, +0.4072,
+ +0.1516, -1.1238, +0.1015, +0.0881, +0.2689, +0.4516, -0.1882,
+ +0.1791, +0.7761, +0.2232, +0.0939, -0.3682, -0.1288, +0.0489,
+ -0.2183, -0.2398, +0.0578, -0.5142, -0.1569, +0.2860, +0.3591,
+ +0.3800, -0.3455, +0.1576, +0.2144, -0.8416, -0.0603, +0.1336,
+ +0.2087, -0.6990, -0.1888, +0.5619, -0.2315, +0.1561, +0.1132,
+ -0.7656, -0.3181
+ ],
+ [
+ -0.1286, +0.1858, -0.2411, +0.0090, -0.3402, -0.2936, +0.1051,
+ +0.1919, -0.2531, +0.4690, -0.6679, +0.3317, +0.2073, -1.1532,
+ -0.7191, +0.0884, -0.0799, +0.2003, -0.1593, -0.1969, -0.2554,
+ -0.2080, -0.2559, +0.3545, -0.8480, +0.4528, -0.2133, -0.4219,
+ -0.4413, +0.1131, -0.0602, -0.1928, +0.0279, +0.1352, -0.2555,
+ +0.2333, -0.2460, +0.0057, -0.8220, -0.0760, +0.0504, -0.9094,
+ -0.6114, +0.1768, +0.0091, -0.0628, -0.1880, -0.2029, +0.2462,
+ +0.1165, +0.2070, -0.1164, -0.1690, +0.1759, -0.1980, -0.2017,
+ -0.2359, -0.5043, -0.7476, -0.3844, -0.1492, -0.5376, +0.2582,
+ +0.3424, -0.1346, -0.1681, -0.4327, +0.0905, -0.2482, +0.1685,
+ +0.3307, +0.1385, -0.2317, +0.2284, -0.6566, +0.2268, -0.1018,
+ -0.2626, -0.0549, -0.3204, -0.1904, -0.0743, -0.8110, +0.2222,
+ -0.0741, -0.0935, +0.1553, +0.1289, -0.1035, -0.0720, +0.4058,
+ -0.3011, +0.0458, +0.2255, -0.6481, +0.0250, +0.1870, +0.1039,
+ +0.1931, +0.1419, -0.7905, +0.0222, +0.2000, -0.1245, +0.2453,
+ -0.4877, +0.2176, +0.2230, -0.5876, -0.0292, +0.0748, -0.3372,
+ -0.0874, +0.0585, +0.4317, -0.0294, +0.3862, +0.3095, -0.2184,
+ -0.5214, +0.3847, +0.0584, +0.3308, +0.0771, -0.0182, +0.1068,
+ +0.0827, -0.3393
+ ],
+ [
+ -0.0223, +0.2438, -0.0411, -0.3990, +0.4767, -0.4751, +0.2604,
+ +0.2775, +0.0951, +0.3999, -0.0248, -0.0078, -0.0592, -0.4420,
+ +0.0711, +0.2006, -0.0424, +0.4881, -0.0616, -0.3197, -0.2655,
+ -0.3899, +0.2844, -0.0932, -0.3590, +0.0607, +0.1592, -0.0413,
+ +0.2932, +0.0039, +0.3933, +0.3092, -0.4648, +0.3378, -0.1120,
+ +0.0148, +0.2869, +0.0393, -0.3506, +0.2658, +0.1252, +0.1600,
+ -0.2529, -0.1268, +0.3310, -0.0902, +0.2594, -0.1768, -0.0035,
+ -0.4478, +0.1509, -0.0057, +0.1382, -0.0739, -0.0245, -0.1634,
+ -0.1252, +0.0223, -0.5591, -0.0023, -0.0707, -0.2333, -0.3290,
+ -0.0214, +0.0871, -0.0567, -0.3501, -0.0693, -0.1038, -0.4635,
+ +0.0217, -0.3380, +0.2432, +0.1398, -0.2903, +0.0658, +0.0269,
+ +0.0889, +0.2137, -0.1885, -0.0677, +0.2808, +0.0891, +0.0853,
+ +0.1616, +0.3423, +0.2141, +0.0873, +0.0890, +0.0168, +0.0364,
+ +0.0070, -0.3678, +0.1200, +0.1389, +0.1118, +0.2462, +0.0112,
+ +0.0536, -0.3833, +0.1149, -0.3142, +0.3757, -0.2268, +0.5505,
+ -0.4528, +0.1183, -0.4295, -0.2305, -0.2820, +0.2610, -0.5187,
+ -0.3496, -0.0884, +0.1280, -0.1898, +0.2082, +0.2891, -0.1266,
+ +0.0223, -0.2194, +0.0958, +0.3503, +0.1008, -0.0299, +0.1613,
+ +0.1108, +0.2884
+ ],
+ [
+ -0.2112, +0.2139, +0.2353, -1.3735, +0.3379, -0.3306, -0.5791,
+ +0.2142, +0.1661, -0.2046, -0.4202, -0.5208, -0.4747, -0.3524,
+ -0.1866, +0.2010, +0.3635, -0.3221, -0.3282, +0.1993, -0.1151,
+ -0.4721, +0.0627, -0.2138, -0.3382, +0.2179, +0.1286, +0.0916,
+ -0.2135, +0.1114, +0.1641, -0.7235, +0.0271, -0.3165, -0.4372,
+ -0.0611, +0.0824, -0.1537, +0.3468, -0.3766, -0.0373, +0.0722,
+ +0.0230, -0.7669, -0.7521, +0.4481, +0.1352, -0.0385, -0.0233,
+ -0.3938, -0.1916, +0.1151, +0.2809, -0.0007, -0.0378, +0.0906,
+ +0.2414, -0.9108, -0.2856, -0.1401, -0.6404, -0.7260, -0.2588,
+ +0.1096, -0.1461, +0.0196, -0.9551, -0.5937, -0.0863, -0.1227,
+ -0.9528, -0.1206, -0.0116, -0.3274, +0.3520, +0.0632, -0.1109,
+ -0.3264, -0.8242, +0.2668, -0.0588, -0.2727, -1.1266, -0.9705,
+ +0.2631, -0.2931, -0.7791, -0.9120, +0.2401, +0.0197, -0.0931,
+ -0.5968, +0.5901, +0.1350, +0.0918, -0.5455, -0.6439, +0.4476,
+ +0.2893, -0.5928, +0.0521, -0.3101, -0.0489, +0.0052, -0.3169,
+ -0.4701, -0.6680, -0.0638, +0.1298, -0.4204, -0.0254, +0.1195,
+ -0.0933, -0.1896, +0.0503, -0.7819, +0.1228, +0.0729, -0.0561,
+ -0.0014, -0.0664, +0.2052, -0.7386, +0.4056, -0.0660, -0.9663,
+ -0.2771, -0.5232
+ ],
+ [
+ -0.1246, -0.2805, -0.3576, +0.2033, +0.1179, +0.0137, -0.6560,
+ -0.2292, -0.5633, -0.0186, -0.2827, +0.1622, +0.1316, -0.4703,
+ -0.7199, +0.2989, +0.1364, -0.1050, +0.4184, -0.0721, -0.1984,
+ -0.8043, +0.1757, +0.1660, +0.1198, -0.6675, -0.1686, -0.0080,
+ -0.0535, -0.2755, -0.0087, -0.0772, -0.1946, -0.1625, +0.2803,
+ -0.4290, +0.3188, -0.5116, +0.3810, -0.4627, -0.3474, -0.0296,
+ -0.0126, -0.5452, -0.1713, +0.0726, +0.1517, -0.3349, +0.2804,
+ -0.4211, -0.3698, -0.0776, +0.5157, -0.0116, -0.1578, -0.2274,
+ -0.5434, -0.7078, -0.1557, +0.1799, -1.7247, +0.0598, -0.2763,
+ -0.2002, -0.1513, +0.0315, +0.1172, -0.5970, -0.4829, -0.1757,
+ -0.6510, -0.2016, +0.0722, -0.2784, +0.2477, -0.1084, +0.3574,
+ +0.2216, -0.2019, -0.0929, -0.2401, -0.0009, +0.0100, +0.3262,
+ +0.1323, -0.3393, +0.0441, +0.0237, -0.1123, -0.3906, +0.1925,
+ +0.2541, +0.0079, -0.3655, +0.1809, +0.0290, -0.2198, +0.2628,
+ -0.1835, +0.1061, +0.2996, +0.5976, -0.0171, -0.0882, +0.0488,
+ +0.0209, -0.4426, -0.1461, -0.7127, +0.0345, -0.0908, -0.0087,
+ -0.6902, +0.0474, +0.3433, +0.2376, +0.0280, +0.1350, -0.6906,
+ -0.1005, -0.3456, -0.4074, -0.3707, -0.4556, +0.1230, +0.1421,
+ -0.1536, +0.4549
+ ],
+ [
+ +0.4253, -0.1862, -0.2521, +0.0973, +0.2793, -0.0849, -0.1390,
+ +0.2692, +0.2426, +0.1690, -0.0772, -0.0276, +0.1998, +0.0185,
+ -0.1736, -0.0510, -0.1957, +0.2297, +0.2222, -0.0429, -0.1558,
+ -0.9350, +0.1733, +0.2294, +0.2759, -0.1063, -0.6416, -0.2152,
+ +0.0899, -0.4758, -0.0466, +0.0209, +0.0777, -0.6026, +0.1939,
+ -0.1837, +0.1779, +0.1248, -0.1254, -0.2091, -0.1979, +0.4873,
+ +0.1698, +0.0795, -0.1283, +0.0153, -0.4910, +0.3692, -0.0166,
+ +0.0893, -0.3555, -1.2133, -0.3912, -0.3162, +0.1056, +0.3104,
+ -0.0164, +0.4362, -0.1710, -0.5106, -0.0164, +0.3129, -0.7867,
+ +0.1497, +0.0967, -0.0521, +0.1755, -0.1235, +0.1731, +0.2002,
+ +0.2755, -0.0072, +0.2876, +0.2190, +0.0101, +0.1913, -0.3036,
+ +0.3041, +0.2350, +0.3212, +0.1128, +0.1641, -0.5767, +0.1855,
+ +0.0141, +0.2336, -0.1784, -0.2715, +0.0631, -0.1110, +0.2796,
+ +0.1881, +0.2210, +0.4339, +0.1268, -0.1757, +0.1511, +0.0015,
+ -0.0059, +0.0019, +0.2075, +0.1971, +0.1113, +0.0985, +0.0434,
+ -0.2494, +0.2593, +0.0467, -0.5946, -0.2618, -0.1521, -0.2028,
+ +0.2417, -0.6486, -0.1829, +0.0708, -0.1101, +0.1115, +0.0227,
+ +0.1591, -0.4037, -0.0098, +0.0621, -0.4142, -0.1739, +0.4112,
+ +0.3607, -0.5380
+ ],
+ [
+ +0.1177, -0.0829, -0.2037, -0.2156, +0.1920, +0.1360, -0.1985,
+ -0.0925, -0.5613, -0.2878, -0.1383, -0.1178, +0.2660, -0.2264,
+ -0.3758, +0.0474, +0.0023, +0.1017, -0.4475, -0.0988, +0.2955,
+ -0.4085, -0.2192, +0.1311, -0.3999, -0.3496, -0.1175, -0.4424,
+ -0.4607, -0.0673, -0.1690, -0.2330, -0.3726, -0.0566, -0.3821,
+ +0.0028, +0.1176, +0.1637, -0.3063, -0.2605, +0.4228, +0.5291,
+ +0.0629, +0.5256, -0.3477, +0.4640, +0.0645, -0.5641, -0.2468,
+ +0.2339, +0.1751, +0.0718, +0.3500, -0.4988, -0.1264, -0.0177,
+ +0.1769, -0.0400, -0.2931, -0.0032, +0.3511, +0.2182, -0.4131,
+ -0.6258, -0.2432, -0.0031, -0.4084, -0.1694, -0.1345, -0.0997,
+ -0.2085, -0.1604, +0.3349, +0.2521, +0.1971, -0.1442, +0.2636,
+ -0.1359, -0.0244, -0.5738, +0.1898, -0.0964, +0.3351, +0.1642,
+ +0.1135, -0.3388, -0.1054, -0.0207, +0.0978, +0.0311, +0.0011,
+ -0.0103, -0.3878, -0.1310, +0.1785, +0.0105, +0.0070, -0.2280,
+ +0.1466, +0.1476, -0.0045, -0.4846, +0.3915, -0.2372, -0.0766,
+ -0.4503, -0.1964, +0.1785, +0.1047, +0.8291, +0.1383, +0.1750,
+ +0.2304, +0.1486, +0.1168, -0.0636, +0.0268, -0.0029, +0.1824,
+ -0.4461, +0.2138, +0.0789, +0.2332, +0.3060, -0.2309, -0.1640,
+ -0.2015, +0.0814
+ ],
+ [
+ -0.2089, +0.1014, -0.0579, +0.3885, -0.0160, +0.3301, -0.4470,
+ +0.4714, -0.1930, -0.4235, -0.0122, -0.5872, +0.3336, +0.0962,
+ +0.1576, +0.0089, +0.0542, -0.1455, -0.1269, +0.1636, -0.1596,
+ -0.1467, -0.0751, -0.3372, -0.0210, -0.3890, +0.2495, -0.5069,
+ +0.2558, +0.2504, -0.0504, -0.1370, -0.1636, +0.1638, -0.4274,
+ -0.4883, +0.1807, -0.3299, -0.2602, -0.1714, +0.3408, +0.1558,
+ +0.3440, -0.2063, +0.3495, -0.0942, -0.1896, +0.1604, +0.2981,
+ +0.0938, +0.3079, -0.0422, +0.2457, -0.0888, -0.1330, +0.3858,
+ +0.1828, +0.2261, +0.0589, +0.0212, +0.2386, -0.2637, -0.1125,
+ -0.6084, -0.1772, +0.1757, -0.0477, -0.4429, -0.5084, -0.0512,
+ -0.0579, +0.2526, +0.2676, -0.3652, +0.0563, +0.1303, +0.1980,
+ -0.1137, -0.1055, +0.1332, +0.2540, -0.0726, -0.2244, +0.1358,
+ +0.1327, -0.5314, -0.5776, +0.0586, +0.4645, -0.5067, +0.2115,
+ -0.8910, -0.0485, -0.2118, +0.0909, +0.4667, +0.1512, -0.4808,
+ +0.0252, -0.1659, +0.2356, -0.1116, +0.0382, +0.0931, +0.1761,
+ +0.0300, -0.3396, -0.1821, +0.1245, -0.1004, -0.1907, +0.1104,
+ -0.0528, -0.1555, -0.0645, +0.0562, -0.2227, +0.3703, -0.2504,
+ -0.1985, -0.2180, -0.1775, +0.2405, -0.0889, +0.1268, +0.3380,
+ -0.3181, +0.3610
+ ],
+ [
+ -0.1952, -0.0578, -1.1057, +0.5134, -0.1378, +0.2639, -0.1665,
+ -0.3419, -0.1661, +0.1025, -0.0394, -0.0055, -0.3502, +0.3829,
+ +0.0351, -0.8268, -0.4556, +0.1120, -0.0705, +0.2972, -0.4725,
+ +0.0838, +0.3422, -0.5389, -0.2642, -0.2428, -0.4464, -0.1878,
+ +0.3799, +0.0833, -0.3188, +0.1659, -0.5127, -0.1637, -0.5105,
+ -0.3803, +0.1553, +0.1436, -0.2048, -0.0348, +0.1922, -0.2446,
+ -0.6350, -0.6326, +0.3759, -0.8518, -0.2066, -0.3527, -0.9225,
+ +0.5922, +0.1130, -0.6997, +0.0371, +0.1281, +0.0358, -0.3420,
+ +0.0422, -0.1585, +0.0060, -0.2306, +0.0093, +0.3616, +0.1565,
+ -0.4825, -0.2306, -0.6262, +0.0261, +0.1737, -0.8466, +0.1037,
+ +0.1481, -0.1724, -0.0477, -0.2328, -0.7668, +0.0539, -0.0205,
+ -0.1615, +0.1709, +0.1200, +0.0062, -0.1006, -0.0631, -0.6605,
+ +0.3073, +0.0534, -0.1759, -0.0048, +0.3530, -0.0488, -0.3439,
+ +0.6192, -1.0127, -0.4404, -0.1655, +0.2329, +0.1701, -0.0102,
+ -0.6998, -0.5205, -0.3661, -0.3588, -0.0991, -0.0539, -0.1724,
+ -0.0598, +0.0298, -0.5078, -0.2480, +0.2300, -0.0248, -0.8744,
+ +0.1165, -0.3571, -0.2669, -0.3494, +0.1781, +0.3223, -0.0251,
+ +0.1327, +0.5895, +0.4107, -0.1365, -0.4952, -0.2869, +0.1122,
+ +0.2460, +0.4473
+ ],
+ [
+ +0.1338, -0.0063, -0.2522, -0.1941, +0.2738, -0.2233, -0.2280,
+ +0.2611, -0.0943, -0.3515, -0.0844, +0.2064, -0.0363, -0.3102,
+ -0.3898, +0.0770, +0.2784, -0.1512, -0.1478, -0.0007, -0.1822,
+ -0.2255, -0.5550, +0.2976, +0.2547, +0.0151, +0.0828, -0.0848,
+ -0.2138, -0.0103, -0.8352, +0.1319, -0.2303, -0.2299, -0.0563,
+ -0.3885, +0.0342, -0.4977, -1.2963, +0.2561, -1.1328, +0.0012,
+ +0.2306, -0.5411, -0.3006, +0.0676, -1.9030, -0.3075, -0.0979,
+ +0.0896, -0.0580, -0.0038, +0.1381, +0.0090, +0.1478, -0.3079,
+ +0.2841, -0.1863, -0.6163, -0.1751, -0.5646, +0.4300, +0.0704,
+ -0.0387, -0.2823, +0.2259, -0.0953, -0.2159, -0.2969, -0.3502,
+ -0.3141, -0.1517, +0.0782, +0.0999, +0.5229, -0.1531, -0.2047,
+ -0.1471, +0.2247, -0.2625, +0.0019, -0.1073, -0.0022, -0.4420,
+ +0.0517, -0.0580, -0.6427, -0.2424, +0.1411, -0.0678, -0.1120,
+ -0.8540, -0.2692, +0.2238, -0.2368, -0.9063, +0.2976, +0.0414,
+ +0.1095, +0.2244, +0.0210, -0.1006, -0.2540, -0.1564, -0.0956,
+ -0.1224, -0.5763, +0.2323, -0.1224, +0.2074, -0.5607, -0.5861,
+ -0.0902, +0.1296, +0.1034, -0.2310, -0.2814, -0.1924, +0.1452,
+ -0.5430, -0.0619, -0.4562, +0.2069, +0.2684, -0.2071, -0.7354,
+ -0.2258, -0.1395
+ ],
+ [
+ -0.1963, -0.0107, -0.0423, +0.0007, +0.3431, +0.3000, -0.2971,
+ +0.3827, -0.2744, -0.6258, -0.7529, -0.2262, -0.0908, +0.7792,
+ -1.4345, -0.7595, -0.0323, -0.4281, -0.0325, +0.0773, -0.4141,
+ +0.1006, +0.5800, +0.4668, +0.3735, -0.3455, -0.2889, -0.2550,
+ +0.2045, -0.2958, -0.0868, -0.0470, -0.2008, +0.1274, +0.0259,
+ +0.1598, -0.2579, -0.5582, -0.0712, +0.2501, -0.4543, +0.1671,
+ -0.0398, -0.3789, -0.6567, +0.3653, -0.5175, -0.0741, -0.1428,
+ -0.9625, -0.1969, +0.3227, -0.7710, -0.2489, +0.0553, +0.1062,
+ +0.2338, -0.8710, -0.2630, +0.1344, +0.2044, -0.1054, -0.3221,
+ -0.7012, -0.1819, -0.1221, -0.0658, -0.0748, -0.3830, +0.3178,
+ +0.6506, -0.3111, -0.4665, +0.2741, -0.2561, +0.2261, -0.4738,
+ -0.0788, +0.0114, -0.5013, -0.6076, -0.4491, -0.4184, +0.6562,
+ +0.3299, -0.1993, +0.3129, -0.6395, -0.0735, -0.5297, +0.0319,
+ +0.4652, +0.6208, +0.0026, -0.1381, -0.5193, +0.0792, +0.5061,
+ -0.5610, +0.5022, -0.1293, -0.0424, -0.2379, -0.2926, -0.4384,
+ -0.4252, -0.6475, +0.4550, -0.1399, -0.3108, -0.6347, +0.2680,
+ +0.6766, +0.5618, +0.0904, -0.0573, -0.3292, +0.1988, -0.2317,
+ +0.3934, -0.3043, -0.1623, -0.4827, -0.1761, -0.1059, +0.0525,
+ -0.0313, -0.1475
+ ],
+ [
+ -0.0720, -0.0474, -0.0168, +0.1428, -0.1180, -0.3548, +0.4974,
+ -0.7262, -0.2118, +0.1000, -0.0795, -0.2894, -0.0655, -0.0423,
+ -0.1659, +0.1347, +0.0860, -0.2163, -0.5078, -0.2881, +0.1382,
+ -0.4808, +0.0168, +0.3667, -0.3162, -0.3973, -0.1601, -0.2069,
+ -0.1248, +0.2609, +0.0856, +0.0030, +0.1974, +0.3896, +0.0707,
+ -0.1730, -0.1112, +0.2419, -0.1894, -0.1437, +0.0670, -0.2615,
+ -0.3430, +0.1329, -0.0827, -0.8066, -0.0254, +0.1680, +0.2338,
+ -0.9633, +0.1481, -0.1104, +0.1121, +0.2071, +0.2378, +0.1063,
+ -0.1278, -0.1192, +0.2428, +0.2460, -0.0064, +0.0025, +0.4307,
+ +0.4768, -0.8693, +0.2835, -0.2696, +0.0314, -0.0276, -0.1222,
+ +0.2166, +0.2363, -0.2178, +0.3113, -0.8229, -0.2482, -0.4106,
+ +0.1824, -0.0883, +0.0695, -1.2673, -0.3113, +0.1158, +0.2840,
+ +0.1894, -0.7726, +0.3572, +0.0157, +0.0035, -0.2735, +0.2097,
+ -0.6630, +0.0192, +0.0644, -0.1819, -0.0937, -0.2322, +0.3941,
+ -0.1772, +0.0560, +0.0390, -0.4749, +0.0099, -0.3858, -0.1375,
+ -0.0988, -0.6115, -0.1879, -0.1092, +0.0315, +0.2415, -0.2787,
+ -0.0006, -0.0118, +0.2440, -0.0432, -0.1334, -0.1346, -0.4602,
+ +0.1854, +0.1047, -0.0036, -0.2341, -0.1576, +0.0653, +0.1567,
+ +0.1526, +0.1044
+ ],
+ [
+ +0.1769, -0.1034, -0.1948, -0.1274, -0.1648, +0.5893, -0.0946,
+ -0.2004, -0.2721, -0.3387, +0.3898, -0.3109, +0.1371, +0.1680,
+ -0.7257, +0.1351, -0.6586, +0.2851, +0.1728, +0.1130, -0.0131,
+ -0.4239, +0.1692, +0.1324, -0.3443, +0.2481, +0.1447, -0.3541,
+ +0.1374, +0.0410, -0.1387, +0.1571, +0.1503, -0.0262, -0.0774,
+ -0.1869, -0.0378, +0.2104, +0.0172, -0.1452, -0.4186, +0.2158,
+ +0.2101, +0.2539, +0.3134, -0.0346, -0.0244, -0.2532, -0.1317,
+ -0.0540, +0.0459, -0.1373, +0.1366, -0.0571, +0.1385, +0.1867,
+ -0.1449, -0.1944, +0.3466, +0.0981, -0.1643, +0.0219, -0.0246,
+ -0.3430, +0.0084, -0.6418, +0.1014, +0.0666, +0.2488, -0.2650,
+ -0.1532, -0.2495, +0.0428, -0.4240, -0.2821, -0.0754, +0.2721,
+ +0.4462, -0.8370, -0.0485, +0.1678, -0.2672, +0.3932, -0.1626,
+ +0.1755, -0.5960, -0.0072, +0.6288, +0.0466, -0.0260, -1.0479,
+ -0.5837, -0.1394, +0.0547, +0.1121, -0.6113, -0.5292, -0.6037,
+ -0.2560, +0.2865, -0.2272, -0.2464, +0.1547, -0.0282, -0.8408,
+ +0.3033, +0.1790, -0.1641, -0.3059, +0.1309, -0.3210, -0.0627,
+ +0.2607, -0.0373, +0.0129, -0.2009, -0.3511, -0.1189, -0.2208,
+ -0.0538, +0.0637, +0.1723, -0.5148, +0.2267, +0.1132, +0.0045,
+ -0.1421, +0.1912
+ ],
+ [
+ +0.0906, -0.1130, -0.2077, +0.1502, +0.3574, -0.4087, -0.1618,
+ -0.1510, +0.2428, -0.3561, -0.3971, -0.2274, -0.1077, +0.2071,
+ +0.5784, +0.3420, +0.2530, -0.1951, -0.1346, +0.2660, -0.0259,
+ +0.0771, -0.0849, +0.3132, -0.0404, -0.1513, -0.0255, +0.1137,
+ +0.3354, -0.1369, -0.1115, -0.1645, +0.1585, -0.2722, +0.4510,
+ -0.0847, -0.0087, -0.1398, +0.0353, -0.0701, -0.4510, -0.8897,
+ +0.0337, -0.0026, +0.1252, +0.0948, +0.2133, +0.2421, -0.2473,
+ +0.2771, +0.3732, -0.0731, -0.4412, -0.0749, +0.1336, -0.0273,
+ +0.1484, -0.3783, +0.1017, +0.0390, -0.5518, +0.0037, -0.6220,
+ +0.2184, +0.3016, +0.0485, +0.1901, +0.2104, +0.1166, -0.1032,
+ +0.3395, -0.0177, -0.3512, +0.1229, +0.0400, +0.2339, -0.5922,
+ -0.4052, -0.5183, +0.4653, +0.1410, +0.2020, +0.1406, -0.1232,
+ +0.2124, -0.1376, -0.2617, -0.0459, -0.4286, -0.7037, -0.0695,
+ -0.5891, +0.0045, -0.1987, -0.3906, +0.1380, +0.0949, -0.3112,
+ -0.2688, -0.1340, -0.2209, -0.3564, -0.1459, +0.3078, +0.0459,
+ +0.2045, +0.1436, -0.1081, -0.6286, -0.3076, +0.1346, +0.1734,
+ -0.0212, +0.2784, -0.2703, -0.5880, -0.1379, +0.0307, +0.4657,
+ -0.2370, -0.6191, -0.0113, +0.2450, -0.0045, +0.1112, -0.0822,
+ +0.3822, -0.0562
+ ],
+ [
+ +0.1409, -0.0538, -0.1432, +0.1716, +0.1670, +0.1345, +0.3174,
+ +0.0786, +0.3477, -0.5395, -0.3514, +0.2158, +0.0896, -0.1822,
+ +0.2500, +0.4068, +0.3118, +0.3923, -1.1109, -0.2122, +0.0909,
+ +0.1655, +0.1356, +0.4056, -0.3149, +0.1185, +0.1717, +0.0258,
+ -0.1728, +0.2402, -0.0251, -0.0708, -0.0743, -0.1093, +0.5213,
+ +0.0419, -0.1286, +0.1853, +0.4699, -0.5875, -0.2311, +0.4390,
+ -0.3652, +0.2524, -0.0379, -0.1384, -0.1974, -0.3096, +0.0594,
+ +0.0794, +0.0578, +0.1156, -0.9567, -0.3747, +0.2159, +0.1118,
+ -0.0018, -0.4289, -0.0497, +0.5024, +0.0897, -0.5219, -0.4890,
+ -0.1756, -0.1832, +0.1821, +0.3873, +0.0030, -0.7192, +0.0757,
+ +0.4871, -0.8119, -0.0317, +0.3589, -0.1295, -0.0279, -0.1444,
+ -0.8395, -0.3653, +0.1671, -0.0373, +0.0349, -0.0650, +0.2142,
+ -0.1536, -0.2972, +0.0513, -0.2596, +0.1086, -0.5500, +0.5186,
+ -0.1609, -0.2082, -0.9726, -0.0006, -0.2899, +0.1783, -0.1634,
+ -0.5750, -0.0325, -0.2408, -0.0379, +0.1189, +0.0418, +0.3697,
+ +0.2451, +0.1595, -0.2399, -0.1088, -0.1213, -0.4627, +0.2782,
+ +0.0666, -0.0095, -0.4685, -0.5872, +0.1120, +0.1272, +0.0088,
+ -0.4947, +0.3034, +0.0580, -0.2964, +0.0579, -0.1105, -0.1897,
+ +0.0601, +0.0605
+ ],
+ [
+ -0.0967, -0.8116, -0.1189, -0.5744, -0.3304, -0.6346, +0.1212,
+ +0.2593, -0.0239, +0.2636, +0.0874, -0.4657, +0.1628, +0.6463,
+ +0.2373, -0.6677, -0.1700, +0.1728, -0.3091, +0.2459, +0.3715,
+ -0.7096, -0.0390, +0.4462, +0.6917, -0.5975, -0.0984, +0.5475,
+ +0.4104, -0.1399, -0.1059, +0.0950, +0.1488, +0.1787, +0.3116,
+ -0.1217, +0.1377, +0.1193, -0.4545, -0.5360, +0.6137, -0.1851,
+ +0.2568, -0.1605, -0.0478, -0.8687, +0.4071, -0.1072, -0.1179,
+ +0.2131, +0.0615, -0.2244, -0.2624, -0.0859, -0.0773, +0.0423,
+ +0.0499, -0.3312, -0.1253, +0.0579, -0.0270, +0.1835, +0.1067,
+ -0.3907, +0.2115, +0.0562, -0.1266, +0.0306, +0.1233, -0.0524,
+ +0.0968, -0.5194, +0.2325, +0.3540, -0.4088, +0.0112, -0.2728,
+ -0.4368, -0.3143, -0.1848, +0.0044, +0.1795, -0.1937, -0.4705,
+ +0.1564, -0.4308, +0.2992, +0.1559, +0.1413, -0.5684, -0.5887,
+ -0.4417, +0.1254, +0.6016, +0.3093, +0.2221, +0.2689, +0.2764,
+ +0.2066, +0.3921, -0.0492, +0.5264, +0.1195, +0.0354, +0.0472,
+ -0.7510, +0.4551, -0.3297, +0.2557, +0.0964, -0.2333, -0.0974,
+ +0.0046, -0.1966, -0.1438, +0.2168, -0.0106, +0.0827, +0.1734,
+ -0.1622, -0.7648, +0.0657, +0.4125, -0.0107, +0.5142, -0.1843,
+ -0.0255, +0.0251
+ ],
+ [
+ -0.4894, -0.3838, -0.0560, -0.0102, +0.2462, +0.2396, -0.1605,
+ +0.6648, +0.0289, +0.3985, -0.3124, -0.1270, +0.0019, -0.0186,
+ -1.0743, +0.6784, +0.1577, +0.2268, -0.0569, +0.2442, -0.1164,
+ -1.2692, -0.6146, -0.5071, -0.0065, -0.1015, +0.0568, -0.0257,
+ -0.1093, -0.1685, +0.5144, -0.0581, +0.5970, +0.3194, -0.3760,
+ +0.2867, +0.3716, -0.2157, -0.1207, +0.3089, +0.5712, +0.2472,
+ +0.0238, -0.7120, +0.0921, -0.5046, -0.4643, +0.3063, +0.0916,
+ -0.7755, +0.0375, +0.1377, +0.4099, +0.1541, -0.0234, -0.2307,
+ -0.2292, +0.1845, -0.3229, -0.0655, -0.0224, -0.3936, +0.1464,
+ -0.2497, -1.0163, -0.0754, -0.2383, -0.1563, +0.0342, -0.2338,
+ +0.3699, +0.0190, +0.3233, +0.0361, -0.3095, +0.1544, -0.2940,
+ -0.0897, +0.2073, +0.4680, -0.3452, -0.1035, -0.1820, -0.5826,
+ -0.4127, -0.5719, -0.2433, +0.1142, -0.1415, -0.4814, -0.1358,
+ -0.0734, +0.4341, +0.2401, -0.4429, +0.3538, -0.2312, -0.2072,
+ +0.0078, -0.2757, -0.2212, +0.0824, -0.0945, -0.2644, +0.0169,
+ -0.6544, -0.0961, -0.2083, +0.4017, -0.6613, -0.2524, +0.2338,
+ -1.7121, -1.9104, +0.2422, -0.0147, +0.3072, -0.3819, +0.3498,
+ -0.4022, -0.4189, +0.4619, +0.1477, +0.3179, -0.2559, -0.0367,
+ +0.1080, -0.3277
+ ],
+ [
+ +0.0885, -0.4506, +0.4188, +0.2334, +0.2903, +0.0490, -0.0631,
+ -0.0504, +0.2215, -0.1555, -0.0389, -0.1621, +0.0310, -0.4083,
+ -0.3338, -0.2568, +0.0147, +0.1238, -0.5747, +0.0482, -0.2570,
+ -0.2541, -0.0272, +0.2152, +0.0003, +0.3637, -0.2845, +0.0474,
+ +0.1485, -0.3750, -0.4793, +0.4647, +0.0522, -0.6269, -0.1822,
+ -0.0465, +0.1702, +0.2424, -0.1810, -0.1115, -0.5531, +0.0817,
+ +0.0351, -0.0986, +0.0474, -0.4087, -0.0984, -0.2288, -0.0353,
+ +0.0090, -0.1881, -0.1815, -0.0516, +0.1652, +0.3100, +0.2649,
+ +0.2842, +0.3319, +0.4483, +0.2002, -0.1618, +0.1024, -0.1409,
+ +0.3892, +0.2560, +0.1263, -0.0126, -0.0984, +0.3725, +0.1183,
+ -0.2909, +0.1879, +0.1049, -0.1430, -0.1976, +0.2291, -0.2020,
+ +0.1399, +0.0848, +0.0876, +0.2030, -0.0233, -0.3914, -0.0174,
+ -0.0214, -0.0481, -0.2875, +0.0232, +0.0775, -0.6476, -0.2746,
+ -0.3848, -0.0085, -0.5357, -0.5196, +0.1634, +0.1043, +0.0855,
+ -0.0452, -0.0374, +0.1830, -0.2180, +0.1506, -0.1684, +0.0160,
+ +0.0860, +0.4804, -0.0316, -0.3141, -0.1559, -0.4767, -0.1185,
+ -0.1897, -0.0881, -0.1665, +0.0357, -0.3111, +0.0422, -0.1488,
+ -0.1632, -0.7307, +0.0462, +0.0164, -0.0160, +0.0143, +0.3344,
+ +0.3005, +0.2044
+ ],
+ [
+ -0.1839, -0.1799, -0.5069, +0.3499, -0.0474, +0.3088, -0.3604,
+ -0.3482, +0.0276, -0.4781, -0.1208, +0.1777, -0.2034, +0.0649,
+ -0.2837, +0.0718, +0.1179, -0.5131, +0.0390, -0.2522, -0.0683,
+ -0.0128, -0.1180, +0.3263, -0.4664, -0.2562, -0.1115, +0.2541,
+ -0.1521, -0.2567, -0.2162, -0.8788, +0.1234, +0.0628, -0.4491,
+ +0.0485, +0.1332, +0.4184, -0.1297, +0.2791, -0.3251, -0.3365,
+ +0.1526, +0.2818, -0.1102, -0.2195, -0.3119, -0.0794, -0.0632,
+ +0.0212, -0.5798, -0.3181, +0.1821, +0.5628, +0.2593, +0.0294,
+ +0.1707, +0.3392, -0.4010, -0.3270, -0.0918, -0.1726, -0.1836,
+ -0.9079, +0.1893, +0.2778, -0.0391, +0.0554, +0.1980, +0.2862,
+ -0.4825, +0.1002, -0.8366, +0.1210, +0.0550, +0.1069, -0.3516,
+ +0.1627, -0.3116, -0.0464, +0.0496, -0.1154, -1.9989, +0.0147,
+ +0.1130, -0.1936, -0.1085, -0.1807, +0.2358, +0.3699, -0.1481,
+ -0.1616, +0.1135, -0.7175, -0.0026, +0.2132, -0.1823, +0.1340,
+ +0.1992, +0.0517, +0.0738, +0.0116, -0.4166, +0.0767, +0.1451,
+ -0.4632, -0.4240, +0.2534, +0.0618, +0.1764, +0.1874, -0.1760,
+ +0.3762, -0.0860, +0.2035, -0.8606, -0.1828, -0.1658, +0.0730,
+ -0.1324, -0.6475, +0.1506, -1.5427, -0.1539, +0.3581, +0.1685,
+ -0.0010, -0.4744
+ ],
+ [
+ -0.0038, +0.2629, -0.0222, -0.4313, +0.2458, -0.0521, +0.2995,
+ +0.1401, -0.1501, +0.2219, -0.0508, -0.6905, +0.2089, -0.1588,
+ -0.1579, +0.3263, +0.1093, +0.1843, -1.6538, -0.1711, +0.0280,
+ +0.0042, +0.1678, +0.3942, -0.1122, -0.7447, +0.1776, +0.0452,
+ +0.0464, +0.1958, -0.5837, -0.2740, -0.8022, -0.0597, -0.1732,
+ -0.3843, -0.1682, +0.4161, +0.5845, +0.0023, -0.0245, -0.0033,
+ -0.0888, -0.0147, -0.0569, -0.7998, +0.1384, -0.1289, +0.3003,
+ -0.0507, -0.4349, +0.5294, +0.0240, +0.1736, -0.1584, -0.1868,
+ +0.2200, +0.0831, -0.6566, -0.1660, +0.1753, -0.0999, -0.5722,
+ -0.1753, -0.4500, -0.0143, -0.2124, -0.0305, -0.8012, +0.2173,
+ -0.1607, +0.3925, -0.3454, -0.6074, -0.1541, -0.4732, -1.1834,
+ -0.0688, -0.0430, -0.5353, -0.1790, -0.4362, -0.2226, +0.0306,
+ -0.0149, -1.2302, -0.6747, -0.3040, +0.1048, -0.6485, -0.4555,
+ +0.0236, -1.1733, +0.5728, -0.1619, +0.1556, +0.1970, -0.2370,
+ -1.8582, -1.0090, +0.0693, -0.1693, -0.1371, +0.3884, -0.1606,
+ -0.2022, -0.2294, +0.5752, -0.0680, +0.2737, -0.1054, -0.5773,
+ -1.0577, +0.0026, +0.1283, -0.2511, -0.0521, +0.1820, -0.6071,
+ +0.1580, -0.1609, -0.1862, -0.1680, -0.1709, -0.1637, -0.2186,
+ -0.2398, -0.2395
+ ],
+ [
+ -0.1990, -0.1855, -0.5902, -0.1221, -0.8566, -0.1161, -0.2680,
+ -0.2043, +0.0571, -0.2467, -0.5931, +0.0254, +0.2520, -0.0025,
+ +0.3188, -0.2049, -0.1082, -0.2633, -0.3426, -0.3033, -0.4411,
+ +0.2479, -0.4121, -0.2249, -0.2227, -0.3816, +0.1910, +0.2194,
+ -0.0299, -0.0100, -0.2124, +0.4138, -0.2423, -0.0244, +0.1657,
+ +0.0472, +0.0487, -0.3765, -0.1005, -0.1568, +0.3201, +0.4085,
+ -0.1769, -0.6161, +0.1530, +0.0596, -0.1156, -0.8411, +0.1763,
+ +0.0797, -0.6425, +0.3897, -0.2085, -0.1751, -0.0950, +0.1567,
+ +0.0639, -0.1603, -0.3423, +0.1372, +0.2382, +0.1874, -0.0615,
+ +0.0112, -0.1747, -0.6345, -0.5276, +0.1812, +0.4886, -0.0955,
+ -0.1977, +0.0003, -0.1835, -1.0626, -0.3339, +0.1317, -0.2761,
+ -0.2422, -0.6792, -0.0781, -0.3236, -0.1302, -0.3486, -0.7894,
+ -0.6369, -0.4031, -0.1746, -0.1511, -0.2680, +0.0775, -0.5212,
+ -0.1803, -0.4150, -0.3021, +0.4448, -0.4643, +0.3082, +0.5188,
+ +0.3292, -0.1640, +0.2659, -0.0533, +0.0046, -0.2112, +0.0273,
+ -0.3975, +0.1884, -0.2407, +0.5993, -0.0079, -0.1007, -0.3500,
+ -0.7119, -0.2974, -0.2962, -0.1762, +0.0230, +0.2033, +0.1797,
+ +0.0175, -0.3485, +0.2241, +0.1257, -0.1503, -0.3651, -0.4343,
+ +0.0671, -0.2769
+ ],
+ [
+ -0.2600, +0.3728, -0.1667, -0.2300, -0.1080, -0.4825, -0.1574,
+ -0.2525, -0.1608, +0.3153, +0.3603, +0.1668, -0.1195, -0.0257,
+ -0.1009, +0.2942, +0.1748, -0.3680, +0.4175, +0.1282, +0.2824,
+ -0.8205, +0.3949, +0.0005, -0.0312, +0.2784, +0.1849, +0.0828,
+ +0.1771, -0.6393, +0.0286, +0.2044, +0.5371, +0.1309, -0.1426,
+ +0.0577, -0.3925, +0.1035, +0.2724, -0.4162, -0.2550, -0.0506,
+ +0.1085, -0.0336, -0.3512, +0.1353, +0.2077, -0.2278, +0.1395,
+ -0.0786, -0.3421, +0.5657, -0.5820, +0.1765, +0.0473, +0.0195,
+ +0.0008, +0.0445, -0.0457, -0.0523, +0.2640, +0.1286, -0.0769,
+ +0.1583, +0.0020, -1.1252, -0.3394, -0.2469, -0.2057, -0.0182,
+ +0.0225, -0.4020, +0.0443, +0.3486, +0.3001, +0.1069, +0.2708,
+ -0.3042, -0.0407, +0.1189, -0.1185, -0.6579, +0.1502, -0.0180,
+ -0.1439, -1.4340, -0.0236, -0.1200, -0.3519, +0.2684, -0.9712,
+ +0.4391, +0.2379, -0.0626, -0.3674, -0.0832, -0.1493, -0.5778,
+ -0.0028, -0.3108, -0.3896, -0.5958, -0.0574, +0.0678, +0.3899,
+ -0.3551, -0.6014, -0.6356, -0.0705, +0.1556, +0.2318, +0.1251,
+ -0.0145, +0.0445, +0.1474, -0.0408, -0.5473, +0.0390, -0.0862,
+ +0.3692, +0.0987, +0.0798, -0.2238, -0.0353, +0.0702, +0.1057,
+ +0.1381, +0.0884
+ ],
+ [
+ -0.1550, -0.6553, -0.0098, -0.0513, +0.4681, -0.4697, +0.3507,
+ -0.6614, -0.1393, +0.2851, -0.2353, +0.1117, +0.3554, -0.4386,
+ -0.3174, -0.8774, -0.7019, +0.2315, -0.2981, -0.2346, +0.5748,
+ +0.3798, -0.0704, -0.0219, +0.2735, -0.1494, -0.1263, -1.4348,
+ +0.3184, -0.1334, -0.0568, +0.1348, -0.5653, -1.3195, -0.4193,
+ +0.0257, -0.6081, -0.2396, +0.5183, +0.0537, -0.4824, +0.1120,
+ -0.1459, -0.6086, +0.2357, -0.4124, -0.1445, -0.6436, -0.1888,
+ -0.2544, +0.3426, -0.6475, +0.2406, +0.4602, +0.1544, +0.1915,
+ -0.8082, +0.3168, -0.2569, +0.0707, +0.1043, +0.0112, +0.5536,
+ +0.2491, -0.4264, -0.4461, +0.4385, -0.2794, +0.0615, -0.1656,
+ -0.3143, +0.1733, -0.5887, -0.1564, +0.0588, +0.2128, +0.4712,
+ -0.0338, +0.2120, -0.0114, -0.2567, -0.4390, +0.1800, +0.1231,
+ -0.0566, +0.0131, +0.3387, -0.1946, -0.0597, +0.6877, +0.3091,
+ -0.3047, -0.0256, +0.3494, -0.5286, -0.1652, +0.4785, -0.6145,
+ -0.5849, +0.3488, -0.2858, +0.0411, -0.0751, -0.0106, +0.0322,
+ +0.1082, +0.1757, -1.0412, -0.1001, +0.1272, -0.2649, -0.2981,
+ +0.0066, -0.6085, -0.2164, +0.3369, -0.4131, -0.3749, -0.1556,
+ -0.2250, +0.3331, -0.7518, +0.5474, +0.2815, -0.1135, -0.0068,
+ +0.0842, +0.1357
+ ],
+ [
+ -0.2586, +0.1079, -0.0247, +0.2432, +0.2292, -0.1817, +0.0774,
+ -0.5248, -0.7265, +0.0755, -0.2294, -0.1428, -0.3254, +0.0887,
+ -0.2064, -0.2610, +0.4028, -0.3058, -0.6010, +0.1141, -0.3263,
+ -0.0803, -0.0203, +0.0699, -0.0710, -0.6511, -0.1640, +0.4584,
+ -0.2584, +0.2199, +0.3318, -0.4902, +0.0846, -0.0167, +0.2071,
+ -0.3865, +0.0593, +0.4101, -0.1511, -0.4140, +0.1307, +0.0728,
+ -0.1314, +0.2545, -0.1680, +0.1449, +0.2776, +0.1651, -0.1073,
+ -0.0356, -0.2519, +0.6122, -0.0189, -0.6031, +0.2458, +0.2116,
+ -0.3389, +0.1072, +0.1387, +0.2409, -0.2313, +0.1170, -0.0619,
+ +0.1290, -0.4353, +0.0356, -0.2926, +0.0432, -0.7712, -0.3432,
+ -0.0004, -0.2343, -0.0708, +0.0205, -0.0015, +0.1525, +0.0152,
+ +0.0648, +0.3449, -0.4003, +0.0074, +0.1720, -0.0653, +0.1272,
+ +0.2053, +0.1385, -0.0542, +0.1896, +0.3601, -1.3929, +0.1053,
+ -0.1274, -0.0188, -0.0037, +0.3852, -0.4051, -0.4026, +0.0011,
+ +0.1984, +0.4017, -0.2087, -0.1526, +0.0104, -0.3145, -0.1186,
+ -0.2420, -0.8113, -0.1924, -0.0769, +0.0629, +0.0287, -0.0093,
+ +0.1665, +0.4061, -0.1140, -0.1501, +0.4697, -0.1004, -0.0598,
+ -0.9584, +0.1174, +0.1803, -0.4207, +0.2724, +0.1135, -0.3000,
+ -0.1081, -0.2234
+ ],
+ [
+ -0.0944, +0.2341, -0.1293, -0.3682, -0.2815, +0.3922, +0.1281,
+ -0.0364, -0.3578, +0.3765, +0.0833, -0.2770, -0.3372, -0.1390,
+ +0.2268, -0.0754, -0.7129, +0.1079, +0.4896, -0.2936, +0.5755,
+ +0.0711, +0.0261, +0.3214, +0.1170, -0.3148, -0.3589, -0.3999,
+ -0.0442, +0.1939, -0.0184, -0.5482, -0.0909, -0.1102, +0.3405,
+ -0.2403, +0.0017, -0.0908, +0.1057, +0.0563, -0.4943, -0.2383,
+ +0.2750, +0.1475, +0.4200, -0.7400, -0.0005, -0.7109, +0.2982,
+ -0.0624, +0.0991, -0.7474, -0.3128, +0.0312, -0.1940, +0.0893,
+ +0.1152, -0.2274, -0.3678, -1.4362, -0.1969, -0.6162, +0.4540,
+ +0.2569, +0.3304, -0.1393, +0.2411, -0.5043, -0.4747, -0.4624,
+ +0.2566, +0.2622, +0.3182, -0.1998, +0.2243, +0.1218, -0.3776,
+ -0.1689, -0.3444, -1.2030, -0.3384, +0.0376, -0.9877, +0.4066,
+ +0.2852, -0.1160, +0.1727, -0.6990, -0.0899, -0.1878, +0.4875,
+ -0.7249, -0.2148, -0.2262, +0.2572, +0.5794, +0.1245, +0.0084,
+ -0.0661, +0.0022, +0.0790, -0.2628, +0.0873, +0.1133, -1.4550,
+ -0.0061, +0.4475, -0.0445, -0.1131, -0.1322, -0.1805, -0.4632,
+ -0.4034, -0.0477, +0.0881, -1.3645, +0.7105, -0.8035, -0.0230,
+ -0.2352, -0.6769, -0.0870, -0.1496, -0.7174, -0.3905, +0.5053,
+ +0.1599, +0.0774
+ ],
+ [
+ -0.0854, -0.3404, +0.0652, +0.0362, -0.0756, +0.0192, -0.1265,
+ +0.3489, -0.3569, -0.8240, +0.0391, -0.0941, -0.1433, +0.3441,
+ -0.1874, -0.2676, +0.5242, +0.2251, -0.2071, -0.1848, -0.2279,
+ -1.2238, +0.2887, +0.0095, -0.1245, -0.3161, +0.0329, -0.0625,
+ -0.2333, +0.3116, +0.0164, -0.3283, -0.4250, +0.1686, +0.2560,
+ -0.5164, -0.2912, -0.3383, -0.1983, +0.1373, +0.2847, +0.4067,
+ +0.1801, -0.1141, +0.0385, -0.4291, -0.2469, +0.0845, -0.0106,
+ -0.4852, +0.2204, -0.3597, -0.3101, +0.0629, -0.1494, -0.0957,
+ -0.2842, -0.2712, -0.1635, -0.3056, -0.0953, -0.7983, -0.2230,
+ +0.1603, +0.1263, +0.0316, +0.1262, +0.0299, +0.2142, -0.1661,
+ -0.1874, -0.2247, -0.1495, +0.4345, -0.0050, -0.0023, -1.0454,
+ -0.1850, +0.0324, -0.1299, +0.0808, +0.2819, -0.3591, -0.0671,
+ +0.3848, +0.0527, +0.0870, +0.2097, -0.7340, -0.0364, +0.1416,
+ -0.7251, +0.3899, -0.0321, +0.2230, +0.2796, +0.3449, -0.1251,
+ +0.1570, +0.2467, +0.0966, +0.1106, -0.0601, +0.2364, -0.1023,
+ +0.1761, -0.3835, +0.3161, +0.1496, +0.0713, +0.3664, -0.1054,
+ -0.8298, -0.0852, -0.6931, -0.3448, -0.0491, +0.0825, -0.1888,
+ +0.0303, -0.1669, -0.2420, +0.1384, -0.1588, -0.0640, +0.0044,
+ +0.0920, +0.5491
+ ],
+ [
+ -0.2530, -0.0550, +0.1767, -0.0197, +0.0392, +0.1533, -0.1908,
+ +0.2095, -0.4558, -0.3182, -0.1207, +0.1121, +0.1108, +0.0632,
+ +0.0251, +0.0800, -0.1490, -0.5128, +0.3625, +0.2499, -0.2294,
+ +0.1496, -0.0599, +0.3519, -1.1459, +0.4171, -0.4250, -0.8933,
+ -0.3909, -0.2782, +0.1234, +0.1028, +0.1640, -0.3572, -0.8056,
+ -0.0328, +0.0441, -0.2858, +0.4340, +0.3755, -0.1979, +0.2009,
+ -0.4347, -0.0842, -0.6567, -0.5243, -0.0483, +0.1214, -0.2512,
+ +0.3272, -1.3854, +0.1747, -0.4386, +0.1441, -0.3902, -0.4389,
+ +0.0880, -1.0031, -1.5420, -0.2146, -0.2588, -0.7700, -0.1053,
+ -0.4492, -1.1340, -0.3955, -0.0062, +0.1858, -0.4721, +0.5749,
+ -0.7658, -0.4602, -0.0370, -0.1331, +0.1250, -0.4708, +0.0186,
+ -0.0472, +0.6910, -0.1052, -1.0263, +0.3958, +0.1160, -0.0658,
+ -0.0263, +0.1706, -0.1598, +0.3593, -0.7746, -0.1430, -0.2939,
+ -0.5315, +0.1469, +0.0629, -0.2287, -0.0982, -0.9673, +0.3858,
+ -0.1839, -0.3926, +0.1103, +0.5221, -0.2097, -0.0538, -0.3374,
+ -0.2589, -0.1362, -0.8023, +0.5058, -0.1019, -0.1020, -0.2040,
+ +0.2014, -0.2802, -0.0912, +0.0152, -0.6996, +0.2708, -0.5717,
+ -0.3458, +0.1621, -0.1512, +0.2791, -0.0776, -0.1128, +0.0089,
+ +0.1515, +0.5123
+ ],
+ [
+ -0.4655, -0.0379, +0.0643, +0.1431, -0.0937, +0.1572, +0.2089,
+ +0.0227, +0.4811, +0.2738, -0.4770, -0.0302, -0.2714, -0.0353,
+ -0.4082, +0.4073, -0.2526, +0.0575, -0.2309, +0.4160, -0.2468,
+ +0.2285, -1.0454, -0.3023, +0.0094, -0.0101, +0.3390, +0.0338,
+ -0.0278, +0.1941, -0.0570, +0.2868, +0.0429, -0.8105, -0.0188,
+ -0.1246, +0.0159, -0.4999, -0.2032, +0.0914, +0.6455, -0.1245,
+ +0.0020, +0.0418, -0.6123, +0.0697, +0.1981, -0.4423, -0.1076,
+ +0.2690, +0.1470, +0.3055, -0.1343, -0.0624, +0.2082, -0.1393,
+ +0.0894, +0.2845, +0.2606, +0.3553, -0.0025, +0.4361, +0.6263,
+ -0.0265, -0.0731, +0.2340, -0.1738, +0.1374, -0.0836, -0.0444,
+ -0.7722, -0.3558, -0.3378, -0.5021, +0.1452, +0.1734, -0.0282,
+ -0.3774, +0.1987, +0.1507, +0.0245, -0.0719, -0.0083, +0.2448,
+ -0.1184, +0.1152, -0.6909, +0.1571, -0.6083, +0.0978, -0.2012,
+ +0.3425, -0.0069, +0.2474, -0.5482, +0.0814, -0.1556, -0.1506,
+ +0.1668, +0.2776, +0.3391, +0.2342, -0.2065, +0.0879, -0.6159,
+ +0.2643, -0.2567, -0.2676, +0.2018, -0.4286, -0.4639, -0.4193,
+ +0.1816, +0.2604, -0.0906, +0.0827, -0.0005, +0.2018, -0.3132,
+ -0.3025, +0.1614, -0.1068, +0.0919, +0.2894, -0.3590, -0.3032,
+ -0.4354, +0.0154
+ ],
+ [
+ -0.0429, -0.3707, -0.3739, +0.3704, -0.0150, +0.2189, -0.4955,
+ -0.7602, -0.6327, +0.1189, +0.3060, -0.5486, +0.1754, -0.5086,
+ -0.4190, -0.6469, +0.0826, -0.0344, +0.1115, -0.4931, +0.2178,
+ -0.6064, -0.0868, +0.2074, -0.1581, +0.4950, -0.4560, +0.1868,
+ -0.2302, -1.1003, -0.9498, -0.3075, -0.1099, -0.7696, +0.2225,
+ +0.3048, +0.0237, +0.1738, -0.1000, -0.0539, +0.2746, -0.6315,
+ -0.7834, +0.5839, -0.7714, -0.1029, -0.3709, -0.2092, +0.5387,
+ +0.0590, +0.3252, -0.1812, -0.0796, +0.0109, +0.1797, -0.1807,
+ -0.6953, +0.0922, +0.2157, -0.0296, +0.0137, +0.0309, -0.0322,
+ +0.1320, -1.3996, -0.5238, +0.0258, +0.1411, -0.3324, -0.0493,
+ -0.8150, -0.2201, -0.6262, -0.1943, -0.2466, -0.3587, -0.5532,
+ +0.3025, -0.9596, +0.2320, +0.0081, -0.3283, +0.0479, -0.5118,
+ -0.1686, +0.5102, -0.2949, +0.2405, -0.0371, +0.3475, -0.2653,
+ -0.1511, -0.3839, -0.0687, +0.0342, -0.5996, -0.4391, -0.5633,
+ +0.3001, -0.8634, +0.0928, +0.1859, +0.1312, -1.4476, +0.4269,
+ +0.6876, -0.3687, +0.0898, -0.2377, -0.3089, +0.2988, -0.4810,
+ -0.0220, -0.2208, -0.3043, -0.2693, -0.5514, -0.1327, +0.0981,
+ +0.1090, +0.0979, +0.0774, +0.1311, -0.0520, +0.5947, +0.1165,
+ +0.0255, +0.0646
+ ],
+ [
+ -0.4015, -0.7856, -0.0138, +0.2379, +0.4219, -0.0133, -0.1120,
+ -0.0367, +0.1862, -0.5656, -0.0802, +0.3317, -0.1842, +0.0494,
+ -0.0962, +0.1796, +0.3449, +0.3633, -0.5248, +0.3595, -0.6307,
+ -0.1464, -0.2156, -0.1198, +0.6068, -2.0541, +0.0744, +0.1036,
+ -0.4800, -0.9317, +0.3650, +0.0608, +0.2096, +0.0011, -0.1670,
+ +0.2135, +0.5401, -0.6114, -1.1094, -0.1530, -1.1694, -0.0469,
+ -0.0043, -0.3584, -0.0760, -0.4375, -0.3118, +0.2781, -0.8857,
+ -0.1821, -0.2038, +0.5715, -0.3865, -0.4510, +0.4034, -0.0904,
+ -0.0075, -0.1263, -0.3763, -0.6469, +0.0981, +0.2835, -1.0551,
+ -0.2261, -0.1222, +0.0047, +0.5585, -0.3472, -0.2015, -0.7965,
+ -0.1860, -0.5664, -0.2167, -0.2244, -0.2145, +0.3671, -0.6399,
+ -0.0906, +0.2896, -0.0949, -0.7272, -0.1690, -0.8668, +0.1197,
+ +0.2210, -0.1381, -0.0362, -0.2772, +0.3834, +0.4729, +0.1046,
+ -0.8879, +0.2266, -0.0665, +0.2083, +0.1939, +0.3427, -0.0931,
+ +0.0226, -0.2263, +0.1235, +0.4096, +0.0778, +0.4601, -0.1834,
+ -0.1526, +0.3648, +0.2721, +0.1836, +0.1039, +0.1252, -0.0670,
+ -0.4777, +0.4181, +0.0461, -1.0144, -0.2770, -0.2780, +0.4376,
+ +0.2788, -0.7011, -0.3962, -0.4795, -0.2742, -0.9814, -0.0447,
+ -0.0447, -0.4444
+ ],
+ [
+ +0.3501, +0.3281, -0.1430, +0.3228, -0.0807, +0.2136, -0.0195,
+ -0.1002, -0.2381, +0.4731, -0.0458, +0.0137, +0.2722, +0.0900,
+ -0.0668, +0.0659, -0.3536, +0.1688, -0.2339, -0.1300, -0.2204,
+ +0.1206, -0.0453, -0.2130, -0.0140, +0.0041, -0.2013, -1.2579,
+ +0.0436, -0.2726, -0.2897, -0.5455, +0.1721, -0.4969, -0.3442,
+ +0.2220, +0.0569, -0.1374, -0.4693, -0.5210, -0.7792, -0.1477,
+ -0.1435, -0.1889, +0.1739, -0.1954, +0.1126, +0.1769, -0.0294,
+ -0.2095, -0.4485, -0.1938, +0.3559, -0.1803, +0.1457, -0.3859,
+ +0.2793, -0.7072, +0.2029, -0.0043, -0.1302, -0.4323, -0.1481,
+ +0.0405, +0.1824, +0.2051, +0.2035, -0.2542, -0.0847, +0.0311,
+ +0.0031, -0.1944, +0.0411, -0.1625, -0.2449, -0.0437, +0.1181,
+ +0.1734, +0.1622, +0.2482, -1.3020, -0.2676, -0.1668, -0.4255,
+ -0.3623, +0.0653, -0.2027, +0.2574, +0.3004, +0.0192, +0.0700,
+ +0.2328, -1.2587, -0.2362, -0.3811, +0.0033, +0.3652, -0.2675,
+ -0.1837, -0.1855, -0.0299, +0.1968, -0.2170, -0.0384, -0.2551,
+ +0.0783, +0.0645, +0.0703, -0.0835, +0.1902, -0.4658, +0.5849,
+ -0.0440, -0.6254, +0.4145, +0.0154, -0.0337, -0.2226, -0.0193,
+ -0.3050, -0.2739, +0.0791, -0.0331, -0.2853, -0.3587, -0.0245,
+ +0.3906, -0.1312
+ ],
+ [
+ -0.3729, -0.3580, +0.1994, +0.3125, -0.1575, +0.0351, +0.1712,
+ +0.0479, -0.5090, -0.1524, -0.0229, -0.3794, -0.2660, -0.2205,
+ -0.3291, +0.5219, -0.3152, -0.3720, +0.0702, -0.4275, +0.0918,
+ +0.0985, +0.2214, +0.2948, +0.0067, +0.1727, +0.3573, -0.0733,
+ -0.3958, -0.5830, -0.0946, -0.2411, +0.1241, -0.5995, +0.1575,
+ +0.2158, -0.5639, -0.1019, -0.1161, -0.0025, +0.3288, -0.3254,
+ +0.0209, +0.2869, +0.0349, -0.0032, +0.2493, -0.1807, +0.2012,
+ +0.0285, -0.9862, -0.3932, +0.0355, -0.6267, -0.2420, -1.1322,
+ +0.3270, -0.4070, +0.0856, +0.1377, -0.4038, -0.2331, -0.0207,
+ -0.5493, -0.2026, -0.7153, +0.1385, +0.1107, +0.0477, +0.0602,
+ -0.3468, -0.0456, -0.3055, -0.5692, +0.0869, +0.0364, +0.2018,
+ +0.0797, +0.2311, +0.4669, -0.2796, -0.5679, +0.0042, +0.0015,
+ -0.0524, -0.2371, -0.3690, -0.3491, +0.1767, -0.2053, -0.2630,
+ -0.6185, +0.0131, -0.2657, -0.5073, -0.2655, +0.0691, -0.0768,
+ -0.4844, -0.6951, -0.3339, +0.3054, -0.8780, -0.0191, -0.6555,
+ -0.3514, -0.3141, -0.3230, -0.0244, +0.0889, +0.1160, +0.3249,
+ +0.2260, -0.1515, -0.2689, -0.3664, -0.1808, +0.0221, +0.5215,
+ +0.0880, -0.1395, -0.5289, -0.7631, +0.0567, -0.4045, -0.2250,
+ +0.0902, -0.3769
+ ],
+ [
+ -0.5947, +0.2274, -0.9496, +0.3703, +0.0841, -0.1836, +0.0044,
+ +0.0021, +0.1787, -0.0429, +0.1353, -0.4052, +0.0083, +0.1235,
+ +0.6274, +0.2087, +0.3484, +0.1119, -0.1528, +0.0003, -0.3680,
+ -0.5990, -0.5782, -0.0053, -0.0038, +0.2493, +0.0427, -0.1297,
+ -0.0332, +0.0291, -0.1151, -0.0122, +0.2482, -0.1746, +0.6397,
+ +0.1691, +0.0541, -0.1390, -0.0668, -0.1904, +0.2275, -0.0548,
+ -0.3013, -0.3059, +0.0162, -0.3792, +0.2507, -1.5725, -0.0162,
+ +0.4433, -0.2386, -0.3115, +0.2838, -0.2357, -0.2010, +0.3173,
+ -0.0459, -0.0212, +0.3470, +0.1231, -0.2594, +0.0194, +0.0015,
+ +0.5905, -0.0855, +0.0124, +0.3250, +0.0103, -0.2701, +0.0159,
+ +0.1874, -0.0726, +0.1616, +0.0483, -0.2104, +0.0683, +0.0354,
+ +0.0604, +0.0738, -0.6140, -0.1024, +0.1922, -0.6209, -0.4914,
+ -0.1139, -0.3441, +0.2979, -0.0118, +0.0571, +0.2113, -0.4013,
+ -0.2839, -0.2274, -0.1234, -0.2224, +0.5136, -0.5031, -0.2097,
+ +0.1413, +0.4381, -0.5172, -0.2161, +0.1183, +0.1782, +0.0394,
+ -0.9201, +0.1413, +0.1968, -0.8099, -0.2413, -0.0397, +0.0048,
+ -0.9168, +0.0216, +0.2725, -0.6455, +0.0540, -0.1368, -0.8279,
+ -0.2034, -0.1583, +0.2583, -0.4102, +0.2368, -0.1897, +0.0892,
+ +0.2035, -0.6145
+ ],
+ [
+ -0.4914, -0.0175, -0.1029, -1.1875, +0.0158, +0.1054, -0.4501,
+ +0.1822, +0.1384, +0.0073, +0.1010, +0.2072, -0.0566, +0.0374,
+ -0.5182, +0.2300, -0.0543, +0.0234, +0.0719, -0.3345, +0.1585,
+ -0.2427, -0.3074, -0.5413, +0.0213, +0.2899, +0.1372, -0.2435,
+ -0.1829, +0.5233, -0.1391, +0.0271, -0.0862, +0.1832, +0.7547,
+ -0.0167, -0.1029, -0.4332, +0.3798, +0.0694, -0.6046, +0.2171,
+ +0.0931, -0.4275, +0.0547, +0.1686, +0.0674, -0.3921, +0.5958,
+ +0.2580, -0.7376, +0.4033, +0.3357, +0.5261, -0.2143, -0.2368,
+ -0.1381, -0.7014, -0.2709, +0.3299, -0.6330, +0.0553, +0.1474,
+ +0.5485, -0.4183, -0.5408, -0.4226, +0.1773, -0.0814, -0.0224,
+ +0.1349, -0.1298, -0.7348, +0.1840, -0.1371, +0.2017, +0.0927,
+ -0.2807, +0.1679, -0.3693, +0.1331, +0.1271, +0.0445, -0.1609,
+ -0.3406, -0.5669, -0.1359, +0.3603, -0.2292, -0.1502, -0.2860,
+ +0.3773, -0.0089, +0.2764, +0.4845, -0.1967, -0.8141, -0.0563,
+ +0.1718, -0.0717, +0.4198, +0.0029, -0.3978, +0.2698, +0.0651,
+ +0.2271, +0.1170, -0.3438, -0.2717, +0.6219, -0.0172, +0.2207,
+ -0.5174, +0.1052, -0.2792, +0.1195, +0.3255, +0.2822, -0.1286,
+ -0.6566, +0.0267, +0.3203, -0.5382, -0.0283, -0.9872, -1.0424,
+ -1.0301, -0.0555
+ ],
+ [
+ -0.0453, -0.2395, +0.2406, +0.0631, +0.0629, +0.0833, +0.1781,
+ +0.3761, -0.2013, -0.5130, -0.5778, -0.0650, -0.1589, -0.3232,
+ -0.3333, -0.8319, +0.2013, +0.2267, +0.2610, -0.5927, -0.0493,
+ +0.2577, +0.4523, +0.1532, -0.6685, -0.0539, +0.2305, +0.2816,
+ -0.1894, +0.1239, +0.0723, -0.3620, +0.0898, -0.0181, -0.0459,
+ +0.1914, -0.6516, +0.1430, -0.5466, -0.3008, -0.0715, -0.6103,
+ +0.0118, +0.0141, +0.1248, -0.1234, +0.0846, +0.2255, -0.5190,
+ -0.2559, -0.1613, +0.4473, +0.1540, -0.5639, -0.8685, +0.1487,
+ -0.2612, +0.3390, -0.4948, -0.0352, +0.0908, +0.1311, +0.0625,
+ -0.1194, -0.2128, +0.0454, +0.2579, +0.3957, +0.5040, +0.1017,
+ -0.3063, -0.4509, -0.2063, -0.2673, -0.3279, +0.0295, -0.1485,
+ +0.2786, +0.1512, +0.1158, +0.1659, -0.1235, -0.8287, -0.2932,
+ +0.0973, -0.0585, -0.3973, +0.2949, +0.2267, -0.1506, +0.2104,
+ -0.1853, -0.4127, -0.8102, -0.1861, -0.2241, -0.0969, -0.1213,
+ +0.2320, -0.8217, +0.0387, +0.1559, +0.0937, +0.0199, +0.2130,
+ +0.5811, +0.1031, +0.0254, +0.1938, -0.1855, +0.2375, -0.6722,
+ -0.1418, +0.6080, -0.6757, -0.2532, +0.0382, +0.2149, -0.2714,
+ +0.3754, -0.2763, +0.0971, -0.3987, +0.5819, -0.0490, -0.6208,
+ -0.0094, -0.0335
+ ],
+ [
+ -0.0520, +0.1143, +0.3346, +0.3328, -0.7457, -0.4004, +0.4402,
+ +0.1565, +0.2192, -0.7181, +0.4356, +0.0638, +0.1050, +0.3447,
+ -0.9636, -0.2623, +0.5175, -0.0571, +0.0749, -0.2558, -0.1522,
+ +0.1987, +0.3003, -0.0340, -0.1250, +0.1917, +0.0105, +0.1603,
+ +0.3017, +0.1785, +0.3443, -1.5343, -0.1129, -0.3967, -0.0861,
+ -0.1839, +0.3447, -0.0320, -0.1140, -0.7012, -0.5374, -0.1204,
+ -0.1188, -0.9007, +0.1548, -0.1386, -0.0337, +0.6399, -0.4455,
+ +0.0039, +0.2296, +0.0017, -0.3522, -0.4161, +0.1904, -0.4585,
+ -0.0504, -0.4775, -0.1963, -0.0786, -0.0918, -0.0926, -0.4992,
+ -0.4981, +0.1395, -0.0966, -0.1520, +0.1250, -0.3255, +0.1306,
+ +0.1884, +0.2478, -0.1758, -0.0991, -0.3168, +0.2045, +0.1035,
+ +0.1926, +0.1510, -0.9593, +0.2111, -0.5241, -0.6604, -0.0298,
+ -0.4766, -0.1225, -0.2626, -0.2218, +0.3571, -0.8226, +0.0405,
+ -0.8556, -0.8859, -0.3557, -0.7047, +0.2757, -0.0380, +0.1300,
+ -0.2333, -0.4366, -0.6659, +0.1032, +0.0568, +0.0892, -0.5488,
+ -0.5828, +0.2135, +0.5198, +0.2927, -0.1756, +0.4095, -0.5759,
+ -0.5219, +0.0122, +0.1435, -0.3798, +0.1782, +0.0249, -0.7436,
+ -0.4398, -1.0002, -0.4882, +0.3656, +0.4042, +0.3798, -0.3411,
+ -0.0478, -0.4250
+ ],
+ [
+ +0.0293, -0.1663, -0.3768, -0.2223, -0.0055, -0.3266, +0.1328,
+ +0.2718, +0.3462, +0.0200, -0.5919, -0.0576, -0.5609, -0.3056,
+ +0.0931, +0.3790, +0.0302, +0.0964, +0.0000, -0.1535, -0.2970,
+ +0.7108, +0.7230, -0.1885, +0.3083, -0.2583, -0.1817, -0.2954,
+ -0.4350, +0.2642, +0.0138, -0.2058, -0.5751, +0.2576, +0.2225,
+ -0.3665, -0.9525, -0.1351, -0.3914, +0.0191, -0.0508, -0.6731,
+ +0.1697, -0.3946, -0.0264, -0.0259, +0.0276, -0.5611, -0.4430,
+ +0.2832, -0.6663, -0.0660, +0.2421, +0.0772, -0.0405, +0.2755,
+ +0.0031, -0.6514, +0.0150, +0.3053, +0.4018, +0.5021, -0.2157,
+ +0.1647, -0.8754, +0.1060, +0.1213, +0.0049, -0.5501, +0.3529,
+ +0.3156, -0.1689, -0.3875, -0.1849, -0.1724, +0.1727, +0.1591,
+ -0.0960, +0.1350, -0.5237, -0.3937, +0.0273, +0.3581, +0.1818,
+ -0.2577, +0.4555, +0.3635, +0.4512, -0.2311, -0.1382, -0.8001,
+ -0.4946, +0.0842, +0.3760, +0.1495, +0.6040, -0.4504, -0.4973,
+ +0.0428, +0.0742, -0.1994, -0.0175, -0.0597, -0.2138, -0.3823,
+ -0.1439, +0.1747, -0.8329, -0.2617, +0.2151, +0.1795, -0.4310,
+ +0.0498, +0.0994, +0.5801, +0.2664, +0.2355, -0.6505, -0.2277,
+ -0.4698, +0.4264, -0.0938, -0.3382, -0.3953, +0.0303, +0.4967,
+ +0.1012, -0.1518
+ ],
+ [
+ -0.2188, +0.1021, -0.2240, -0.4672, +0.1532, -0.3045, +0.1718,
+ +0.1418, -0.5078, -0.3792, +0.0666, +0.0985, -0.3817, -0.1581,
+ -0.3091, -0.4972, -0.4725, +0.1204, -0.6940, -0.1842, +0.0045,
+ -0.9836, +0.1029, -0.1811, +0.0756, +0.0428, +0.0777, -0.3013,
+ -0.4269, -0.0528, +0.0722, -0.0670, -0.7216, +0.1244, +0.2999,
+ -0.0958, +0.0789, -0.1816, -0.4453, -0.6704, -0.0310, -0.2875,
+ +0.3572, -0.0051, -0.4087, +0.0230, +0.3466, -0.1092, +0.3518,
+ -0.3754, -0.1125, -0.1751, -0.1190, +0.0514, +0.2108, +0.0382,
+ -0.2385, -1.1745, -0.6549, +0.1466, +0.1003, -0.1397, +0.1939,
+ -0.1007, -0.5671, -0.2141, -0.3080, -0.3285, -0.5235, -0.5764,
+ -0.3409, -0.5457, +0.1450, +0.2169, -0.0775, -0.3134, -0.2641,
+ +0.0260, -0.1224, -0.2079, -1.1028, -0.0962, +0.3657, +0.2675,
+ +0.2761, -0.1438, -0.0040, +0.3894, -0.1598, -0.9228, -0.4203,
+ +0.3786, -0.6578, -0.2065, +0.4389, -0.6512, +0.1878, +0.1302,
+ -0.1187, +0.0349, -0.2018, +0.2299, -0.1649, -0.5971, -0.0187,
+ -1.1908, -0.2499, -0.4757, +0.0489, -0.0761, +0.6595, +0.0984,
+ -0.2936, -0.1527, +0.3843, +0.4120, +0.2702, +0.0496, -0.1293,
+ +0.6906, +0.2244, -0.1256, -0.4838, +0.6558, -0.0440, -0.2431,
+ -0.5317, +0.1463
+ ],
+ [
+ +0.1007, -0.2044, +0.0915, -0.1110, +0.2309, +0.0957, +0.0353,
+ -0.2517, -0.1242, -0.1429, -0.3406, +0.0926, +0.0606, +0.0489,
+ +0.0082, +0.1055, -1.3637, +0.2863, -0.8374, +0.0397, -0.0966,
+ +0.1015, +0.0416, +0.2654, -0.1580, +0.0091, +0.2479, -0.1647,
+ +0.0940, +0.1184, -0.1846, +0.2333, -0.1408, -0.0981, +0.1680,
+ +0.0911, +0.4148, +0.2737, +0.0429, -0.3616, +0.0468, +0.2632,
+ -0.2784, +0.4318, +0.0774, -0.4683, +0.0070, -0.0744, -0.0775,
+ +0.0305, +0.0484, -0.1177, +0.0596, -0.1406, +0.0670, -0.0642,
+ +0.2147, -0.3049, -0.0589, +0.2003, -0.0902, -0.1474, -0.3707,
+ +0.1232, -0.3934, +0.1415, -0.2993, +0.0076, -0.1834, +0.0297,
+ -0.1118, +0.1966, +0.1434, +0.0009, +0.0595, -0.2880, +0.0926,
+ -0.3560, -0.5908, +0.2940, -0.0431, -0.0223, +0.4797, +0.1149,
+ -0.0131, -0.0821, +0.0943, -0.2290, +0.1531, +0.2856, -0.3395,
+ -0.1174, -0.5446, +0.0501, -0.0462, -0.1134, -0.1696, +0.0725,
+ -0.0470, -0.0893, +0.0332, -0.0180, +0.5846, -0.2333, +0.1019,
+ -0.0331, +0.0771, +0.2611, -0.1336, -0.1301, -0.9212, -0.3052,
+ +0.0114, +0.0305, -0.2702, -0.1209, +0.2616, +0.4937, -0.0724,
+ +0.2716, -0.0188, +0.2153, +0.3038, +0.1207, +0.1832, -0.1724,
+ +0.2292, +0.2457
+ ],
+ [
+ -0.1804, -0.6413, -0.0744, +0.1991, -0.0737, -0.2933, +0.1017,
+ -0.1491, +0.4600, +0.2833, -0.2731, -0.1631, -0.5416, -0.4341,
+ -0.2894, -0.1315, -0.2177, +0.0498, -0.0359, +0.4271, -0.1389,
+ -0.0952, -0.0668, -0.2945, +0.0423, -0.4391, +0.1829, -0.0940,
+ +0.2085, +0.4466, -0.0549, -0.4789, +0.1381, +0.3271, -0.1952,
+ -0.5656, -0.4272, -0.6747, -0.1363, -0.4104, +0.3835, +0.1417,
+ +0.3708, +0.0614, -1.0061, -0.3433, +0.5277, -0.0979, +0.2403,
+ -0.3140, -0.1091, -0.0942, -0.7187, -0.1379, -0.0743, -0.0831,
+ -0.0651, -1.4077, -0.2030, +0.4326, +0.1291, +0.0197, +0.0664,
+ +0.0799, -0.0921, -0.1370, -0.4199, +0.2537, -0.1733, -0.5453,
+ -0.3406, +0.2641, -0.2840, -0.2217, -0.1717, -0.2596, -0.6149,
+ +0.2036, -0.1179, -0.4542, -0.2821, -0.0771, -0.3978, -0.0618,
+ -0.0831, -0.2506, -0.1301, +0.0824, -0.5279, -0.0014, -0.0490,
+ -0.5102, -0.3509, -0.0945, +0.3115, +0.4273, -0.6854, -0.7175,
+ -0.3040, +0.1343, -0.3622, -0.2034, +0.4940, -0.5965, +0.0041,
+ -0.6200, +0.0382, +0.2886, -0.6852, +0.1837, -0.1224, -0.3253,
+ -0.2527, -0.8300, -0.0729, +0.0226, -0.4047, +0.1606, +0.2364,
+ -0.4973, -0.6442, +0.1035, +0.3565, +0.0052, +0.3142, +0.3418,
+ +0.0403, -0.5119
+ ],
+ [
+ -0.1017, -0.0053, +0.0267, -1.0741, -0.1520, -0.1370, -0.3307,
+ -0.0732, -0.4366, -0.7079, -0.2262, -0.2293, -0.1644, +0.1885,
+ +0.6407, -0.2647, +0.0997, +0.1705, +0.3492, -0.1606, -0.0041,
+ -1.6792, +0.0112, -0.0425, -0.4714, -0.0951, +0.1999, +0.1248,
+ +0.2741, +0.2132, +0.3065, +0.2279, -0.1889, +0.0610, -0.3630,
+ +0.1476, -0.0402, -0.1753, -0.7225, -0.0120, +0.0444, +0.1587,
+ +0.1624, -0.3233, +0.0357, +0.1818, +0.2471, -0.5049, -0.9300,
+ -0.1819, -0.0472, -0.1533, +0.2635, +0.2933, -0.1783, -0.2531,
+ -0.1683, -0.0108, +0.0977, +0.2713, -0.0255, -0.2324, +0.1616,
+ -0.3653, -0.1300, -0.0267, -0.0338, +0.1684, +0.0473, -0.0590,
+ -0.1669, +0.0260, -0.2941, +0.1953, -0.7179, -0.1900, +0.1382,
+ +0.3187, +0.1247, -0.5942, -0.5205, -0.0947, -0.0335, -0.0588,
+ -0.0189, +0.3053, -0.0854, -0.3207, +0.1741, +0.0546, +0.0115,
+ -0.2876, +0.1458, +0.3574, -0.2910, +0.0976, +0.1731, -0.0817,
+ -0.0826, +0.2886, -0.1298, +0.2386, +0.2121, -0.1873, +0.3193,
+ +0.3598, +0.3700, -0.4408, +0.0477, -0.2259, -0.8351, -0.3033,
+ -0.1020, -0.3804, -0.0147, -0.0782, -0.0253, +0.2604, +0.0669,
+ -0.0886, -0.2918, +0.0786, -0.0955, +0.1704, -0.2301, -1.1527,
+ -0.0295, +0.4580
+ ],
+ [
+ -0.6923, -0.0835, -0.2932, +0.1860, -0.0988, +0.0671, +0.0189,
+ +0.2117, +0.1516, +0.1037, -0.1780, +0.5206, -0.2900, -0.4395,
+ +0.0723, -0.1160, +0.1709, -0.1442, +0.3346, -0.7235, -0.4740,
+ +0.0875, -0.0777, -0.1537, +0.4708, +0.3247, +0.1284, -0.2747,
+ +0.4688, +0.1906, -0.5578, -0.2271, -0.6142, -0.2636, -0.1089,
+ -0.4988, -0.1197, -0.1757, +0.0829, -0.0075, +0.2441, -0.6189,
+ -0.1981, +0.1928, +0.1158, -0.3283, -0.5588, +0.0071, +0.6097,
+ +0.3238, -0.3600, +0.4527, -0.0510, +0.7691, -0.5023, -0.2895,
+ +0.2136, +0.1607, +0.3858, -0.0098, +0.3589, -0.1146, -0.0712,
+ -0.0400, -0.1925, -0.4676, +0.2759, +0.1378, -0.4339, -0.5202,
+ -0.4195, +0.0838, -0.2441, -0.3500, +0.0759, -1.0871, -0.1415,
+ -0.2753, -1.1007, -0.0186, +0.1863, -0.5634, +0.0043, +0.1119,
+ +0.2769, -0.1073, -0.2010, +0.4234, -1.3143, +0.3216, +0.1197,
+ -0.0692, -0.4731, -0.6585, +0.1252, +0.1992, -0.2571, +0.1463,
+ -1.2326, +0.1175, +0.0214, -0.3330, -0.2817, -0.4959, -0.0610,
+ -0.0143, -0.7349, +0.2925, -0.2817, -0.2231, +0.1759, -0.9774,
+ +0.2390, -0.1225, -0.9171, -0.1901, -0.7895, -0.4615, +0.0353,
+ -0.5406, -0.4352, +0.3894, +0.1673, -0.5319, -0.4118, -0.2283,
+ -0.5668, +0.2083
+ ],
+ [
+ -0.2980, -0.3592, -0.0770, -0.3542, +0.1863, +0.2256, -0.1919,
+ -0.1789, -0.4016, +0.1436, -0.2752, +0.0135, +0.2265, -0.3872,
+ +0.0598, +0.0476, -0.2551, -0.1743, -0.7473, -0.2520, -0.2357,
+ -0.3911, +0.0377, +0.1986, -0.0369, -0.3049, +0.1196, +0.2373,
+ +0.1458, +0.2655, +0.1632, -0.1340, -0.2975, +0.4237, +0.2112,
+ +0.4525, -0.0604, -0.0543, -0.4549, +0.0763, -0.6850, -0.4227,
+ -0.7335, -0.1524, -0.2647, -0.1532, +0.3511, -0.2706, +0.1650,
+ -0.4522, -0.0460, +0.6378, -0.1204, +0.0676, -0.0465, -0.0767,
+ +0.2404, -0.8729, +0.2271, +0.4106, -0.1021, +0.0290, -0.5288,
+ -0.1131, -0.3274, +0.0984, -0.4574, +0.5551, -0.1834, +0.0660,
+ -0.1157, +0.1353, -0.2033, -0.3010, +0.5301, +0.0713, -0.2118,
+ -0.1965, +0.0318, +0.5520, -1.3944, +0.3160, -0.5554, -0.3506,
+ +0.0334, +0.1534, +0.1675, -0.2854, +0.1113, -0.2012, +0.3805,
+ -0.0233, -0.2185, +0.1111, +0.0239, -0.4577, +0.1438, +0.1930,
+ -0.1968, +0.1310, +0.6313, -0.3919, -0.4534, +0.2406, -0.5656,
+ +0.1666, +0.0888, +0.0411, +0.0157, +0.3176, -0.1931, +0.2688,
+ -0.3309, +0.0924, -0.0175, +0.3059, +0.0998, -0.1257, +0.2527,
+ -0.5143, +0.0128, +0.0456, -0.3505, -0.3927, -0.0699, -0.4737,
+ -0.5614, -0.4470
+ ],
+ [
+ -0.4806, +0.3155, +0.0923, -0.0874, -0.3705, +0.0612, +0.2649,
+ -0.5107, -0.7034, +0.1830, -0.2687, -0.0724, -0.0851, -1.4003,
+ +0.0659, -0.5941, +0.1984, +0.1414, -0.1043, +0.0107, -0.6484,
+ -0.0740, +0.2101, +0.0407, -0.2219, +0.0094, -0.1241, -0.3421,
+ -0.0127, -0.1056, +0.2103, +0.2309, -0.2926, -0.7421, -0.5438,
+ +0.0586, +0.0710, +0.3101, -0.6930, +0.0095, -0.5734, +0.1109,
+ -0.3719, +0.1490, +0.1394, -1.1226, -0.0579, +0.3137, -0.1024,
+ +0.3899, +0.0721, -0.4998, +0.0433, +0.3800, +0.2369, +0.2631,
+ -0.4126, +0.4422, -0.0038, +0.1540, -0.2970, +0.2507, +0.0484,
+ -0.0013, -0.1378, +0.3255, -0.6364, +0.1867, +0.3550, +0.1193,
+ -0.1194, -0.5268, -0.0703, +0.0644, -0.1363, +0.0177, +0.0322,
+ +0.2742, +0.0973, -0.1359, -1.5205, +0.3452, +0.1356, -0.0290,
+ -0.1225, -0.5191, -0.1403, -0.1737, -0.3189, +0.1529, +0.1788,
+ +0.5082, -0.2529, -0.1178, +0.1159, -0.2308, +0.0791, +0.0944,
+ +0.2157, -0.1984, -0.6510, -0.2869, -0.0004, +0.2280, +0.0338,
+ +0.1443, -0.5017, +0.3413, -0.0812, -0.3725, -0.0953, -0.1753,
+ -0.6761, -0.7394, -0.2595, -0.5947, -0.1616, -0.1802, +0.1509,
+ -0.3197, -0.0278, +0.2917, +0.2329, -0.0423, +0.1683, -0.2103,
+ +0.1495, +0.0141
+ ],
+ [
+ -0.0667, -0.0992, -0.1614, +0.0497, +0.1847, +0.0645, +0.1867,
+ +0.1900, +0.0920, -0.4507, +0.0406, -0.5628, +0.1646, +0.0726,
+ -0.0777, -0.0642, -0.7265, +0.1354, +0.2330, -0.3079, +0.1769,
+ -0.1255, +0.2995, -0.1625, -0.6023, -0.1636, +0.2149, +0.0838,
+ +0.1872, -0.0040, -0.2513, +0.1646, +0.4241, +0.3852, -0.2071,
+ +0.2552, +0.5452, +0.2415, +0.1584, -0.3388, +0.0944, -0.0345,
+ +0.1485, -0.2260, +0.1944, -0.3549, -0.0954, -0.3895, +0.0756,
+ -0.1107, +0.3953, -0.2296, -0.6125, +0.2883, +0.5243, -0.1802,
+ +0.1412, +0.0637, +0.2653, +0.1138, +0.0330, -0.8522, -0.4973,
+ -0.1516, -0.1257, +0.0568, -0.1561, -0.9619, -0.3596, +0.0625,
+ +0.0618, -0.3619, +0.0190, -0.0134, +0.0080, -0.1078, +0.5391,
+ +0.0050, +0.0016, -0.2223, -0.0290, -0.2086, +0.1544, -0.4426,
+ +0.2384, -1.1034, -0.0437, +0.1262, +0.2907, +0.1822, +0.2386,
+ -0.3384, -0.0796, -0.0364, -0.2243, -0.3665, +0.2532, -0.0050,
+ -0.5482, -0.1726, -0.0011, +0.2308, -0.1187, +0.4308, +0.3380,
+ -0.5357, -0.3053, -0.1135, -0.4833, +0.2517, -0.3469, -0.1541,
+ +0.2791, -0.6348, +0.3385, +0.0960, +0.0710, -0.0633, -0.0994,
+ +0.3203, -0.7650, -0.3229, -0.2339, -0.1777, +0.1286, +0.3831,
+ +0.2287, +0.2214
+ ],
+ [
+ -0.2278, +0.0599, +0.1749, +0.0846, +0.2653, -0.2085, +0.2674,
+ +0.0839, +0.1695, +0.0025, +0.1746, -0.6353, -1.5946, -0.0767,
+ +0.1051, -1.0178, -0.4124, -0.8966, -0.4066, -0.4909, +0.1857,
+ -0.3586, -0.0416, -0.0515, -0.5398, -0.4615, +0.0544, -0.2038,
+ -0.6872, -0.1224, +0.1132, -0.0118, +0.5187, -0.3769, -0.3153,
+ -0.6752, -0.0928, +0.5779, -0.3849, -0.2489, -0.2858, +0.0034,
+ -1.1811, -0.5856, +0.0593, -0.7577, -0.4646, -0.0720, -0.0858,
+ -0.6801, -0.3070, -0.2493, -0.3826, +0.1238, +0.0142, +0.1338,
+ -0.2912, +0.1265, +0.1413, -0.0790, -0.4042, -0.1121, +0.0566,
+ -0.5050, -0.1847, -0.0788, -0.7086, +0.4693, +0.0922, -0.5241,
+ +0.0480, -0.6937, -0.3177, +0.3113, -0.2466, -0.0568, -0.3864,
+ +0.0785, +0.1268, +0.3052, -0.4641, +0.0233, +0.3174, +0.4796,
+ +0.2136, +0.2071, -0.3378, +0.1770, -0.3073, -0.4837, +0.0268,
+ +0.3070, -0.7598, +0.1185, -0.9079, -0.0655, -0.8789, +0.1163,
+ +0.0533, -0.4104, -1.1246, +0.3531, -0.2305, -0.0769, +0.2587,
+ -0.2744, -0.1765, +0.1128, -0.3661, -0.2759, -0.3635, -0.0870,
+ +0.2840, -0.1848, -0.7447, -0.1136, -0.5474, +0.1823, +0.3944,
+ -0.8700, +0.2521, +0.2599, -0.1910, -0.1516, -0.0022, +0.1349,
+ +0.0809, -0.0219
+ ],
+ [
+ +0.1997, -0.1686, +0.1633, +0.3972, -0.2555, -0.4707, +0.0986,
+ +0.2124, +0.2609, -0.0477, +0.0647, +0.2468, -0.4802, +0.2162,
+ +0.1008, -0.3933, -0.7887, +0.1305, -0.3189, +0.1509, +0.1744,
+ +0.0297, +0.1503, +0.3479, +0.4152, -0.0781, -0.1543, -0.3510,
+ -0.4484, +0.2827, -0.3342, +0.2767, -0.1857, -0.0755, +0.0698,
+ -0.0198, +0.3059, +0.1141, -0.1964, +0.0740, +0.1471, +0.0524,
+ +0.3166, +0.4728, +0.2753, -0.2491, -0.3577, -0.0727, +0.1008,
+ +0.2395, +0.1954, -0.2640, +0.1138, +0.2663, -0.0429, -0.1869,
+ -0.1945, +0.2696, -0.0298, -0.4269, +0.1007, -0.0709, +0.1780,
+ -0.0386, +0.1516, -0.2490, +0.0642, -0.1984, +0.1382, +0.2252,
+ +0.2989, -0.0884, +0.5567, -0.1373, -0.0234, -0.1539, +0.2249,
+ +0.0235, +0.0363, -0.0671, +0.5934, -0.3499, -0.4031, -0.0343,
+ +0.0282, +0.2338, -0.1531, -0.0376, -0.3333, -0.0082, +0.3619,
+ +0.0112, -0.2805, +0.1392, -0.2005, -0.4171, -0.0823, -0.1410,
+ -0.0805, -0.1926, +0.4222, -0.0171, +0.5127, +0.2822, +0.2713,
+ -0.5033, +0.1302, -0.1223, -0.2492, +0.0080, +0.3015, +0.2210,
+ -0.1282, -0.2839, -0.2694, +0.0342, +0.0786, -0.0651, +0.4300,
+ -0.3366, +0.1258, +0.0659, +0.1648, -0.3529, -0.1900, -0.0573,
+ -0.1043, +0.3084
+ ],
+ [
+ -0.3196, -0.3881, -0.2989, +0.0906, -0.1275, -0.0363, +0.1150,
+ -0.0005, -0.3683, +0.2742, -0.0017, +0.0236, -0.4375, +0.2102,
+ +0.3765, -0.4295, -0.1413, -0.1046, -0.4363, -0.2343, -1.3066,
+ -1.2125, +0.2322, +0.0435, -0.2443, +0.2904, +0.3639, +0.0835,
+ -0.0235, +0.1044, +0.0270, -0.2595, -0.1545, +0.4291, -0.6825,
+ -0.1580, -0.3518, -0.4174, -0.3360, +0.1452, -0.3446, -0.0335,
+ -0.2831, -0.0344, +0.0732, +0.0012, -0.7452, -0.2454, +0.0288,
+ +0.0435, +0.2431, -0.1675, +0.3184, -0.0510, +0.2899, -0.5552,
+ +0.0075, -0.7057, +0.0556, -0.1258, -0.9960, -0.9879, +0.2819,
+ +0.0506, -0.4218, +0.0495, +0.1051, +0.0847, +0.1042, +0.1964,
+ +0.0236, -0.4007, -0.2263, +0.1160, -0.4721, +0.0103, -0.1899,
+ -0.0715, +0.2563, +0.4472, -0.0286, +0.0117, +0.1024, -0.0833,
+ +0.2239, +0.0298, +0.0470, +0.0317, -0.2442, +0.1281, -0.1152,
+ +0.2104, +0.1516, -0.3350, +0.1161, +0.0015, -0.2331, -0.1021,
+ +0.1318, +0.0211, -0.0406, -0.3460, -0.0693, +0.3281, +0.2538,
+ +0.0049, -1.5453, -0.5795, +0.1501, -0.0246, -0.1320, +0.1567,
+ +0.1448, -0.5247, +0.0656, -0.1189, +0.2296, -0.2399, +0.1571,
+ +0.1269, -0.2336, -0.2560, -0.2979, -0.0549, +0.2824, -0.0339,
+ -0.4543, +0.0071
+ ],
+ [
+ +0.2987, -0.2200, +0.0036, -0.7426, -0.0864, +0.0387, -0.2558,
+ -0.3795, -0.2955, -0.2933, +0.2701, +0.1779, -0.0576, -0.4442,
+ +0.1014, -0.1645, -0.1616, +0.0985, +0.4104, +0.5039, -0.1322,
+ -0.2139, +0.2462, -0.3159, -0.2811, -0.2837, +0.4436, +0.3231,
+ +0.1408, +0.1549, +0.1745, +0.1944, -0.2509, +0.4857, -0.9717,
+ +0.0911, -0.1165, -0.1745, -0.2154, +0.5759, -0.3839, +0.4048,
+ +0.1516, -0.1299, -0.2511, +0.1025, +0.0566, -0.2283, -0.3304,
+ -0.2317, +0.4664, +0.1280, -0.2645, -0.3396, +0.2112, +0.1603,
+ +0.3225, +0.3721, +0.3877, +0.2450, -0.0419, +0.0659, -0.3701,
+ -0.7026, -0.3082, +0.0884, +0.1561, +0.3241, -0.1554, -0.3413,
+ -0.1884, -0.9844, -0.5072, -0.0303, +0.1457, +0.3460, -0.5375,
+ -0.2408, -0.1810, -0.5850, +0.0492, +0.1837, -0.1011, +0.4130,
+ +0.0559, -0.0881, +0.3454, +0.2754, -0.7812, +0.1154, -0.3114,
+ -0.2542, +0.0460, -0.0661, +0.1960, +0.1341, -0.1157, +0.1198,
+ -0.2963, -0.3547, +0.3525, -0.3400, -0.1312, +0.0590, -0.0392,
+ +0.4954, +0.0648, +0.3201, -0.2454, -0.2929, +0.0651, +0.5381,
+ -0.3279, +0.2092, -0.1961, -0.1749, -0.5174, -0.1017, -0.1551,
+ +0.1715, -0.0994, +0.1894, +0.0272, +0.2676, +0.1321, -0.0582,
+ -0.1677, +0.2883
+ ],
+ [
+ -0.0146, -0.0709, -0.0518, -0.0176, -0.2959, -0.1746, -0.0633,
+ +0.6862, +0.2387, +0.0482, -0.2509, +0.1436, +0.1807, -0.3079,
+ +0.0494, -0.3246, +0.3055, -0.0408, +0.0555, -0.3382, -0.0025,
+ -0.6834, +0.3476, -0.0030, +0.1579, +0.0862, -0.1791, +0.2797,
+ -0.1817, -0.5095, +0.1178, -0.0809, +0.0146, +0.0715, +0.2182,
+ +0.1804, -0.0511, +0.2319, +0.3272, +0.1131, -0.8983, -0.2011,
+ +0.1689, +0.1074, -0.2583, +0.1779, -0.3014, -0.6327, -0.6665,
+ -0.1555, -0.4645, +0.3818, -0.1123, -0.0006, +0.0179, -0.2749,
+ -0.2487, +0.2292, -0.4893, +0.0555, +0.0468, -0.6136, +0.5404,
+ +0.0466, +0.4146, +0.1579, -0.2530, -0.1750, +0.1629, +0.3238,
+ +0.5659, -0.0503, +0.0016, +0.2809, +0.2784, +0.1475, -0.6414,
+ +0.0670, +0.2265, -0.1811, -0.3040, -0.0546, -0.2173, -0.2576,
+ +0.0802, +0.2631, +0.0972, -0.4235, -0.2117, +0.1895, -0.0280,
+ -0.5000, +0.0190, -0.4688, -0.1146, -0.1668, -0.3957, -0.4922,
+ -0.4706, +0.0001, +0.0590, +0.2283, +0.2287, +0.1000, +0.0845,
+ -0.0947, -0.0734, +0.0261, -0.6553, +0.0896, +0.2446, -0.0348,
+ +0.0433, +0.4232, -0.0218, -0.3960, -0.5046, -0.2987, +0.0280,
+ +0.1634, +0.2381, +0.3501, -0.3088, -0.1006, -0.1233, +0.2142,
+ +0.2062, -0.1283
+ ],
+ [
+ +0.4739, -0.1162, -0.1366, +0.3816, -0.0417, +0.1261, -0.2335,
+ +0.3669, -0.2401, -0.9522, +0.2109, -0.0132, -0.1865, +0.4836,
+ +0.1055, -0.2218, -0.1196, +0.0196, -0.0025, -0.1330, +0.2417,
+ +0.1743, -0.1366, -0.0336, -0.6017, -0.1232, -0.0231, -0.5966,
+ -0.2600, +0.2885, +0.1231, -0.4905, +0.1792, +0.3717, -0.3098,
+ -0.1309, +0.0815, +0.2542, +0.4068, +0.0271, +0.5056, -0.1061,
+ +0.0995, +0.1470, +0.0906, +0.0087, -0.0164, -0.0068, +0.1400,
+ +0.0244, +0.1745, -0.5422, +0.1526, +0.2037, +0.3617, +0.0946,
+ -0.0461, +0.3309, +0.1855, +0.1393, +0.1067, -0.1586, +0.4164,
+ -0.3496, -0.0448, -0.1618, +0.1439, +0.1217, -0.1955, +0.1186,
+ -0.4702, -0.0768, +0.1980, +0.0206, -0.1104, +0.1408, +0.2186,
+ +0.2172, -0.0080, -0.5046, -0.2846, +0.2130, +0.3136, +0.1544,
+ -0.1141, -0.2175, +0.1584, +0.3487, +0.0853, -0.3997, +0.1498,
+ -0.7731, -0.3221, -0.1360, +0.1550, -0.3316, +0.2193, +0.1954,
+ +0.1046, -0.4732, +0.0718, -0.0856, +0.1472, +0.1259, +0.4658,
+ -0.9460, -0.3982, -0.2009, +0.0725, +0.0534, -0.1006, +0.1511,
+ +0.1744, -0.0355, +0.0462, +0.0833, +0.1941, +0.2094, -0.0421,
+ -0.3453, +0.0553, -0.3758, +0.4053, +0.1095, +0.3244, +0.2891,
+ +0.0966, +0.1166
+ ],
+ [
+ -0.0724, +0.1085, -0.4972, -0.0028, -0.0067, +0.0227, -0.0290,
+ -0.2167, -0.6043, +0.0365, +0.4909, -0.1674, +0.2678, +0.0223,
+ -0.3653, -0.0437, -0.1391, +0.0805, -0.1396, +0.2644, -0.1395,
+ +0.0312, -0.3119, -0.0578, -0.3483, -0.0024, +0.0221, -0.0269,
+ +0.0651, -0.4800, +0.3787, -0.7678, -0.2529, +0.1472, +0.2696,
+ +0.0188, +0.0343, +0.1721, -0.2451, -0.1120, -0.2019, -0.2884,
+ -0.6638, -0.1714, +0.2885, +0.2285, +0.0318, -0.3222, -0.3335,
+ +0.2194, -0.3422, -0.4953, +0.2280, -0.5251, -0.1215, -0.6155,
+ -0.1824, -0.5457, -0.2367, -0.3223, -0.0156, +0.1921, -0.3315,
+ +0.0449, -0.4019, -0.2108, -0.1561, +0.4559, +0.0354, +0.1694,
+ +0.1857, -0.1764, -0.1723, +0.2748, -0.4499, -0.2516, -0.2862,
+ -0.7654, +0.1760, -0.3138, +0.1232, +0.1452, -0.4399, -0.4372,
+ -0.5577, +0.4384, +0.1098, +0.2407, +0.3873, +0.2635, -0.4921,
+ +0.0278, +0.0434, -1.1753, -0.5458, -0.7957, -0.5668, +0.1613,
+ -0.4191, +0.1752, -0.0424, +0.0031, -0.1225, +0.3289, -0.2935,
+ -0.1039, -0.1187, +0.0134, -0.1290, -0.0443, -0.4428, +0.1887,
+ +0.3621, -0.5257, -0.1781, -0.4115, -0.2030, -0.0053, -0.3871,
+ +0.1769, +0.0771, +0.1107, -0.5442, +0.1559, -0.2440, +0.0977,
+ +0.0242, -0.3956
+ ],
+ [
+ -0.0798, -0.1869, -0.4505, +0.2138, +0.1049, +0.3944, +0.1550,
+ -0.0989, -0.2967, +0.0611, +0.3077, +0.1048, +0.0462, -0.2095,
+ -0.1263, +0.3146, -0.2458, -0.2668, -0.2381, +0.0026, +0.1260,
+ +0.4875, +0.0092, -0.0631, +0.1149, +0.0102, -0.2396, +0.0068,
+ -0.0141, -0.3464, +0.1864, -0.2542, -0.2427, +0.2244, -0.8746,
+ +0.2318, -0.0816, +0.0589, -0.9249, -0.0227, -0.4448, +0.0442,
+ +0.2586, -0.0237, +0.0434, +0.3148, +0.1130, -0.1757, -0.2727,
+ -0.0835, -0.8797, -0.1123, -0.2536, +0.0793, -0.0724, +0.0759,
+ -0.8041, +0.0838, +0.0876, +0.2154, +0.0597, -0.4181, +0.5480,
+ -0.0952, +0.3059, -0.1575, -0.0610, -0.1407, -0.1976, -0.1626,
+ -0.5145, +0.4673, +0.1151, +0.2068, -0.0202, -0.5073, -0.2761,
+ -0.0609, -0.0292, +0.2907, -0.0149, -0.2919, -0.0782, -0.0149,
+ +0.2524, +0.0138, +0.5132, -0.0625, -0.0648, -0.1619, +0.0246,
+ -0.4964, +0.4155, -0.1614, -0.0334, +0.2199, -0.4551, -1.1411,
+ +0.4183, -0.5659, +0.4333, -0.1543, -0.3226, +0.1156, +0.2702,
+ +0.1286, -0.1775, -0.1968, -0.0402, +0.4610, -1.0954, +0.0405,
+ +0.2891, -0.0159, -0.1103, +0.1736, +0.0364, -0.3440, -0.4703,
+ -0.0790, +0.2281, -0.0608, -0.0070, +0.1701, +0.2180, +0.2921,
+ -0.1660, -0.0240
+ ],
+ [
+ -0.1531, -0.0762, +0.2434, +0.2059, +0.0006, -0.0483, -0.0835,
+ -0.1988, +0.1489, -0.3940, -0.0165, +0.2051, -0.3440, -0.4387,
+ +0.1805, -0.0351, +0.0964, -0.2094, +0.0173, -0.1027, +0.0215,
+ -0.5647, -0.2739, -0.1528, +0.4392, +0.0523, +0.1529, +0.0308,
+ +0.0211, +0.1656, -0.0450, -0.1568, +0.0969, +0.1154, -0.3587,
+ +0.2964, -0.0999, -0.3697, +0.1148, -0.0733, -0.5812, +0.1674,
+ +0.0484, +0.2600, -0.0143, +0.0457, -0.0709, -0.0018, +0.0157,
+ -0.0339, -0.2562, -0.0362, -0.8209, -0.1456, -0.2533, +0.1077,
+ -0.0559, -0.4240, -0.0907, -0.3365, -1.1521, -0.1654, -0.1469,
+ -0.3055, -0.2623, +0.2880, +0.1382, +0.1370, +0.2796, -0.0196,
+ +0.4249, -1.0353, -0.1271, -0.4022, +0.0980, -0.0444, +0.1223,
+ -0.2851, -0.2339, +0.6282, +0.2245, -0.2938, +0.1645, -0.0032,
+ +0.2605, -0.5217, -0.1395, -0.3899, -0.1549, -0.0148, -0.3275,
+ +0.3340, -0.0451, -0.4814, -0.8078, +0.0940, -1.2753, +0.1369,
+ -0.2777, +0.1625, +0.1247, -0.1658, -0.3757, +0.3097, +0.1633,
+ -0.3481, -0.1820, +0.2435, -0.3022, -0.3967, -0.5671, -0.2281,
+ +0.0564, -0.0929, +0.0627, -0.2076, +0.1221, -0.0419, -0.0861,
+ +0.0797, -0.0192, -0.2822, -0.1680, -0.3009, -0.3804, -0.4238,
+ +0.0706, +0.1520
+ ],
+ [
+ +0.0304, -0.2949, -0.1197, -0.2498, -0.1144, +0.2134, +0.0354,
+ +0.4345, -0.1183, +0.2633, -0.0164, +0.0046, -0.2470, -0.0179,
+ -0.0765, -1.0519, +0.4042, +0.2414, -0.3601, +0.2761, -0.2936,
+ +0.2004, +0.0272, -0.3135, +0.5484, -0.2961, +0.1134, +0.1317,
+ +0.2315, -0.5105, +0.2052, +0.3595, +0.1048, -0.6679, +0.3744,
+ -0.0238, -0.3705, -0.5327, -0.4238, -0.3695, -0.3441, +0.1102,
+ -0.2174, -0.2318, +0.3524, -0.8398, +0.3412, +0.6612, -0.2882,
+ -0.1543, -0.4695, -0.5044, +0.0114, -0.2963, -0.1065, -0.4779,
+ -0.0599, -0.0249, +0.2302, +0.2725, -0.2193, -0.4488, -0.0592,
+ +0.3570, +0.3488, -0.3927, -0.8498, -0.5230, -0.2438, -0.3574,
+ +0.1329, -0.0425, -0.1903, +0.0357, +0.0999, +0.2359, -0.0484,
+ -0.1651, +0.0435, +0.3874, -0.1912, +0.3354, +0.0358, +0.0585,
+ +0.1967, +0.0366, +0.0187, -0.0461, +0.0070, +0.1871, -0.5516,
+ -0.0042, -1.0255, -0.3259, -0.0243, -0.5298, +0.2294, -0.5062,
+ -0.1477, +0.1261, -0.0510, +0.1436, +0.0660, -0.5151, +0.2660,
+ -0.5662, -0.1677, -0.8036, +0.2069, +0.1128, -1.1921, +0.2165,
+ -0.2782, -0.0133, +0.3023, +0.4483, +0.3006, +0.1258, -0.3541,
+ +0.4909, -0.5832, -0.2644, -0.5679, -0.0143, +0.4790, -0.5303,
+ -0.0335, +0.1827
+ ],
+ [
+ +0.1815, -0.0401, +0.5799, -0.1930, -0.1426, +0.2715, -0.2027,
+ -0.4024, +0.1903, -0.2936, -0.1695, +0.1541, +0.0735, +0.1619,
+ +0.2111, -0.2971, +0.1040, -0.2205, +0.0246, +0.3006, +0.0952,
+ -0.0275, -0.0447, +0.1255, -0.0167, -0.3038, +0.0067, +0.0918,
+ +0.4534, +0.3729, +0.2850, +0.3374, -0.4727, -0.1795, -0.1843,
+ -0.7887, -0.1064, +0.3617, +0.4538, -0.4319, +0.5354, +0.2161,
+ +0.0345, -0.0433, +0.3310, -0.3595, +0.2615, -0.0568, +0.0303,
+ +0.3004, +0.0770, -0.2452, -0.6659, -0.5601, -0.2301, -0.0998,
+ +0.0636, -0.1085, +0.1295, -0.0602, +0.0307, -0.0612, +0.1105,
+ -0.0609, +0.1408, -0.2544, -0.6422, -0.0406, +0.2392, +0.0856,
+ -0.2494, -0.0096, -0.0540, +0.0659, -0.1719, -0.1073, -0.2555,
+ -0.2760, -0.4249, -0.0601, +0.2513, +0.1583, -0.1241, +0.1113,
+ -0.5371, -0.0592, -0.3068, -0.5263, +0.1182, -0.1418, -0.6853,
+ -0.5592, -0.8657, -0.0064, +0.1229, -0.6746, +0.0328, -0.5248,
+ +0.0427, +0.0597, +0.0565, +0.1423, +0.0662, -0.1197, +0.0264,
+ +0.4936, -1.0516, -0.4423, -0.1124, +0.0092, -0.2064, -0.8563,
+ -0.3046, -0.4646, -0.0318, +0.1897, +0.3785, +0.4474, +0.1881,
+ -0.2840, -0.1618, +0.0267, -0.0722, -0.1734, -0.2372, -1.1021,
+ -0.7337, +0.1509
+ ],
+ [
+ -0.6447, +0.3449, -0.9011, -0.2403, -0.0744, -0.1438, +0.2014,
+ -0.3920, -0.2266, +0.0825, -0.3074, -0.4425, -0.0174, -0.3714,
+ -1.7478, -0.1300, +0.1309, -0.2163, -0.6222, +0.5497, -0.1621,
+ -0.6566, +0.0829, -0.3938, +0.2074, -0.0513, +0.2233, -0.6168,
+ -0.0091, -0.1450, +0.3245, +0.1645, -0.2045, -0.1519, +0.8124,
+ +0.1053, -0.2874, -0.5231, -0.2111, -0.2046, -0.3640, -1.6102,
+ -0.0478, +0.2372, -0.3473, -0.2914, -0.2621, -0.0857, -0.4149,
+ -0.5113, -1.0806, +0.1913, +0.0824, -0.1712, -0.3389, -0.9758,
+ -0.2708, +0.1427, -1.3125, -0.7610, -1.1084, +0.0959, -0.3895,
+ -0.0990, +0.2630, -0.2732, +0.5443, -0.6141, +0.0143, -0.2621,
+ +0.5494, +0.5633, -0.0835, -1.4201, -0.0531, -0.0703, -0.5871,
+ -0.1776, -0.6265, -0.1685, -0.5413, -1.0861, +0.2029, -0.2093,
+ +0.5018, +0.3682, +0.0130, -0.4049, -0.2864, -0.5180, -0.3193,
+ -0.2385, +0.1110, -0.1328, -0.9537, -0.4612, -0.8338, +0.2002,
+ +0.5781, -0.5692, +0.0020, +0.4453, -0.5529, +0.0276, -0.3348,
+ +0.6694, -0.0618, -0.0625, +0.1663, +0.3807, -0.7775, +0.0974,
+ +0.1139, +0.1578, -0.4627, -0.4537, +0.2381, -0.0858, +0.0478,
+ -0.2309, -0.3844, +0.1591, -0.2309, -0.0848, -0.4875, -0.2816,
+ -0.1464, +0.3074
+ ],
+ [
+ +0.0608, -0.1224, -0.6330, -0.1259, +0.4083, -0.1106, -0.0339,
+ -0.3438, +0.4411, -0.1641, -0.0177, +0.1939, -0.3302, -0.3217,
+ +0.1455, -0.0684, +0.0289, -0.3108, -0.3304, -0.3683, -0.4343,
+ -0.2011, +0.0423, +0.2278, -0.4396, +0.0042, -0.4049, +0.4562,
+ -0.2658, +0.5984, -0.1613, -0.0498, -0.1887, -0.1891, +0.2460,
+ -0.0120, +0.3477, +0.3723, +0.1210, +0.9048, -0.6516, -0.4915,
+ +0.5168, +0.0967, +0.0134, -0.4125, -0.1386, -0.4876, +0.0348,
+ +0.2497, -0.2787, +0.0328, +0.2342, +0.4503, +0.4376, +0.3408,
+ -0.2701, -0.0179, -0.3997, -0.4566, -0.6290, +0.0888, -0.0180,
+ -0.4430, -0.2944, -0.1129, +0.1297, -0.2416, -0.1129, -0.0031,
+ -0.1250, -0.0975, -0.3855, -0.2048, +0.3220, -0.2710, -0.3520,
+ -0.3234, +0.0636, +0.4856, -0.1456, -0.0888, -1.0173, -0.3701,
+ +0.0300, -0.4591, +0.1676, -0.1109, -0.0447, -0.0134, -0.1801,
+ -0.2803, -0.5276, +0.0692, -0.3301, -0.5713, -0.4566, -0.0351,
+ +0.3655, +0.0301, -0.3156, -0.0812, -0.3689, -0.1990, -0.3871,
+ +0.6426, -0.0287, -0.1836, +0.3070, +0.2296, +0.0925, -0.5309,
+ -0.2213, -0.1056, +0.2159, -0.0555, +0.5778, -0.1754, +0.2780,
+ -0.2772, +0.0251, +0.3355, -0.2899, -0.0700, +0.1763, +0.2300,
+ +0.1414, -0.4682
+ ],
+ [
+ -0.2827, +0.2157, +0.1368, +0.0241, -0.1796, -0.2885, -0.3154,
+ +0.2077, -0.0781, -0.3434, +0.1631, +0.2726, -0.0359, -0.1775,
+ -1.2394, -0.2690, -0.5155, +0.0391, -0.0500, +0.1368, -0.0134,
+ -0.1563, +0.1046, -0.1969, -0.2891, +0.0316, -0.2012, +0.3028,
+ -0.0851, -0.3458, -0.7299, -0.2510, +0.4461, +0.2600, +0.3267,
+ +0.0790, -0.1682, -0.1931, -0.0799, +0.2881, -0.5884, +0.0632,
+ +0.3180, -0.3941, +0.1914, +0.5623, +0.3005, +0.0005, -0.0287,
+ -0.2098, +0.0567, -0.6083, -0.5947, -0.5355, -0.4706, +0.4109,
+ +0.1546, +0.0628, -0.5879, -0.5762, -0.4205, -0.1880, -0.6307,
+ +0.3561, +0.3985, -0.5811, +0.3369, +0.2780, +0.0391, -0.3813,
+ +0.0994, +0.3831, +0.1480, +0.0737, -0.2445, +0.0227, -0.0794,
+ -0.0114, -0.5846, -0.3964, -0.0213, -0.4718, -0.8218, +0.0227,
+ -0.1789, +0.1025, -0.2074, -0.0989, +0.4805, +0.1240, -0.2949,
+ +0.2676, -0.0070, -0.1780, -0.1916, -0.1816, -0.3574, +0.0061,
+ +0.1938, -0.0771, -0.1268, -0.3721, +0.0112, -0.4341, +0.0241,
+ -0.1961, -0.0148, -0.1895, +0.2493, -0.1105, -0.0807, -0.0370,
+ +0.4592, +0.6299, +0.1287, +0.3238, +0.1459, +0.3146, -0.0258,
+ +0.4083, -0.1598, -0.1403, -0.4425, -0.0246, +0.1522, -0.1340,
+ -0.0754, +0.0788
+ ],
+ [
+ +0.1139, -0.1473, +0.0625, -0.2686, -0.1878, +0.1209, +0.1643,
+ -0.6718, -0.2045, -0.2222, -0.8136, -0.0653, -0.2586, +0.0177,
+ -0.6514, -0.4516, +0.0916, -0.3649, -0.2173, +0.2538, -0.5378,
+ +0.2946, +0.3534, +0.3872, +0.1299, -0.0175, +0.3286, +0.0112,
+ +0.1354, +0.4912, +0.4418, +0.3883, -0.0243, -0.0846, -0.3096,
+ +0.1244, -0.4983, +0.0288, -0.8007, -0.1267, +0.0108, +0.1520,
+ -0.2865, +0.4799, -0.3412, -0.2733, -0.4696, +0.6912, +0.0983,
+ +0.0998, +0.2374, -0.1982, +0.2253, +0.1817, -0.2972, -1.1327,
+ -0.0503, +0.0064, +0.3198, -0.3973, -1.0132, +0.0144, +0.1239,
+ -0.3439, +0.3481, -0.1054, -0.1642, -0.3204, +0.2265, -0.6322,
+ -0.6049, +0.0105, +0.2317, +0.0861, -0.5469, +0.3185, +0.3799,
+ +0.2897, -0.1284, +0.1114, +0.0065, -0.2713, -0.1795, +0.2296,
+ +0.2176, +0.0355, -0.1739, -0.2801, +0.1071, -0.3920, +0.1264,
+ +0.1638, -0.6773, -0.2767, -0.4543, -0.1426, -0.0279, -0.0029,
+ -0.2080, -0.3354, +0.3200, -0.2031, -0.0694, +0.2044, +0.1851,
+ -0.0066, +0.3423, +0.3267, +0.2141, -0.1742, +0.3827, -0.0116,
+ +0.2795, +0.3505, -0.6727, +0.0667, -0.1962, +0.1275, -0.3322,
+ +0.1561, +0.2273, -0.7180, -0.4079, -0.6132, -0.8328, -0.0139,
+ -0.0531, +0.0699
+ ],
+ [
+ -0.2162, +0.3650, -0.0775, +0.1286, +0.2833, -0.2686, +0.2269,
+ +0.1891, +0.5902, +0.0766, -0.5377, -0.4029, +0.3113, -1.0276,
+ -0.5917, -0.0088, -0.0177, +0.3982, -0.8924, +0.0721, +0.0778,
+ +0.4037, -0.1173, -0.1329, -0.2413, +0.1995, -0.2764, +0.2759,
+ -0.0765, -0.0474, +0.4479, +0.0464, +0.0024, +0.2887, +0.2408,
+ -0.2897, -0.5199, -0.3479, +0.0651, -0.0846, -0.5294, -0.3773,
+ -0.3503, +0.0261, -0.0676, -0.6216, +0.3592, +0.1187, +0.1490,
+ -0.1143, +0.1841, -0.0096, -0.5919, +0.3378, -0.8474, -0.9084,
+ +0.0227, -0.7069, -0.0190, -0.9554, -0.5866, +0.2025, -0.2729,
+ +0.1888, -0.4473, -0.1897, -0.1489, -0.0217, +0.1219, -0.3593,
+ +0.0485, +0.2373, +0.2032, +0.5618, -0.2778, -0.4513, +0.1367,
+ +0.2175, -0.0878, -0.2160, -0.0099, -0.1469, -0.2830, +0.3326,
+ -0.3476, +0.0601, -0.2457, +0.2154, -0.4680, -0.3028, -0.0916,
+ +0.1164, -0.0634, -0.4959, -0.2114, +0.2425, +0.0475, +0.2571,
+ -0.0876, +0.0062, -0.4116, +0.4813, -0.1849, -0.0425, +0.0471,
+ -0.4631, -0.7976, +0.2002, -0.1408, +0.2919, +0.0119, -0.5573,
+ +0.3390, +0.4550, -0.3039, -0.1137, +0.2137, -0.0528, -0.6604,
+ -0.0976, +0.3270, -0.0922, -0.2643, -0.4038, -0.3013, -0.1558,
+ -0.1576, -0.3229
+ ],
+ [
+ +0.1884, +0.1581, -0.1678, -0.1605, -0.0788, -0.2348, -0.2711,
+ +0.0234, +0.1463, -0.4431, -0.4578, -0.1051, +0.1719, +0.0025,
+ +0.2520, -0.1683, -0.5398, -0.5436, -0.5340, -0.3022, +0.0653,
+ +0.2823, +0.3645, -0.2714, -0.0326, +0.2143, +0.1475, +0.3053,
+ -0.4027, +0.1658, +0.2754, -0.0655, -0.5440, -0.1419, +0.0892,
+ -0.2852, -0.4614, +0.0123, +0.2066, +0.4549, -0.3081, -0.7535,
+ -0.2124, -0.4547, -0.3026, +0.3357, -0.6742, +0.1423, -0.3012,
+ +0.0458, -0.9311, -0.7505, -0.1701, +0.2159, -0.1285, +0.2552,
+ -0.4995, -0.0120, -0.1738, +0.1413, +0.0009, -0.6367, -0.2474,
+ +0.3341, -0.3521, +0.1533, +0.2673, +0.0852, -0.2343, -0.0740,
+ +0.1619, -0.0412, -0.1895, -0.1293, +0.0769, +0.0521, -0.1532,
+ -0.2426, +0.1172, -1.5164, +0.0624, -0.3847, +0.1773, -0.1819,
+ -0.6927, -0.3207, +0.1571, +0.1593, -0.1427, +0.3353, +0.5158,
+ +0.0365, +0.0112, +0.3568, +0.1530, +0.1749, -0.7890, -0.1237,
+ -0.3425, -0.5343, -0.1073, -0.0057, +0.4587, +0.0027, -0.0265,
+ -0.3313, +0.0943, -0.2787, -0.3268, -0.3629, -0.1698, -0.0133,
+ -0.0167, -0.5999, -1.1855, +0.2669, -0.1889, +0.2187, +0.3723,
+ -0.5664, +0.0426, +0.0538, +0.6252, +0.0166, +0.2159, +0.1125,
+ +0.4596, +0.0911
+ ]])
-weights_final_w = np.array([
-[ -0.0500, +0.0520, -0.1401, +0.2030, -0.3231, +0.0144, -0.1040, +0.2029, -0.1153, -0.1412, -0.0326, +0.0192, +0.0153, +0.1157, -0.2278, +0.0663, -0.0588],
-[ -0.1934, +0.1167, +0.0131, +0.0005, -0.0056, +0.2003, +0.0647, +0.0407, +0.1506, +0.0205, -0.2231, -0.1559, -0.2919, +0.0398, +0.0346, +0.0151, -0.0333],
-[ -0.5131, +0.0469, -0.0589, -0.2056, -0.0316, +0.1800, -0.1217, -0.1480, +0.1785, +0.0261, -0.1138, -0.1974, +0.2588, -0.0282, -0.0632, +0.2111, -0.2802],
-[ +0.0465, -0.2210, +0.1704, -0.4249, -0.0303, -0.1091, +0.0872, -0.1461, -0.0034, +0.2490, -0.2206, -0.0736, +0.0300, -0.0700, -0.1995, +0.3273, -0.1255],
-[ +0.0426, +0.3676, -0.1660, -0.0894, +0.0383, -0.0723, +0.0043, -0.0986, -0.0594, -0.0239, -0.0395, +0.0166, +0.1111, -0.0135, +0.0101, -0.1226, +0.0468],
-[ -0.1512, -0.0761, +0.2163, +0.0025, +0.1200, +0.1947, -0.2594, -0.1264, +0.0708, -0.0100, +0.2345, +0.1272, +0.0181, +0.0598, +0.0196, +0.0544, +0.0077],
-[ -0.0479, +0.0877, -0.1959, +0.2171, +0.1391, -0.0882, +0.1955, -0.0043, +0.0778, -0.0865, +0.0036, +0.0395, -0.0664, -0.0722, -0.0999, +0.0403, +0.0459],
-[ -0.1554, -0.0621, +0.0832, +0.0046, -0.1666, -0.0623, -0.0754, -0.1921, -0.0802, +0.1742, -0.3199, +0.2225, -0.0935, -0.0165, -0.1373, -0.1331, +0.1116],
-[ +0.1641, +0.0611, -0.0527, -0.0480, +0.1270, -0.0116, -0.1430, -0.2651, +0.0744, +0.1591, -0.0271, -0.1597, +0.0145, -0.0970, -0.0396, +0.0642, -0.1355],
-[ -0.1786, +0.1061, -0.0170, +0.2049, -0.0101, -0.0016, +0.1681, +0.2846, +0.0429, +0.0779, -0.0644, +0.2227, +0.0480, -0.0613, -0.1086, +0.0909, +0.0695],
-[ -0.1132, -0.0676, +0.0076, +0.1158, -0.0424, -0.0585, +0.0658, -0.1111, -0.0105, +0.1243, -0.1272, -0.1166, -0.1396, -0.0158, +0.2221, -0.5519, +0.0056],
-[ -0.2191, +0.0914, -0.2542, -0.0066, -0.1819, -0.0521, +0.0304, +0.0955, +0.0114, +0.1190, +0.1209, -0.1486, -0.2386, +0.0012, +0.0523, -0.0173, -0.0888],
-[ +0.1867, +0.1779, +0.1244, +0.0109, +0.0969, +0.0768, -0.3619, -0.0457, +0.1208, -0.0982, +0.0409, -0.1705, -0.0508, -0.0835, +0.1529, -0.0571, -0.1034],
-[ -0.1137, -0.2575, +0.0101, -0.4039, -0.1796, -0.2636, +0.1259, +0.0388, +0.1942, -0.0287, +0.2606, -0.0823, -0.0069, +0.1304, +0.4204, +0.0883, -0.1248],
-[ -0.2387, +0.1436, -0.1701, +0.2502, +0.0021, +0.0202, +0.1469, -0.1469, +0.1600, -0.0124, +0.0876, -0.1535, +0.4238, -0.0717, +0.3870, +0.4299, -0.1141],
-[ +0.2502, +0.1630, +0.0301, -0.1261, +0.1486, -0.1277, -0.0184, -0.1144, -0.0368, +0.1179, -0.1200, -0.1448, -0.1146, -0.0880, +0.3904, -0.0074, +0.1483],
-[ -0.2122, +0.1499, -0.0626, -0.0072, +0.0174, -0.1730, +0.0620, -0.1867, +0.0511, -0.0842, -0.2439, -0.0841, -0.0805, +0.1795, -0.0691, -0.2461, +0.1777],
-[ +0.0065, +0.2415, +0.1155, -0.2030, +0.0613, +0.2977, -0.0146, +0.0042, +0.1047, -0.1538, -0.0089, -0.1895, +0.0561, -0.0879, +0.0143, -0.0559, -0.0890],
-[ -0.1464, -0.0184, +0.1731, +0.0010, +0.0459, -0.0302, -0.0838, -0.1482, +0.1891, -0.0848, +0.0385, -0.0858, -0.3817, -0.0695, -0.2484, -0.3315, -0.0779],
-[ -0.1571, -0.1686, -0.0109, -0.0342, -0.0847, -0.1510, -0.0678, -0.0963, +0.0833, +0.1933, +0.3233, -0.0954, +0.0170, -0.1014, +0.0558, -0.1237, -0.0068],
-[ +0.1069, -0.2466, -0.1261, +0.2319, -0.0456, +0.0744, -0.0796, +0.0739, +0.1059, +0.0330, -0.1405, +0.1594, -0.2326, -0.1312, +0.1011, +0.0532, -0.0480],
-[ -0.3261, -0.3612, +0.4744, +0.1766, -0.2084, +0.0832, +0.0138, -0.1178, -0.1055, -0.0774, +0.1118, +0.1659, +0.2805, -0.2790, -0.4162, -0.1110, -0.0465],
-[ -0.0609, +0.0663, -0.1358, +0.2174, +0.1067, +0.0559, -0.0523, -0.0194, +0.2576, +0.0302, -0.0394, -0.0745, -0.0917, -0.0268, -0.0366, +0.0958, +0.0342],
-[ +0.0260, -0.1912, -0.2794, -0.2077, +0.0565, +0.0009, -0.0691, -0.0750, -0.0582, +0.0129, -0.0717, -0.1249, -0.0442, +0.0543, -0.0696, +0.0801, +0.0080],
-[ +0.0147, +0.1115, -0.2710, +0.0096, -0.1212, +0.1514, -0.0183, -0.0714, +0.2782, -0.1610, +0.1000, +0.0025, +0.0322, +0.0412, -0.1214, +0.1739, -0.0345],
-[ -0.1663, -0.0534, -0.0607, +0.2529, +0.0435, +0.0024, -0.1550, +0.2743, +0.0510, +0.0220, +0.1415, -0.1839, +0.1584, +0.0849, +0.0793, +0.3077, -0.0912],
-[ +0.1709, +0.0804, +0.0473, +0.1288, +0.0029, +0.1389, +0.2928, +0.0363, -0.0596, -0.0483, +0.3041, -0.0522, -0.0675, +0.0609, -0.0559, -0.0244, +0.0003],
-[ -0.1667, +0.1194, +0.1725, +0.0877, -0.1228, -0.0480, -0.0474, -0.0550, +0.1146, +0.0949, +0.0477, -0.4471, -0.3624, -0.0280, -0.0140, -0.1358, -0.0709],
-[ +0.0310, -0.0247, +0.1299, -0.0083, +0.1510, -0.0586, -0.0757, +0.0686, +0.2878, -0.0194, -0.0216, +0.0047, +0.1680, +0.0598, -0.2225, -0.0494, -0.0765],
-[ +0.1092, -0.3239, +0.1943, -0.0899, -0.0506, +0.1235, +0.0486, +0.0174, +0.0141, -0.0921, +0.1887, +0.0339, +0.1610, -0.0140, -0.1033, +0.1223, -0.0155],
-[ -0.0277, +0.0191, +0.0459, +0.0300, +0.1183, -0.0972, +0.3191, +0.1737, +0.1869, +0.0644, +0.0507, -0.0121, -0.0506, +0.0448, -0.1096, -0.0081, -0.0789],
-[ -0.2677, +0.1532, +0.0895, -0.0466, -0.0054, +0.0569, +0.0022, -0.3044, +0.1862, -0.2223, -0.0157, +0.0559, +0.0186, -0.0800, -0.1146, +0.3398, -0.1068],
-[ +0.0242, -0.0935, +0.0429, -0.0115, +0.2126, +0.0859, +0.0020, -0.1650, +0.1600, -0.0348, -0.1426, -0.0212, +0.0662, +0.0819, -0.2960, -0.0660, -0.0242],
-[ -0.0361, -0.0494, +0.0313, +0.1553, +0.0623, -0.1620, +0.2842, +0.0104, -0.1632, +0.1637, +0.2602, -0.2550, -0.0172, -0.0868, -0.1758, +0.0689, +0.0731],
-[ +0.0089, +0.3266, -0.2115, +0.1473, +0.0423, +0.0773, +0.1420, +0.2675, -0.0000, +0.1361, -0.4133, +0.0742, +0.0148, +0.2438, -0.0297, +0.0726, +0.0325],
-[ -0.1394, +0.0096, -0.1679, +0.1894, +0.0730, +0.0572, -0.2028, +0.0843, -0.0058, -0.1014, +0.1447, -0.0080, -0.1056, -0.0686, +0.0299, +0.0535, +0.0238],
-[ -0.0404, +0.0493, -0.0139, +0.0949, +0.0198, +0.1132, -0.0484, +0.0609, +0.2326, +0.2329, -0.3538, +0.0420, +0.0020, +0.1391, +0.0121, -0.1743, +0.0309],
-[ -0.0571, -0.0159, -0.3700, +0.0511, +0.3797, -0.1085, +0.0214, +0.1002, -0.0533, -0.0098, -0.1695, +0.0261, -0.0258, -0.0383, -0.0943, -0.0375, -0.0874],
-[ -0.2690, +0.3889, -0.1825, -0.2502, +0.3067, +0.2693, -0.0415, -0.2989, -0.0810, -0.2701, -0.0876, +0.1370, +0.0814, +0.1991, +0.1026, -0.3468, +0.0540],
-[ +0.0901, +0.1083, +0.0109, +0.3720, -0.1897, -0.1353, -0.0002, -0.0120, -0.1493, -0.0239, +0.0070, -0.2525, -0.2358, -0.0631, +0.1656, +0.1604, +0.0500],
-[ +0.3311, -0.0797, +0.0255, -0.1776, +0.0926, +0.1546, +0.0071, -0.0737, -0.2305, +0.0552, -0.0238, +0.2687, -0.3520, -0.1743, +0.0424, -0.0234, -0.1280],
-[ -0.1053, -0.0652, +0.2033, +0.1009, +0.1072, +0.2026, -0.0444, +0.0543, -0.0881, -0.4387, +0.0020, -0.0239, -0.2309, -0.0730, +0.1919, -0.0019, -0.1239],
-[ +0.1863, -0.1390, -0.0368, +0.1796, -0.1910, +0.0543, -0.3425, +0.1458, +0.0116, +0.1308, +0.1313, +0.1098, -0.0819, +0.0199, -0.1105, -0.0217, +0.0668],
-[ -0.1977, -0.2812, -0.0967, +0.2061, -0.0280, -0.1759, +0.0672, +0.1179, +0.0423, +0.1185, +0.0052, +0.1873, -0.0213, +0.0987, +0.1273, -0.0343, +0.0754],
-[ -0.1596, +0.0493, +0.2797, +0.0854, +0.1617, +0.0723, +0.1626, +0.1054, -0.0487, +0.0097, -0.0439, -0.1232, +0.1922, -0.0277, +0.0119, +0.1730, +0.1012],
-[ +0.0703, +0.1970, +0.0967, +0.0519, -0.0242, -0.0490, +0.1296, +0.1286, +0.2053, -0.0337, +0.0747, +0.2130, -0.0591, +0.0786, +0.1569, -0.1778, +0.0426],
-[ +0.1670, -0.0426, +0.0293, +0.0224, +0.0965, +0.2378, +0.1234, -0.0270, +0.0717, +0.0657, +0.1491, +0.1309, -0.0047, +0.1014, -0.0419, -0.3916, +0.1701],
-[ -0.1341, -0.0447, -0.0123, -0.0296, -0.5153, -0.0471, +0.0095, -0.0265, -0.0487, -0.1160, -0.1601, +0.2510, +0.2775, -0.0465, +0.1130, -0.0542, +0.1162],
-[ -0.0102, -0.1284, +0.1419, -0.0311, +0.0061, -0.1030, +0.0771, -0.1695, -0.0464, +0.1868, -0.2451, -0.2036, -0.0334, +0.0034, +0.0619, +0.1707, -0.0432],
-[ +0.1202, +0.0824, -0.0883, -0.0337, +0.2071, -0.3426, -0.1190, +0.1154, +0.0478, +0.3089, +0.2514, -0.0086, -0.0398, +0.0412, +0.0666, +0.0843, -0.0302],
-[ -0.0201, +0.0295, -0.0884, -0.0905, +0.1772, +0.0316, +0.0128, -0.5102, +0.2854, +0.0869, -0.0243, -0.2130, +0.1952, +0.1135, -0.1489, -0.1426, -0.1163],
-[ +0.0725, +0.2234, -0.1540, -0.2566, -0.0715, +0.1212, -0.1259, -0.0770, +0.0403, +0.0321, +0.1270, +0.3933, -0.2743, +0.1460, +0.0257, +0.0532, +0.0935],
-[ +0.0539, -0.0206, +0.1057, -0.0783, +0.0933, +0.1618, -0.0672, -0.0393, +0.0656, +0.0044, +0.2199, -0.1817, -0.0652, -0.1396, +0.3507, -0.1025, +0.0075],
-[ -0.2804, -0.1096, +0.0919, -0.1097, -0.0635, +0.0266, +0.1040, -0.2046, +0.1255, +0.1206, -0.0410, -0.0632, -0.0094, -0.0336, +0.0988, +0.2421, +0.0582],
-[ +0.0741, -0.0379, -0.1480, -0.0401, -0.0145, +0.0121, -0.0270, +0.1328, +0.0768, +0.1763, +0.0653, +0.2162, +0.1625, -0.0759, -0.2528, -0.0400, -0.0609],
-[ -0.0612, -0.1351, +0.1460, +0.0407, -0.1009, +0.1307, -0.2049, -0.2043, +0.1486, +0.0571, +0.0194, +0.1111, +0.0900, -0.1686, +0.2435, +0.0025, -0.0025],
-[ +0.1537, -0.0991, +0.0023, +0.0866, +0.1233, +0.0192, +0.0099, +0.0112, -0.1178, -0.0302, +0.1665, -0.1938, +0.0973, +0.0237, -0.0594, -0.2662, +0.0543],
-[ -0.0866, +0.0235, -0.4950, -0.2234, -0.3568, +0.1504, -0.3272, -0.2139, -0.0608, -0.2261, +0.3710, -0.0093, +0.2967, +0.4035, -0.1705, -0.1567, -0.1671],
-[ +0.2094, +0.2050, -0.2027, -0.3216, -0.0898, -0.3793, +0.1276, -0.2629, -0.2257, -0.0036, -0.1710, +0.0087, -0.1903, +0.0476, -0.4685, -0.0350, +0.0185],
-[ +0.0761, -0.1583, -0.2297, -0.1768, -0.0385, -0.0560, -0.2828, +0.1289, +0.2082, -0.0280, +0.2047, -0.0699, -0.0760, +0.0177, +0.0795, -0.2414, -0.0863],
-[ +0.0051, -0.0159, +0.3049, -0.1012, +0.2151, +0.0903, -0.0857, +0.2459, -0.0574, -0.1813, -0.0363, +0.2777, +0.1517, -0.2497, -0.1926, -0.2714, -0.1205],
-[ -0.0313, -0.1017, +0.1731, +0.1876, +0.1274, -0.0242, -0.0131, +0.2359, -0.0604, -0.0337, +0.2364, -0.1355, -0.0705, +0.3669, -0.1421, +0.1863, +0.0562],
-[ -0.0262, -0.0691, +0.0511, +0.2557, -0.0593, +0.0052, +0.2013, +0.2306, -0.1830, +0.1198, +0.1838, +0.5372, +0.1109, +0.0263, -0.1590, +0.1215, -0.0652],
-[ -0.0851, +0.2184, +0.0468, +0.0364, +0.0370, -0.0666, +0.0343, -0.1203, +0.0828, +0.1937, -0.1424, +0.0270, +0.4887, +0.0595, +0.3850, -0.1007, -0.1618],
-[ -0.0647, -0.0491, -0.1482, -0.0725, +0.1533, -0.0067, -0.0163, -0.2621, +0.4495, -0.0230, -0.1823, -0.2028, +0.0139, +0.0228, -0.0210, +0.1549, +0.0272],
-[ +0.0583, +0.1002, -0.2269, -0.1197, +0.2894, -0.0435, +0.1308, -0.0852, +0.3371, +0.1352, -0.0481, +0.4537, +0.2147, -0.0701, +0.1391, -0.0899, -0.0713],
-[ -0.1840, -0.3356, -0.0079, +0.1192, -0.3029, -0.0518, -0.2026, +0.3101, -0.2164, -0.1004, +0.0849, -0.2748, +0.3760, -0.0042, +0.3993, +0.4109, -0.0759],
-[ -0.0964, -0.1880, -0.0638, -0.0073, +0.0270, -0.1475, +0.1412, +0.0414, -0.1057, -0.1715, +0.1548, -0.0673, +0.1397, -0.0826, +0.1504, -0.0542, +0.0261],
-[ -0.0436, +0.0176, -0.2640, -0.0555, +0.0581, +0.0930, +0.1484, +0.1862, +0.0059, -0.0723, +0.0217, -0.0897, +0.1173, +0.0441, +0.2001, +0.2820, +0.0056],
-[ +0.0250, -0.0386, -0.0329, +0.0484, +0.0093, +0.0156, +0.0280, -0.0594, -0.1825, +0.1148, -0.1595, -0.0615, -0.0671, +0.1472, +0.1153, +0.0946, -0.1374],
-[ +0.1758, +0.1463, -0.0741, -0.2125, +0.1636, -0.0032, -0.0480, +0.2846, -0.1297, +0.0617, -0.0237, +0.0512, +0.1992, +0.1058, +0.3484, +0.0708, +0.1671],
-[ +0.2952, -0.0091, -0.0190, -0.0003, +0.1044, -0.0487, +0.3075, +0.0950, -0.1509, +0.1373, -0.2803, +0.1419, +0.2875, +0.0242, +0.0065, -0.0936, +0.0162],
-[ +0.1659, +0.1577, +0.1013, -0.1512, +0.1424, +0.2053, +0.1997, +0.1179, -0.1882, -0.2216, -0.2507, +0.1068, -0.1726, +0.0142, +0.2472, +0.3217, -0.0999],
-[ +0.0972, +0.1773, +0.0982, +0.0548, -0.0945, +0.1250, +0.0022, -0.0743, -0.3627, -0.0801, +0.1161, +0.2369, +0.1528, -0.0622, -0.0397, -0.1468, -0.1702],
-[ +0.1908, +0.0306, +0.0756, -0.0095, -0.1140, +0.2149, -0.2536, +0.0192, -0.1244, -0.0219, -0.0060, +0.0286, +0.1742, +0.0430, +0.0622, +0.0760, +0.0211],
-[ -0.2068, -0.0279, +0.1215, +0.1463, -0.0032, -0.0667, -0.0069, +0.0322, -0.1577, +0.0497, +0.0793, +0.0504, +0.2050, +0.0459, +0.0586, -0.0467, +0.0756],
-[ -0.0050, -0.1217, +0.1720, -0.0497, +0.2169, +0.0608, -0.0893, +0.2269, -0.1392, +0.0636, -0.0461, +0.0243, -0.3206, +0.1114, -0.2682, -0.1793, +0.0532],
-[ -0.0919, -0.1976, +0.0794, +0.0269, +0.1282, -0.0851, +0.0248, +0.1133, +0.0308, -0.1318, -0.2297, -0.0558, -0.2465, -0.0534, -0.0406, +0.1037, +0.2015],
-[ -0.1945, +0.1965, +0.0724, -0.1509, +0.1594, -0.2093, +0.0466, -0.1090, +0.0338, -0.0269, -0.0978, +0.2136, -0.3288, -0.0004, -0.0335, +0.0991, -0.1539],
-[ +0.3684, +0.0830, +0.1588, +0.3764, +0.1412, -0.1288, -0.1443, +0.0388, +0.0819, +0.1563, -0.0173, +0.0067, +0.2200, +0.1175, +0.0211, +0.0056, +0.0099],
-[ +0.1937, -0.1604, -0.2249, -0.1253, -0.2346, -0.6112, -0.3301, +0.0008, +0.0128, +0.2471, +0.3018, -0.1123, -0.0536, -0.0060, -0.2138, -0.0642, -0.0224],
-[ -0.0750, +0.0249, +0.2450, -0.1484, -0.0077, -0.1160, +0.1432, +0.0341, -0.0626, -0.0306, +0.0240, -0.1328, +0.2852, +0.1698, -0.1014, -0.1040, -0.0586],
-[ -0.1895, +0.0789, -0.1464, +0.1532, +0.0039, -0.1385, +0.1615, +0.1964, +0.2573, +0.1177, +0.0378, +0.2443, +0.3998, -0.0943, -0.4698, +0.0102, +0.2408],
-[ -0.0270, -0.0811, -0.0578, +0.2961, +0.0481, +0.0643, -0.0719, +0.0192, +0.0965, -0.1667, +0.0554, -0.0081, -0.0330, +0.1145, +0.1502, -0.2212, -0.0304],
-[ +0.0547, -0.0325, +0.0254, -0.0844, +0.4001, -0.0142, +0.0167, -0.0836, +0.0950, -0.1405, +0.0599, +0.1493, +0.0871, +0.1385, -0.0614, -0.0024, -0.0119],
-[ -0.1367, +0.1318, -0.1068, +0.0860, -0.3123, +0.1001, +0.3291, -0.2463, -0.0354, -0.1765, +0.1861, +0.0849, +0.2081, +0.1625, -0.1385, -0.0860, -0.0052],
-[ -0.0067, +0.2718, -0.0711, +0.0202, +0.0372, -0.1661, +0.0658, +0.0383, -0.1041, -0.1056, +0.2210, +0.0247, -0.0011, -0.1070, -0.0103, +0.2565, -0.0143],
-[ -0.0009, +0.2050, +0.2110, -0.1294, -0.0535, +0.0716, -0.0756, +0.1513, -0.0375, -0.0890, +0.1466, +0.2619, -0.0011, -0.1757, +0.1141, +0.0407, -0.0847],
-[ -0.0193, -0.1029, +0.1858, +0.0139, +0.2608, -0.0146, +0.0154, +0.0489, -0.1093, +0.0104, -0.2219, +0.0648, -0.0656, -0.0877, +0.0203, -0.0899, -0.0903],
-[ -0.0886, +0.1405, -0.3229, +0.1365, -0.0121, +0.0062, -0.0392, -0.0051, +0.1538, +0.2586, -0.0580, +0.1502, -0.0022, -0.0271, -0.0936, -0.4547, +0.0754],
-[ +0.3475, +0.0164, -0.2164, +0.0795, -0.0293, +0.1575, +0.0395, -0.4194, +0.0051, -0.0399, +0.1034, +0.3149, -0.0858, -0.1606, -0.0197, -0.0434, -0.0950],
-[ +0.1236, -0.0872, -0.2009, +0.3143, +0.1047, +0.0123, -0.1373, -0.0199, +0.0415, -0.0361, +0.4936, +0.1017, +0.0232, -0.2103, -0.0957, -0.1162, +0.0018],
-[ -0.0303, +0.2271, +0.2671, -0.1139, +0.0505, +0.0459, +0.0181, -0.0978, +0.0442, +0.0428, -0.0411, +0.1537, -0.2310, -0.0133, +0.0393, +0.2811, +0.0302],
-[ +0.0180, -0.2184, -0.0850, -0.1738, -0.1618, +0.0298, -0.0198, +0.3145, -0.1872, -0.0837, -0.0753, -0.1052, -0.0610, -0.1089, -0.0288, +0.0058, -0.0733],
-[ +0.0005, +0.1507, +0.1555, +0.0516, -0.1457, -0.1738, -0.0570, +0.0876, +0.2975, +0.1416, +0.0454, -0.3029, +0.0148, -0.2664, +0.0913, +0.0374, +0.1604],
-[ +0.0099, +0.1211, +0.3735, +0.2346, +0.0826, -0.0476, -0.0548, -0.0957, +0.0246, -0.0414, +0.0233, -0.0779, +0.0275, -0.1103, +0.1439, -0.1177, +0.0950],
-[ +0.0991, -0.0663, -0.0226, -0.2599, -0.2676, -0.2060, -0.0898, +0.0218, -0.0629, +0.3991, -0.0857, -0.0919, -0.0442, +0.0097, -0.0634, -0.1714, +0.0120],
-[ -0.0083, -0.2737, -0.0861, -0.1251, +0.0406, +0.0368, -0.1133, +0.1224, -0.1233, +0.0078, +0.1233, +0.0664, -0.2030, +0.0159, -0.4872, +0.0998, -0.1442],
-[ -0.0557, +0.0044, +0.0650, -0.3940, +0.0112, +0.1438, +0.0244, -0.0566, -0.1197, +0.0153, -0.0472, -0.1162, -0.1096, -0.0067, +0.0748, -0.1948, +0.0299],
-[ -0.1223, -0.1968, +0.0289, -0.1279, +0.2201, -0.2378, +0.0276, +0.2640, +0.0479, +0.0962, -0.0191, -0.2616, -0.1661, -0.1301, +0.1400, +0.0645, -0.1336],
-[ +0.0914, +0.0268, +0.0498, +0.2482, -0.1405, -0.1721, +0.0066, +0.0427, +0.1062, -0.0699, +0.0238, +0.1893, +0.0670, -0.0401, -0.0636, +0.0611, -0.0596],
-[ -0.1982, -0.2318, +0.1808, +0.0593, +0.1440, +0.3635, +0.0442, -0.1524, +0.0650, +0.0216, -0.0772, -0.1202, +0.2329, +0.0204, -0.0736, +0.2445, +0.0261],
-[ -0.3588, +0.0298, -0.0034, -0.0458, +0.2777, +0.2485, +0.3801, -0.0695, -0.1679, -0.5362, -0.1887, +0.0389, +0.2512, -0.0413, +0.0365, -0.0915, +0.0519],
-[ -0.0069, +0.1737, +0.1234, +0.0086, +0.0216, +0.1098, -0.0172, +0.0209, -0.1796, +0.1730, -0.0681, +0.1485, +0.1096, -0.0660, -0.0895, +0.1351, -0.0554],
-[ -0.2458, +0.0149, +0.0155, -0.0099, +0.0206, +0.3378, +0.2285, +0.0385, -0.0532, +0.2575, -0.0545, +0.0151, +0.0540, -0.0833, +0.0946, +0.0446, -0.0862],
-[ -0.1136, +0.1565, +0.1244, -0.0161, -0.0614, +0.1204, -0.0771, +0.2362, +0.0355, +0.2028, -0.0155, -0.0652, -0.2262, -0.0749, -0.1730, -0.0957, +0.2760],
-[ +0.0634, -0.0011, -0.1770, -0.1426, +0.1599, +0.0892, -0.0261, +0.0790, +0.0812, +0.4281, +0.0143, +0.1554, +0.3770, -0.0206, -0.1564, +0.0818, -0.0514],
-[ +0.0102, -0.1232, -0.2659, -0.1866, +0.0090, +0.2672, -0.0540, +0.1100, -0.2942, -0.2454, -0.0566, -0.2273, +0.1938, +0.0229, -0.1563, -0.0024, -0.0975],
-[ -0.0645, -0.0004, +0.1548, +0.2129, -0.0429, -0.0628, +0.0306, +0.1769, -0.0491, -0.0285, -0.0621, -0.4293, +0.1821, +0.1154, -0.0027, +0.0264, -0.0107],
-[ +0.3158, -0.0591, +0.0461, +0.0682, +0.0015, -0.0667, +0.1125, +0.0242, -0.0998, +0.0405, -0.1104, +0.0892, -0.1950, -0.0443, -0.1472, +0.1181, -0.0764],
-[ -0.0697, -0.0853, +0.1715, +0.0623, +0.0484, -0.0205, -0.2043, -0.0463, -0.1115, +0.0058, -0.0556, -0.0808, +0.0454, -0.0959, +0.1666, +0.3646, +0.2677],
-[ -0.1574, -0.2403, -0.1285, -0.0211, -0.2054, -0.0027, +0.1099, -0.1112, -0.2730, -0.1247, +0.1788, -0.1336, -0.1028, +0.1764, +0.2594, -0.0231, +0.1732],
-[ +0.2124, +0.1167, -0.0895, -0.0324, +0.2043, +0.0680, -0.0162, -0.0062, -0.0897, +0.0854, +0.0748, +0.3693, -0.0414, +0.0972, +0.0094, +0.0354, +0.1289],
-[ +0.2460, -0.1170, -0.1432, -0.0896, +0.0093, +0.0557, -0.0195, +0.0088, +0.0839, +0.0375, +0.1659, -0.0451, -0.1184, -0.2017, +0.0481, -0.1517, +0.1372],
-[ -0.0602, +0.3316, -0.0452, -0.0173, +0.0148, +0.0459, +0.0167, -0.0842, +0.0428, +0.2873, -0.0527, +0.0752, -0.0441, +0.0583, +0.0443, +0.1112, -0.0272],
-[ +0.0051, -0.0555, +0.1717, +0.1398, -0.1614, -0.0300, -0.1820, -0.0658, +0.0742, -0.0847, -0.1139, +0.0728, +0.1420, +0.2099, -0.2902, +0.1338, +0.1417],
-[ -0.0094, -0.0020, -0.1126, -0.2572, -0.2766, +0.0049, +0.1369, +0.0054, -0.1328, +0.0361, +0.1361, +0.3090, +0.0047, +0.1695, +0.0896, -0.1901, -0.1786],
-[ +0.1339, -0.0886, +0.0770, +0.0189, -0.1017, -0.0070, +0.1551, -0.0489, +0.0966, -0.0131, -0.0856, -0.1183, +0.1585, -0.0139, +0.1861, -0.1487, +0.0005],
-[ +0.2260, +0.0098, -0.3146, -0.0441, +0.1948, +0.0520, +0.0863, -0.0021, -0.1183, +0.0328, +0.0124, +0.0056, +0.0944, -0.0319, +0.0679, +0.0774, +0.0409],
-[ -0.0237, -0.3453, -0.1483, -0.2272, +0.1675, -0.1041, -0.0126, +0.3376, -0.0138, +0.1525, -0.0322, +0.2070, -0.2725, -0.0600, -0.1466, -0.2563, +0.0551],
-[ +0.1966, -0.0838, -0.0537, +0.0933, -0.0060, -0.0721, -0.0399, -0.1153, -0.1987, -0.0413, +0.2588, +0.0648, -0.0473, +0.1387, +0.6180, +0.0229, -0.2610],
-[ -0.1566, -0.0589, -0.0600, +0.0966, +0.0738, -0.0744, -0.0010, +0.0253, +0.2387, -0.0539, +0.0625, +0.1197, +0.0486, +0.0605, +0.2775, -0.0594, -0.0759],
-[ -0.4288, -0.0693, +0.0067, +0.3567, +0.0813, -0.1369, -0.3431, +0.0559, -0.0320, +0.0158, -0.1947, -0.3235, +0.1294, -0.2915, -0.2301, -0.1980, +0.0892],
-[ -0.1741, +0.0445, -0.0525, +0.0650, -0.0474, +0.1845, -0.0831, -0.0693, -0.0071, -0.0772, +0.0915, -0.0571, -0.1035, -0.0038, -0.1508, -0.2323, -0.1788],
-[ +0.1543, -0.0994, +0.0674, +0.1953, +0.1254, -0.1263, +0.0854, -0.1048, +0.0106, -0.0203, +0.1019, -0.0881, +0.2788, -0.2237, -0.0723, +0.0393, -0.0969],
-[ +0.0560, +0.2425, +0.1031, +0.1155, -0.1187, -0.1155, -0.0789, +0.2113, +0.0024, +0.2648, -0.1811, -0.0259, -0.1363, -0.2149, -0.2199, -0.1105, -0.1616],
-[ -0.0967, +0.0007, -0.2230, +0.1197, +0.1085, +0.0267, -0.0633, +0.1611, -0.0078, +0.0088, -0.0879, -0.1362, +0.1364, -0.1784, +0.1725, -0.0491, -0.0177],
-[ +0.0724, -0.0574, +0.0696, -0.0095, -0.1601, +0.1243, +0.2373, -0.1058, +0.1610, -0.1874, -0.0689, +0.1806, -0.2117, -0.0855, -0.0657, +0.0366, -0.0797]
+weights_dense2_b = np.array([
+ +0.1576, -0.1010, +0.0138, +0.3265, +0.2288, +0.0764, +0.0671, -0.1334,
+ +0.1474, +0.1138, +0.0768, +0.1304, +0.2356, +0.0043, +0.0230, +0.1405,
+ -0.0490, +0.2157, +0.1432, +0.1021, +0.0087, +0.1419, +0.0887, +0.1315,
+ +0.1993, +0.1391, +0.2385, +0.0697, +0.1521, +0.1446, +0.1235, +0.2313,
+ +0.1099, +0.1952, +0.1449, +0.2652, +0.0128, +0.2281, +0.1987, +0.1900,
+ +0.0668, +0.1516, +0.0543, +0.0443, +0.1702, -0.0012, +0.1350, -0.0182,
+ +0.1091, +0.1445, +0.1419, -0.0253, -0.0059, +0.0150, +0.1739, +0.0979,
+ +0.1677, +0.0557, +0.1365, +0.1161, +0.2681, +0.1524, +0.1655, +0.1234,
+ +0.1366, +0.2115, +0.1751, +0.0743, +0.1009, +0.3255, +0.0978, +0.3483,
+ +0.3591, -0.0855, +0.2378, -0.0121, +0.2396, +0.0827, +0.1282, +0.2056,
+ +0.2524, +0.1829, +0.0006, +0.0432, +0.1458, +0.1960, +0.2966, +0.1491,
+ +0.0097, +0.0552, +0.1618, +0.0341, +0.1177, +0.0545, +0.2253, +0.1174,
+ -0.0110, +0.0619, +0.0641, +0.1169, +0.1377, -0.0361, +0.3361, +0.0248,
+ -0.0144, +0.2120, +0.2515, +0.1977, +0.1501, +0.1138, +0.1061, +0.1561,
+ -0.0356, +0.1378, +0.1289, +0.0579, +0.1030, +0.1400, +0.1058, +0.1320,
+ -0.0224, +0.0156, +0.0664, -0.0583, +0.1267, +0.3404, +0.2669, +0.0034
])
-weights_final_b = np.array([ -0.0356, +0.0776, -0.0344, +0.1375, +0.1048, +0.3648, +0.3240, +0.1319, +0.1161, +0.3373, +0.3193, +0.0120, +0.0253, -0.2434, -0.1291, +0.1042, -0.2448])
+weights_final_w = np.array(
+ [[
+ -0.0500, +0.0520, -0.1401, +0.2030, -0.3231, +0.0144, -0.1040, +0.2029,
+ -0.1153, -0.1412, -0.0326, +0.0192, +0.0153, +0.1157, -0.2278, +0.0663,
+ -0.0588
+ ],
+ [
+ -0.1934, +0.1167, +0.0131, +0.0005, -0.0056, +0.2003, +0.0647,
+ +0.0407, +0.1506, +0.0205, -0.2231, -0.1559, -0.2919, +0.0398,
+ +0.0346, +0.0151, -0.0333
+ ],
+ [
+ -0.5131, +0.0469, -0.0589, -0.2056, -0.0316, +0.1800, -0.1217,
+ -0.1480, +0.1785, +0.0261, -0.1138, -0.1974, +0.2588, -0.0282,
+ -0.0632, +0.2111, -0.2802
+ ],
+ [
+ +0.0465, -0.2210, +0.1704, -0.4249, -0.0303, -0.1091, +0.0872,
+ -0.1461, -0.0034, +0.2490, -0.2206, -0.0736, +0.0300, -0.0700,
+ -0.1995, +0.3273, -0.1255
+ ],
+ [
+ +0.0426, +0.3676, -0.1660, -0.0894, +0.0383, -0.0723, +0.0043,
+ -0.0986, -0.0594, -0.0239, -0.0395, +0.0166, +0.1111, -0.0135,
+ +0.0101, -0.1226, +0.0468
+ ],
+ [
+ -0.1512, -0.0761, +0.2163, +0.0025, +0.1200, +0.1947, -0.2594,
+ -0.1264, +0.0708, -0.0100, +0.2345, +0.1272, +0.0181, +0.0598,
+ +0.0196, +0.0544, +0.0077
+ ],
+ [
+ -0.0479, +0.0877, -0.1959, +0.2171, +0.1391, -0.0882, +0.1955,
+ -0.0043, +0.0778, -0.0865, +0.0036, +0.0395, -0.0664, -0.0722,
+ -0.0999, +0.0403, +0.0459
+ ],
+ [
+ -0.1554, -0.0621, +0.0832, +0.0046, -0.1666, -0.0623, -0.0754,
+ -0.1921, -0.0802, +0.1742, -0.3199, +0.2225, -0.0935, -0.0165,
+ -0.1373, -0.1331, +0.1116
+ ],
+ [
+ +0.1641, +0.0611, -0.0527, -0.0480, +0.1270, -0.0116, -0.1430,
+ -0.2651, +0.0744, +0.1591, -0.0271, -0.1597, +0.0145, -0.0970,
+ -0.0396, +0.0642, -0.1355
+ ],
+ [
+ -0.1786, +0.1061, -0.0170, +0.2049, -0.0101, -0.0016, +0.1681,
+ +0.2846, +0.0429, +0.0779, -0.0644, +0.2227, +0.0480, -0.0613,
+ -0.1086, +0.0909, +0.0695
+ ],
+ [
+ -0.1132, -0.0676, +0.0076, +0.1158, -0.0424, -0.0585, +0.0658,
+ -0.1111, -0.0105, +0.1243, -0.1272, -0.1166, -0.1396, -0.0158,
+ +0.2221, -0.5519, +0.0056
+ ],
+ [
+ -0.2191, +0.0914, -0.2542, -0.0066, -0.1819, -0.0521, +0.0304,
+ +0.0955, +0.0114, +0.1190, +0.1209, -0.1486, -0.2386, +0.0012,
+ +0.0523, -0.0173, -0.0888
+ ],
+ [
+ +0.1867, +0.1779, +0.1244, +0.0109, +0.0969, +0.0768, -0.3619,
+ -0.0457, +0.1208, -0.0982, +0.0409, -0.1705, -0.0508, -0.0835,
+ +0.1529, -0.0571, -0.1034
+ ],
+ [
+ -0.1137, -0.2575, +0.0101, -0.4039, -0.1796, -0.2636, +0.1259,
+ +0.0388, +0.1942, -0.0287, +0.2606, -0.0823, -0.0069, +0.1304,
+ +0.4204, +0.0883, -0.1248
+ ],
+ [
+ -0.2387, +0.1436, -0.1701, +0.2502, +0.0021, +0.0202, +0.1469,
+ -0.1469, +0.1600, -0.0124, +0.0876, -0.1535, +0.4238, -0.0717,
+ +0.3870, +0.4299, -0.1141
+ ],
+ [
+ +0.2502, +0.1630, +0.0301, -0.1261, +0.1486, -0.1277, -0.0184,
+ -0.1144, -0.0368, +0.1179, -0.1200, -0.1448, -0.1146, -0.0880,
+ +0.3904, -0.0074, +0.1483
+ ],
+ [
+ -0.2122, +0.1499, -0.0626, -0.0072, +0.0174, -0.1730, +0.0620,
+ -0.1867, +0.0511, -0.0842, -0.2439, -0.0841, -0.0805, +0.1795,
+ -0.0691, -0.2461, +0.1777
+ ],
+ [
+ +0.0065, +0.2415, +0.1155, -0.2030, +0.0613, +0.2977, -0.0146,
+ +0.0042, +0.1047, -0.1538, -0.0089, -0.1895, +0.0561, -0.0879,
+ +0.0143, -0.0559, -0.0890
+ ],
+ [
+ -0.1464, -0.0184, +0.1731, +0.0010, +0.0459, -0.0302, -0.0838,
+ -0.1482, +0.1891, -0.0848, +0.0385, -0.0858, -0.3817, -0.0695,
+ -0.2484, -0.3315, -0.0779
+ ],
+ [
+ -0.1571, -0.1686, -0.0109, -0.0342, -0.0847, -0.1510, -0.0678,
+ -0.0963, +0.0833, +0.1933, +0.3233, -0.0954, +0.0170, -0.1014,
+ +0.0558, -0.1237, -0.0068
+ ],
+ [
+ +0.1069, -0.2466, -0.1261, +0.2319, -0.0456, +0.0744, -0.0796,
+ +0.0739, +0.1059, +0.0330, -0.1405, +0.1594, -0.2326, -0.1312,
+ +0.1011, +0.0532, -0.0480
+ ],
+ [
+ -0.3261, -0.3612, +0.4744, +0.1766, -0.2084, +0.0832, +0.0138,
+ -0.1178, -0.1055, -0.0774, +0.1118, +0.1659, +0.2805, -0.2790,
+ -0.4162, -0.1110, -0.0465
+ ],
+ [
+ -0.0609, +0.0663, -0.1358, +0.2174, +0.1067, +0.0559, -0.0523,
+ -0.0194, +0.2576, +0.0302, -0.0394, -0.0745, -0.0917, -0.0268,
+ -0.0366, +0.0958, +0.0342
+ ],
+ [
+ +0.0260, -0.1912, -0.2794, -0.2077, +0.0565, +0.0009, -0.0691,
+ -0.0750, -0.0582, +0.0129, -0.0717, -0.1249, -0.0442, +0.0543,
+ -0.0696, +0.0801, +0.0080
+ ],
+ [
+ +0.0147, +0.1115, -0.2710, +0.0096, -0.1212, +0.1514, -0.0183,
+ -0.0714, +0.2782, -0.1610, +0.1000, +0.0025, +0.0322, +0.0412,
+ -0.1214, +0.1739, -0.0345
+ ],
+ [
+ -0.1663, -0.0534, -0.0607, +0.2529, +0.0435, +0.0024, -0.1550,
+ +0.2743, +0.0510, +0.0220, +0.1415, -0.1839, +0.1584, +0.0849,
+ +0.0793, +0.3077, -0.0912
+ ],
+ [
+ +0.1709, +0.0804, +0.0473, +0.1288, +0.0029, +0.1389, +0.2928,
+ +0.0363, -0.0596, -0.0483, +0.3041, -0.0522, -0.0675, +0.0609,
+ -0.0559, -0.0244, +0.0003
+ ],
+ [
+ -0.1667, +0.1194, +0.1725, +0.0877, -0.1228, -0.0480, -0.0474,
+ -0.0550, +0.1146, +0.0949, +0.0477, -0.4471, -0.3624, -0.0280,
+ -0.0140, -0.1358, -0.0709
+ ],
+ [
+ +0.0310, -0.0247, +0.1299, -0.0083, +0.1510, -0.0586, -0.0757,
+ +0.0686, +0.2878, -0.0194, -0.0216, +0.0047, +0.1680, +0.0598,
+ -0.2225, -0.0494, -0.0765
+ ],
+ [
+ +0.1092, -0.3239, +0.1943, -0.0899, -0.0506, +0.1235, +0.0486,
+ +0.0174, +0.0141, -0.0921, +0.1887, +0.0339, +0.1610, -0.0140,
+ -0.1033, +0.1223, -0.0155
+ ],
+ [
+ -0.0277, +0.0191, +0.0459, +0.0300, +0.1183, -0.0972, +0.3191,
+ +0.1737, +0.1869, +0.0644, +0.0507, -0.0121, -0.0506, +0.0448,
+ -0.1096, -0.0081, -0.0789
+ ],
+ [
+ -0.2677, +0.1532, +0.0895, -0.0466, -0.0054, +0.0569, +0.0022,
+ -0.3044, +0.1862, -0.2223, -0.0157, +0.0559, +0.0186, -0.0800,
+ -0.1146, +0.3398, -0.1068
+ ],
+ [
+ +0.0242, -0.0935, +0.0429, -0.0115, +0.2126, +0.0859, +0.0020,
+ -0.1650, +0.1600, -0.0348, -0.1426, -0.0212, +0.0662, +0.0819,
+ -0.2960, -0.0660, -0.0242
+ ],
+ [
+ -0.0361, -0.0494, +0.0313, +0.1553, +0.0623, -0.1620, +0.2842,
+ +0.0104, -0.1632, +0.1637, +0.2602, -0.2550, -0.0172, -0.0868,
+ -0.1758, +0.0689, +0.0731
+ ],
+ [
+ +0.0089, +0.3266, -0.2115, +0.1473, +0.0423, +0.0773, +0.1420,
+ +0.2675, -0.0000, +0.1361, -0.4133, +0.0742, +0.0148, +0.2438,
+ -0.0297, +0.0726, +0.0325
+ ],
+ [
+ -0.1394, +0.0096, -0.1679, +0.1894, +0.0730, +0.0572, -0.2028,
+ +0.0843, -0.0058, -0.1014, +0.1447, -0.0080, -0.1056, -0.0686,
+ +0.0299, +0.0535, +0.0238
+ ],
+ [
+ -0.0404, +0.0493, -0.0139, +0.0949, +0.0198, +0.1132, -0.0484,
+ +0.0609, +0.2326, +0.2329, -0.3538, +0.0420, +0.0020, +0.1391,
+ +0.0121, -0.1743, +0.0309
+ ],
+ [
+ -0.0571, -0.0159, -0.3700, +0.0511, +0.3797, -0.1085, +0.0214,
+ +0.1002, -0.0533, -0.0098, -0.1695, +0.0261, -0.0258, -0.0383,
+ -0.0943, -0.0375, -0.0874
+ ],
+ [
+ -0.2690, +0.3889, -0.1825, -0.2502, +0.3067, +0.2693, -0.0415,
+ -0.2989, -0.0810, -0.2701, -0.0876, +0.1370, +0.0814, +0.1991,
+ +0.1026, -0.3468, +0.0540
+ ],
+ [
+ +0.0901, +0.1083, +0.0109, +0.3720, -0.1897, -0.1353, -0.0002,
+ -0.0120, -0.1493, -0.0239, +0.0070, -0.2525, -0.2358, -0.0631,
+ +0.1656, +0.1604, +0.0500
+ ],
+ [
+ +0.3311, -0.0797, +0.0255, -0.1776, +0.0926, +0.1546, +0.0071,
+ -0.0737, -0.2305, +0.0552, -0.0238, +0.2687, -0.3520, -0.1743,
+ +0.0424, -0.0234, -0.1280
+ ],
+ [
+ -0.1053, -0.0652, +0.2033, +0.1009, +0.1072, +0.2026, -0.0444,
+ +0.0543, -0.0881, -0.4387, +0.0020, -0.0239, -0.2309, -0.0730,
+ +0.1919, -0.0019, -0.1239
+ ],
+ [
+ +0.1863, -0.1390, -0.0368, +0.1796, -0.1910, +0.0543, -0.3425,
+ +0.1458, +0.0116, +0.1308, +0.1313, +0.1098, -0.0819, +0.0199,
+ -0.1105, -0.0217, +0.0668
+ ],
+ [
+ -0.1977, -0.2812, -0.0967, +0.2061, -0.0280, -0.1759, +0.0672,
+ +0.1179, +0.0423, +0.1185, +0.0052, +0.1873, -0.0213, +0.0987,
+ +0.1273, -0.0343, +0.0754
+ ],
+ [
+ -0.1596, +0.0493, +0.2797, +0.0854, +0.1617, +0.0723, +0.1626,
+ +0.1054, -0.0487, +0.0097, -0.0439, -0.1232, +0.1922, -0.0277,
+ +0.0119, +0.1730, +0.1012
+ ],
+ [
+ +0.0703, +0.1970, +0.0967, +0.0519, -0.0242, -0.0490, +0.1296,
+ +0.1286, +0.2053, -0.0337, +0.0747, +0.2130, -0.0591, +0.0786,
+ +0.1569, -0.1778, +0.0426
+ ],
+ [
+ +0.1670, -0.0426, +0.0293, +0.0224, +0.0965, +0.2378, +0.1234,
+ -0.0270, +0.0717, +0.0657, +0.1491, +0.1309, -0.0047, +0.1014,
+ -0.0419, -0.3916, +0.1701
+ ],
+ [
+ -0.1341, -0.0447, -0.0123, -0.0296, -0.5153, -0.0471, +0.0095,
+ -0.0265, -0.0487, -0.1160, -0.1601, +0.2510, +0.2775, -0.0465,
+ +0.1130, -0.0542, +0.1162
+ ],
+ [
+ -0.0102, -0.1284, +0.1419, -0.0311, +0.0061, -0.1030, +0.0771,
+ -0.1695, -0.0464, +0.1868, -0.2451, -0.2036, -0.0334, +0.0034,
+ +0.0619, +0.1707, -0.0432
+ ],
+ [
+ +0.1202, +0.0824, -0.0883, -0.0337, +0.2071, -0.3426, -0.1190,
+ +0.1154, +0.0478, +0.3089, +0.2514, -0.0086, -0.0398, +0.0412,
+ +0.0666, +0.0843, -0.0302
+ ],
+ [
+ -0.0201, +0.0295, -0.0884, -0.0905, +0.1772, +0.0316, +0.0128,
+ -0.5102, +0.2854, +0.0869, -0.0243, -0.2130, +0.1952, +0.1135,
+ -0.1489, -0.1426, -0.1163
+ ],
+ [
+ +0.0725, +0.2234, -0.1540, -0.2566, -0.0715, +0.1212, -0.1259,
+ -0.0770, +0.0403, +0.0321, +0.1270, +0.3933, -0.2743, +0.1460,
+ +0.0257, +0.0532, +0.0935
+ ],
+ [
+ +0.0539, -0.0206, +0.1057, -0.0783, +0.0933, +0.1618, -0.0672,
+ -0.0393, +0.0656, +0.0044, +0.2199, -0.1817, -0.0652, -0.1396,
+ +0.3507, -0.1025, +0.0075
+ ],
+ [
+ -0.2804, -0.1096, +0.0919, -0.1097, -0.0635, +0.0266, +0.1040,
+ -0.2046, +0.1255, +0.1206, -0.0410, -0.0632, -0.0094, -0.0336,
+ +0.0988, +0.2421, +0.0582
+ ],
+ [
+ +0.0741, -0.0379, -0.1480, -0.0401, -0.0145, +0.0121, -0.0270,
+ +0.1328, +0.0768, +0.1763, +0.0653, +0.2162, +0.1625, -0.0759,
+ -0.2528, -0.0400, -0.0609
+ ],
+ [
+ -0.0612, -0.1351, +0.1460, +0.0407, -0.1009, +0.1307, -0.2049,
+ -0.2043, +0.1486, +0.0571, +0.0194, +0.1111, +0.0900, -0.1686,
+ +0.2435, +0.0025, -0.0025
+ ],
+ [
+ +0.1537, -0.0991, +0.0023, +0.0866, +0.1233, +0.0192, +0.0099,
+ +0.0112, -0.1178, -0.0302, +0.1665, -0.1938, +0.0973, +0.0237,
+ -0.0594, -0.2662, +0.0543
+ ],
+ [
+ -0.0866, +0.0235, -0.4950, -0.2234, -0.3568, +0.1504, -0.3272,
+ -0.2139, -0.0608, -0.2261, +0.3710, -0.0093, +0.2967, +0.4035,
+ -0.1705, -0.1567, -0.1671
+ ],
+ [
+ +0.2094, +0.2050, -0.2027, -0.3216, -0.0898, -0.3793, +0.1276,
+ -0.2629, -0.2257, -0.0036, -0.1710, +0.0087, -0.1903, +0.0476,
+ -0.4685, -0.0350, +0.0185
+ ],
+ [
+ +0.0761, -0.1583, -0.2297, -0.1768, -0.0385, -0.0560, -0.2828,
+ +0.1289, +0.2082, -0.0280, +0.2047, -0.0699, -0.0760, +0.0177,
+ +0.0795, -0.2414, -0.0863
+ ],
+ [
+ +0.0051, -0.0159, +0.3049, -0.1012, +0.2151, +0.0903, -0.0857,
+ +0.2459, -0.0574, -0.1813, -0.0363, +0.2777, +0.1517, -0.2497,
+ -0.1926, -0.2714, -0.1205
+ ],
+ [
+ -0.0313, -0.1017, +0.1731, +0.1876, +0.1274, -0.0242, -0.0131,
+ +0.2359, -0.0604, -0.0337, +0.2364, -0.1355, -0.0705, +0.3669,
+ -0.1421, +0.1863, +0.0562
+ ],
+ [
+ -0.0262, -0.0691, +0.0511, +0.2557, -0.0593, +0.0052, +0.2013,
+ +0.2306, -0.1830, +0.1198, +0.1838, +0.5372, +0.1109, +0.0263,
+ -0.1590, +0.1215, -0.0652
+ ],
+ [
+ -0.0851, +0.2184, +0.0468, +0.0364, +0.0370, -0.0666, +0.0343,
+ -0.1203, +0.0828, +0.1937, -0.1424, +0.0270, +0.4887, +0.0595,
+ +0.3850, -0.1007, -0.1618
+ ],
+ [
+ -0.0647, -0.0491, -0.1482, -0.0725, +0.1533, -0.0067, -0.0163,
+ -0.2621, +0.4495, -0.0230, -0.1823, -0.2028, +0.0139, +0.0228,
+ -0.0210, +0.1549, +0.0272
+ ],
+ [
+ +0.0583, +0.1002, -0.2269, -0.1197, +0.2894, -0.0435, +0.1308,
+ -0.0852, +0.3371, +0.1352, -0.0481, +0.4537, +0.2147, -0.0701,
+ +0.1391, -0.0899, -0.0713
+ ],
+ [
+ -0.1840, -0.3356, -0.0079, +0.1192, -0.3029, -0.0518, -0.2026,
+ +0.3101, -0.2164, -0.1004, +0.0849, -0.2748, +0.3760, -0.0042,
+ +0.3993, +0.4109, -0.0759
+ ],
+ [
+ -0.0964, -0.1880, -0.0638, -0.0073, +0.0270, -0.1475, +0.1412,
+ +0.0414, -0.1057, -0.1715, +0.1548, -0.0673, +0.1397, -0.0826,
+ +0.1504, -0.0542, +0.0261
+ ],
+ [
+ -0.0436, +0.0176, -0.2640, -0.0555, +0.0581, +0.0930, +0.1484,
+ +0.1862, +0.0059, -0.0723, +0.0217, -0.0897, +0.1173, +0.0441,
+ +0.2001, +0.2820, +0.0056
+ ],
+ [
+ +0.0250, -0.0386, -0.0329, +0.0484, +0.0093, +0.0156, +0.0280,
+ -0.0594, -0.1825, +0.1148, -0.1595, -0.0615, -0.0671, +0.1472,
+ +0.1153, +0.0946, -0.1374
+ ],
+ [
+ +0.1758, +0.1463, -0.0741, -0.2125, +0.1636, -0.0032, -0.0480,
+ +0.2846, -0.1297, +0.0617, -0.0237, +0.0512, +0.1992, +0.1058,
+ +0.3484, +0.0708, +0.1671
+ ],
+ [
+ +0.2952, -0.0091, -0.0190, -0.0003, +0.1044, -0.0487, +0.3075,
+ +0.0950, -0.1509, +0.1373, -0.2803, +0.1419, +0.2875, +0.0242,
+ +0.0065, -0.0936, +0.0162
+ ],
+ [
+ +0.1659, +0.1577, +0.1013, -0.1512, +0.1424, +0.2053, +0.1997,
+ +0.1179, -0.1882, -0.2216, -0.2507, +0.1068, -0.1726, +0.0142,
+ +0.2472, +0.3217, -0.0999
+ ],
+ [
+ +0.0972, +0.1773, +0.0982, +0.0548, -0.0945, +0.1250, +0.0022,
+ -0.0743, -0.3627, -0.0801, +0.1161, +0.2369, +0.1528, -0.0622,
+ -0.0397, -0.1468, -0.1702
+ ],
+ [
+ +0.1908, +0.0306, +0.0756, -0.0095, -0.1140, +0.2149, -0.2536,
+ +0.0192, -0.1244, -0.0219, -0.0060, +0.0286, +0.1742, +0.0430,
+ +0.0622, +0.0760, +0.0211
+ ],
+ [
+ -0.2068, -0.0279, +0.1215, +0.1463, -0.0032, -0.0667, -0.0069,
+ +0.0322, -0.1577, +0.0497, +0.0793, +0.0504, +0.2050, +0.0459,
+ +0.0586, -0.0467, +0.0756
+ ],
+ [
+ -0.0050, -0.1217, +0.1720, -0.0497, +0.2169, +0.0608, -0.0893,
+ +0.2269, -0.1392, +0.0636, -0.0461, +0.0243, -0.3206, +0.1114,
+ -0.2682, -0.1793, +0.0532
+ ],
+ [
+ -0.0919, -0.1976, +0.0794, +0.0269, +0.1282, -0.0851, +0.0248,
+ +0.1133, +0.0308, -0.1318, -0.2297, -0.0558, -0.2465, -0.0534,
+ -0.0406, +0.1037, +0.2015
+ ],
+ [
+ -0.1945, +0.1965, +0.0724, -0.1509, +0.1594, -0.2093, +0.0466,
+ -0.1090, +0.0338, -0.0269, -0.0978, +0.2136, -0.3288, -0.0004,
+ -0.0335, +0.0991, -0.1539
+ ],
+ [
+ +0.3684, +0.0830, +0.1588, +0.3764, +0.1412, -0.1288, -0.1443,
+ +0.0388, +0.0819, +0.1563, -0.0173, +0.0067, +0.2200, +0.1175,
+ +0.0211, +0.0056, +0.0099
+ ],
+ [
+ +0.1937, -0.1604, -0.2249, -0.1253, -0.2346, -0.6112, -0.3301,
+ +0.0008, +0.0128, +0.2471, +0.3018, -0.1123, -0.0536, -0.0060,
+ -0.2138, -0.0642, -0.0224
+ ],
+ [
+ -0.0750, +0.0249, +0.2450, -0.1484, -0.0077, -0.1160, +0.1432,
+ +0.0341, -0.0626, -0.0306, +0.0240, -0.1328, +0.2852, +0.1698,
+ -0.1014, -0.1040, -0.0586
+ ],
+ [
+ -0.1895, +0.0789, -0.1464, +0.1532, +0.0039, -0.1385, +0.1615,
+ +0.1964, +0.2573, +0.1177, +0.0378, +0.2443, +0.3998, -0.0943,
+ -0.4698, +0.0102, +0.2408
+ ],
+ [
+ -0.0270, -0.0811, -0.0578, +0.2961, +0.0481, +0.0643, -0.0719,
+ +0.0192, +0.0965, -0.1667, +0.0554, -0.0081, -0.0330, +0.1145,
+ +0.1502, -0.2212, -0.0304
+ ],
+ [
+ +0.0547, -0.0325, +0.0254, -0.0844, +0.4001, -0.0142, +0.0167,
+ -0.0836, +0.0950, -0.1405, +0.0599, +0.1493, +0.0871, +0.1385,
+ -0.0614, -0.0024, -0.0119
+ ],
+ [
+ -0.1367, +0.1318, -0.1068, +0.0860, -0.3123, +0.1001, +0.3291,
+ -0.2463, -0.0354, -0.1765, +0.1861, +0.0849, +0.2081, +0.1625,
+ -0.1385, -0.0860, -0.0052
+ ],
+ [
+ -0.0067, +0.2718, -0.0711, +0.0202, +0.0372, -0.1661, +0.0658,
+ +0.0383, -0.1041, -0.1056, +0.2210, +0.0247, -0.0011, -0.1070,
+ -0.0103, +0.2565, -0.0143
+ ],
+ [
+ -0.0009, +0.2050, +0.2110, -0.1294, -0.0535, +0.0716, -0.0756,
+ +0.1513, -0.0375, -0.0890, +0.1466, +0.2619, -0.0011, -0.1757,
+ +0.1141, +0.0407, -0.0847
+ ],
+ [
+ -0.0193, -0.1029, +0.1858, +0.0139, +0.2608, -0.0146, +0.0154,
+ +0.0489, -0.1093, +0.0104, -0.2219, +0.0648, -0.0656, -0.0877,
+ +0.0203, -0.0899, -0.0903
+ ],
+ [
+ -0.0886, +0.1405, -0.3229, +0.1365, -0.0121, +0.0062, -0.0392,
+ -0.0051, +0.1538, +0.2586, -0.0580, +0.1502, -0.0022, -0.0271,
+ -0.0936, -0.4547, +0.0754
+ ],
+ [
+ +0.3475, +0.0164, -0.2164, +0.0795, -0.0293, +0.1575, +0.0395,
+ -0.4194, +0.0051, -0.0399, +0.1034, +0.3149, -0.0858, -0.1606,
+ -0.0197, -0.0434, -0.0950
+ ],
+ [
+ +0.1236, -0.0872, -0.2009, +0.3143, +0.1047, +0.0123, -0.1373,
+ -0.0199, +0.0415, -0.0361, +0.4936, +0.1017, +0.0232, -0.2103,
+ -0.0957, -0.1162, +0.0018
+ ],
+ [
+ -0.0303, +0.2271, +0.2671, -0.1139, +0.0505, +0.0459, +0.0181,
+ -0.0978, +0.0442, +0.0428, -0.0411, +0.1537, -0.2310, -0.0133,
+ +0.0393, +0.2811, +0.0302
+ ],
+ [
+ +0.0180, -0.2184, -0.0850, -0.1738, -0.1618, +0.0298, -0.0198,
+ +0.3145, -0.1872, -0.0837, -0.0753, -0.1052, -0.0610, -0.1089,
+ -0.0288, +0.0058, -0.0733
+ ],
+ [
+ +0.0005, +0.1507, +0.1555, +0.0516, -0.1457, -0.1738, -0.0570,
+ +0.0876, +0.2975, +0.1416, +0.0454, -0.3029, +0.0148, -0.2664,
+ +0.0913, +0.0374, +0.1604
+ ],
+ [
+ +0.0099, +0.1211, +0.3735, +0.2346, +0.0826, -0.0476, -0.0548,
+ -0.0957, +0.0246, -0.0414, +0.0233, -0.0779, +0.0275, -0.1103,
+ +0.1439, -0.1177, +0.0950
+ ],
+ [
+ +0.0991, -0.0663, -0.0226, -0.2599, -0.2676, -0.2060, -0.0898,
+ +0.0218, -0.0629, +0.3991, -0.0857, -0.0919, -0.0442, +0.0097,
+ -0.0634, -0.1714, +0.0120
+ ],
+ [
+ -0.0083, -0.2737, -0.0861, -0.1251, +0.0406, +0.0368, -0.1133,
+ +0.1224, -0.1233, +0.0078, +0.1233, +0.0664, -0.2030, +0.0159,
+ -0.4872, +0.0998, -0.1442
+ ],
+ [
+ -0.0557, +0.0044, +0.0650, -0.3940, +0.0112, +0.1438, +0.0244,
+ -0.0566, -0.1197, +0.0153, -0.0472, -0.1162, -0.1096, -0.0067,
+ +0.0748, -0.1948, +0.0299
+ ],
+ [
+ -0.1223, -0.1968, +0.0289, -0.1279, +0.2201, -0.2378, +0.0276,
+ +0.2640, +0.0479, +0.0962, -0.0191, -0.2616, -0.1661, -0.1301,
+ +0.1400, +0.0645, -0.1336
+ ],
+ [
+ +0.0914, +0.0268, +0.0498, +0.2482, -0.1405, -0.1721, +0.0066,
+ +0.0427, +0.1062, -0.0699, +0.0238, +0.1893, +0.0670, -0.0401,
+ -0.0636, +0.0611, -0.0596
+ ],
+ [
+ -0.1982, -0.2318, +0.1808, +0.0593, +0.1440, +0.3635, +0.0442,
+ -0.1524, +0.0650, +0.0216, -0.0772, -0.1202, +0.2329, +0.0204,
+ -0.0736, +0.2445, +0.0261
+ ],
+ [
+ -0.3588, +0.0298, -0.0034, -0.0458, +0.2777, +0.2485, +0.3801,
+ -0.0695, -0.1679, -0.5362, -0.1887, +0.0389, +0.2512, -0.0413,
+ +0.0365, -0.0915, +0.0519
+ ],
+ [
+ -0.0069, +0.1737, +0.1234, +0.0086, +0.0216, +0.1098, -0.0172,
+ +0.0209, -0.1796, +0.1730, -0.0681, +0.1485, +0.1096, -0.0660,
+ -0.0895, +0.1351, -0.0554
+ ],
+ [
+ -0.2458, +0.0149, +0.0155, -0.0099, +0.0206, +0.3378, +0.2285,
+ +0.0385, -0.0532, +0.2575, -0.0545, +0.0151, +0.0540, -0.0833,
+ +0.0946, +0.0446, -0.0862
+ ],
+ [
+ -0.1136, +0.1565, +0.1244, -0.0161, -0.0614, +0.1204, -0.0771,
+ +0.2362, +0.0355, +0.2028, -0.0155, -0.0652, -0.2262, -0.0749,
+ -0.1730, -0.0957, +0.2760
+ ],
+ [
+ +0.0634, -0.0011, -0.1770, -0.1426, +0.1599, +0.0892, -0.0261,
+ +0.0790, +0.0812, +0.4281, +0.0143, +0.1554, +0.3770, -0.0206,
+ -0.1564, +0.0818, -0.0514
+ ],
+ [
+ +0.0102, -0.1232, -0.2659, -0.1866, +0.0090, +0.2672, -0.0540,
+ +0.1100, -0.2942, -0.2454, -0.0566, -0.2273, +0.1938, +0.0229,
+ -0.1563, -0.0024, -0.0975
+ ],
+ [
+ -0.0645, -0.0004, +0.1548, +0.2129, -0.0429, -0.0628, +0.0306,
+ +0.1769, -0.0491, -0.0285, -0.0621, -0.4293, +0.1821, +0.1154,
+ -0.0027, +0.0264, -0.0107
+ ],
+ [
+ +0.3158, -0.0591, +0.0461, +0.0682, +0.0015, -0.0667, +0.1125,
+ +0.0242, -0.0998, +0.0405, -0.1104, +0.0892, -0.1950, -0.0443,
+ -0.1472, +0.1181, -0.0764
+ ],
+ [
+ -0.0697, -0.0853, +0.1715, +0.0623, +0.0484, -0.0205, -0.2043,
+ -0.0463, -0.1115, +0.0058, -0.0556, -0.0808, +0.0454, -0.0959,
+ +0.1666, +0.3646, +0.2677
+ ],
+ [
+ -0.1574, -0.2403, -0.1285, -0.0211, -0.2054, -0.0027, +0.1099,
+ -0.1112, -0.2730, -0.1247, +0.1788, -0.1336, -0.1028, +0.1764,
+ +0.2594, -0.0231, +0.1732
+ ],
+ [
+ +0.2124, +0.1167, -0.0895, -0.0324, +0.2043, +0.0680, -0.0162,
+ -0.0062, -0.0897, +0.0854, +0.0748, +0.3693, -0.0414, +0.0972,
+ +0.0094, +0.0354, +0.1289
+ ],
+ [
+ +0.2460, -0.1170, -0.1432, -0.0896, +0.0093, +0.0557, -0.0195,
+ +0.0088, +0.0839, +0.0375, +0.1659, -0.0451, -0.1184, -0.2017,
+ +0.0481, -0.1517, +0.1372
+ ],
+ [
+ -0.0602, +0.3316, -0.0452, -0.0173, +0.0148, +0.0459, +0.0167,
+ -0.0842, +0.0428, +0.2873, -0.0527, +0.0752, -0.0441, +0.0583,
+ +0.0443, +0.1112, -0.0272
+ ],
+ [
+ +0.0051, -0.0555, +0.1717, +0.1398, -0.1614, -0.0300, -0.1820,
+ -0.0658, +0.0742, -0.0847, -0.1139, +0.0728, +0.1420, +0.2099,
+ -0.2902, +0.1338, +0.1417
+ ],
+ [
+ -0.0094, -0.0020, -0.1126, -0.2572, -0.2766, +0.0049, +0.1369,
+ +0.0054, -0.1328, +0.0361, +0.1361, +0.3090, +0.0047, +0.1695,
+ +0.0896, -0.1901, -0.1786
+ ],
+ [
+ +0.1339, -0.0886, +0.0770, +0.0189, -0.1017, -0.0070, +0.1551,
+ -0.0489, +0.0966, -0.0131, -0.0856, -0.1183, +0.1585, -0.0139,
+ +0.1861, -0.1487, +0.0005
+ ],
+ [
+ +0.2260, +0.0098, -0.3146, -0.0441, +0.1948, +0.0520, +0.0863,
+ -0.0021, -0.1183, +0.0328, +0.0124, +0.0056, +0.0944, -0.0319,
+ +0.0679, +0.0774, +0.0409
+ ],
+ [
+ -0.0237, -0.3453, -0.1483, -0.2272, +0.1675, -0.1041, -0.0126,
+ +0.3376, -0.0138, +0.1525, -0.0322, +0.2070, -0.2725, -0.0600,
+ -0.1466, -0.2563, +0.0551
+ ],
+ [
+ +0.1966, -0.0838, -0.0537, +0.0933, -0.0060, -0.0721, -0.0399,
+ -0.1153, -0.1987, -0.0413, +0.2588, +0.0648, -0.0473, +0.1387,
+ +0.6180, +0.0229, -0.2610
+ ],
+ [
+ -0.1566, -0.0589, -0.0600, +0.0966, +0.0738, -0.0744, -0.0010,
+ +0.0253, +0.2387, -0.0539, +0.0625, +0.1197, +0.0486, +0.0605,
+ +0.2775, -0.0594, -0.0759
+ ],
+ [
+ -0.4288, -0.0693, +0.0067, +0.3567, +0.0813, -0.1369, -0.3431,
+ +0.0559, -0.0320, +0.0158, -0.1947, -0.3235, +0.1294, -0.2915,
+ -0.2301, -0.1980, +0.0892
+ ],
+ [
+ -0.1741, +0.0445, -0.0525, +0.0650, -0.0474, +0.1845, -0.0831,
+ -0.0693, -0.0071, -0.0772, +0.0915, -0.0571, -0.1035, -0.0038,
+ -0.1508, -0.2323, -0.1788
+ ],
+ [
+ +0.1543, -0.0994, +0.0674, +0.1953, +0.1254, -0.1263, +0.0854,
+ -0.1048, +0.0106, -0.0203, +0.1019, -0.0881, +0.2788, -0.2237,
+ -0.0723, +0.0393, -0.0969
+ ],
+ [
+ +0.0560, +0.2425, +0.1031, +0.1155, -0.1187, -0.1155, -0.0789,
+ +0.2113, +0.0024, +0.2648, -0.1811, -0.0259, -0.1363, -0.2149,
+ -0.2199, -0.1105, -0.1616
+ ],
+ [
+ -0.0967, +0.0007, -0.2230, +0.1197, +0.1085, +0.0267, -0.0633,
+ +0.1611, -0.0078, +0.0088, -0.0879, -0.1362, +0.1364, -0.1784,
+ +0.1725, -0.0491, -0.0177
+ ],
+ [
+ +0.0724, -0.0574, +0.0696, -0.0095, -0.1601, +0.1243, +0.2373,
+ -0.1058, +0.1610, -0.1874, -0.0689, +0.1806, -0.2117, -0.0855,
+ -0.0657, +0.0366, -0.0797
+ ]])
+
+weights_final_b = np.array([
+ -0.0356, +0.0776, -0.0344, +0.1375, +0.1048, +0.3648, +0.3240, +0.1319,
+ +0.1161, +0.3373, +0.3193, +0.0120, +0.0253, -0.2434, -0.1291, +0.1042,
+ -0.2448
+])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py
index 916094b1f..84220d533 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_HumanoidFlagrunHarderBulletEnv_v1_2017jul.py
@@ -2,7 +2,7 @@
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
@@ -10,500 +10,7853 @@ import pybullet_envs
import os.path
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], 256)
- assert weights_dense2_w.shape == (256, 128)
- assert weights_final_w.shape == (128, 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], 256)
+ assert weights_dense2_w.shape == (256, 128)
+ assert weights_final_w.shape == (128, 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 demo_run():
- gui = True
- env = gym.make("HumanoidFlagrunHarderBulletEnv-v0")
- if (gui):
- env.render(mode="human")
+ gui = True
+ env = gym.make("HumanoidFlagrunHarderBulletEnv-v0")
+ if (gui):
+ env.render(mode="human")
+
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ obs = env.reset()
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
while 1:
- frame = 0
- score = 0
- restart_delay = 0
- obs = env.reset()
+ a = pi.act(obs)
+ obs, r, done, _ = env.step(a)
+ score += r
+ frame += 1
+ if (gui):
+ time.sleep(1. / 60)
+
+ still_open = env.render("human")
- while 1:
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- score += r
- frame += 1
- if (gui):
- time.sleep(1./60)
+ if still_open == False:
+ return
+ if not done: continue
+ if restart_delay == 0:
+ print("score=%0.2f in %i frames" % (score, frame))
+ if still_open != True: # not True in multiplayer or non-Roboschool environment
+ break
+ restart_delay = 60 * 2 # 2 sec at 60 fps
+ restart_delay -= 1
+ if restart_delay == 0: break
- 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))
- if still_open!=True: # not True in multiplayer or non-Roboschool environment
- break
- restart_delay = 60*2 # 2 sec at 60 fps
- restart_delay -= 1
- if restart_delay==0: break
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ +0.3543, -0.3833, +0.3987, +0.1828, +0.5746, +0.3807, +0.1427, +0.2510,
+ -0.3705, -0.2212, +0.0019, +0.7898, +0.2609, -0.5883, -0.1780, +0.1319,
+ +0.4746, -0.5833, -0.4251, +0.5949, +0.6170, -0.2344, +0.1624, -0.7524,
+ -0.1314, +0.3180, -0.3183, -0.5343, +0.6109, -0.0071, +0.0890, +0.1470,
+ +0.3201, -0.1915, -0.1192, -0.2254, +0.1921, +0.5020, +0.8814, +0.7632,
+ +0.2973, -0.0293, +0.0134, -0.1171, +0.4190, +0.2720, -0.1020, +0.2688,
+ -0.3085, -0.0548, +0.4256, +0.5690, -0.2243, +0.4055, +0.7467, +0.2371,
+ -0.1666, -0.3083, -0.2019, -0.1256, -0.2922, -0.0295, -0.1915, +0.4345,
+ +0.4745, +0.4599, +0.7173, +0.1671, -0.1942, +0.6437, +0.1593, -0.2243,
+ -0.3772, +0.0888, +0.0181, +1.5305, +0.1103, -0.0983, +0.5553, -0.2304,
+ +0.1091, -0.7436, -0.4132, -0.0910, -0.3729, +0.5907, -0.0080, -0.3815,
+ +0.4647, -0.4074, +0.2752, +0.2604, +0.2102, +0.1988, +0.5086, +0.1865,
+ -0.5980, +0.1655, +0.3442, -0.0285, +0.4722, -0.4559, -0.8286, +0.2297,
+ +0.1441, +0.5148, +0.9493, +0.3310, +0.1502, +0.1993, +0.4227, +0.8433,
+ -0.3427, +0.7080, +0.3844, +0.4788, +0.0027, +0.0413, -0.2622, -0.2789,
+ -0.1309, -0.0235, +0.9649, -0.3073, +0.4120, -0.1224, +0.3168, -0.4171,
+ +0.2409, +0.8089, +0.2216, +0.7449, +0.1001, -0.0277, -0.2632, +0.0697,
+ +0.2002, +0.4163, -0.1231, +0.3181, +0.4182, +0.9432, +0.5265, +0.0247,
+ +0.0824, +0.2249, -0.5920, +0.1227, -0.4454, +0.2406, +0.2175, +0.4905,
+ +0.2078, +0.1180, -0.2074, +0.2553, -0.4872, +1.0349, +0.0574, -0.0449,
+ -0.3136, +0.1975, -0.1428, +0.1385, +0.0113, -0.0366, -0.2522, +0.7889,
+ -0.5059, +1.0163, +0.4410, +0.0459, -0.2020, +0.3168, -0.8575, +0.4499,
+ -0.0539, -0.0231, -0.0449, +0.0083, +0.0040, +1.1597, -0.3938, +0.0570,
+ +0.2773, +0.7838, +0.5444, +0.3460, +0.0922, -0.0916, -0.1977, -0.2641,
+ +0.5723, +0.1033, -0.6443, +0.1281, +0.4627, +0.6561, +0.0765, +0.2997,
+ +0.4318, -0.4581, +0.0353, +0.1669, +0.0664, -0.0233, +0.0447, +0.3139,
+ +0.0570, +0.0322, +0.7074, -0.0692, +0.0741, +0.1177, +0.7109, +0.1507,
+ -1.0050, +0.0803, +0.1696, -0.7228, -0.3827, +0.3475, -0.0327, +0.0961,
+ +0.5664, +0.2477, +0.3436, -0.0406, +0.2801, +0.1499, +0.0971, -0.2689,
+ +0.0691, -0.1481, -0.1288, +0.5560, +0.2778, +0.2370, +0.1795, +0.3816,
+ +0.8086, +0.2443, -0.2036, +0.8701, +0.3228, +0.0493, +0.4232, +0.2833,
+ +0.1421, +0.0004, -0.3722, -0.8666, -0.1084, -0.2561, -0.2230, -0.0161
+ ],
+ [
+ +0.0958, -0.1782, +0.3288, +0.0482, +0.0290, -0.3382, +0.3124,
+ +0.1661, +0.0309, +0.0167, +0.3039, -0.2731, +0.2352, -0.0909,
+ +0.0472, -0.0685, +0.2378, +0.0030, -0.0057, -0.2164, +0.1759,
+ +0.2240, +0.1018, +0.3923, +0.2377, +0.2124, -0.2076, +0.2497,
+ +0.2697, -0.2019, -0.1881, -0.0446, -0.4666, +0.4909, -0.0879,
+ -0.3494, -0.3057, -0.0409, +0.0555, -0.1819, -0.0586, -0.2323,
+ +1.0968, -0.1451, +0.0927, +0.1340, -0.3688, -0.0321, -0.1371,
+ +0.2704, -0.2831, +0.0576, +0.2786, -0.4570, +0.0034, -0.1193,
+ -0.2615, +0.1571, -0.0981, +0.1934, +0.2114, +0.4198, +0.0797,
+ +0.0997, -0.0848, -0.1339, +0.2575, -0.0421, +0.2907, +0.2311,
+ +0.2077, -0.1234, +0.2197, +0.3210, +0.2515, -0.1523, +0.0573,
+ +0.0863, +0.0221, -0.1319, +0.1101, -0.1512, -0.0253, +0.3307,
+ +0.3122, +0.2278, +0.0856, +0.0814, -0.2028, -0.0373, -0.2210,
+ +0.2000, +0.1657, -0.0533, +0.1978, -0.2226, +0.0377, +0.4188,
+ +0.0766, +0.2088, +0.2568, -0.0574, -0.3792, +0.2971, -0.1956,
+ -0.0845, -0.1638, -0.0269, -0.2203, +0.5461, +0.0076, +0.3380,
+ -0.2262, +0.1973, -0.2503, -0.1507, -0.2942, +0.1642, -0.2460,
+ -0.1684, -0.0207, +0.0026, +0.3213, -0.0170, +0.5102, -0.2842,
+ +0.2971, -0.2165, +0.1205, -0.0015, +0.0166, +0.1441, -0.1231,
+ +0.0713, +0.1159, -0.3383, +0.0572, -0.0782, -0.0589, +0.2331,
+ -0.0825, -0.0095, -0.1379, -0.0909, +0.0111, -0.0969, +0.1849,
+ -0.1454, +0.1298, -0.1478, -0.1134, -0.0017, +0.4045, +0.1368,
+ -0.2911, +0.0401, -0.0180, +0.5063, +0.3238, +0.1427, -0.1532,
+ -0.0783, -0.1042, -0.0411, +0.0817, -0.1855, +0.0211, +0.0212,
+ +0.0748, -0.1480, -0.0379, +0.0186, +0.0107, -0.0290, +0.0324,
+ +0.0711, +0.2620, +0.1047, -0.4431, -0.1354, +0.0647, +0.1472,
+ -0.0249, -0.3687, +0.4135, +0.1640, -0.1606, +0.1635, -0.2894,
+ +0.1293, +0.1063, -0.3286, -0.5707, -0.1076, +0.2624, +0.0245,
+ -0.3619, +0.0624, -0.1214, +0.3565, -0.2067, +0.2906, +0.2800,
+ +0.0814, +0.4657, +0.1716, -0.2339, +0.1425, -0.2436, -0.0386,
+ +0.6793, +0.0337, +0.3238, +0.2363, -0.1065, -0.3087, -0.1684,
+ -0.0784, +0.1175, +0.1939, +0.5676, -0.1382, -0.1300, +0.6986,
+ -0.1262, -0.1023, -0.6929, +0.0871, -0.2003, -0.2158, -0.4234,
+ +0.1276, +0.2671, +0.1822, +0.7594, +0.1000, +0.4422, +0.0027,
+ +0.0716, +0.2667, +0.1928, +0.2579, -0.1292, -0.1112, -0.0446,
+ -0.1893, +0.5958, -0.0906, +0.1439, +0.3357, +0.4613, +0.2427,
+ -0.2639, -0.2407, -0.0296, +0.1122
+ ],
+ [
+ -0.5187, +0.2287, +0.2752, +0.1228, -0.4072, +0.0853, -0.0049,
+ -0.0030, -0.0514, +0.2529, +0.0103, +0.3002, -0.1213, -0.3048,
+ +0.1508, +0.0940, +0.1131, -0.0398, -0.1921, +0.0943, +0.3511,
+ +0.1262, -0.1832, -0.0754, -0.3122, -0.1396, -0.1342, +0.0026,
+ +0.1042, +0.1073, -0.3781, +0.1753, -0.1475, -0.0098, -0.1979,
+ -0.0963, +0.0744, +0.1211, -0.4690, -0.0567, -0.2050, +0.0610,
+ +0.0799, -0.0853, +0.1085, -0.2187, -0.0474, +0.0588, -0.4914,
+ -0.3591, -0.0325, -0.1640, -0.1259, +0.2144, +0.2286, -0.0006,
+ -0.2550, -0.1209, +0.0025, -0.2094, +0.0772, -0.3342, -0.1242,
+ +0.1456, -0.2479, -0.0827, -0.2497, +0.1308, -0.1004, -0.0134,
+ +0.0534, +0.0458, -0.5951, +0.0508, +0.2547, +0.0729, +0.0317,
+ -0.1115, +0.3033, -0.2973, +0.1477, +0.1418, -0.1385, +0.1961,
+ +0.2135, -0.0573, +0.0018, -0.1410, +0.1146, -0.3430, -0.2801,
+ -0.0008, +0.3632, -0.0757, -0.1747, +0.1223, +0.0343, +0.1432,
+ +0.2027, -0.0085, -0.1352, +0.2187, -0.2602, -0.4523, -0.1417,
+ -0.0164, +0.0977, +0.1679, +0.0650, +0.3161, +0.5088, +0.2696,
+ -0.0018, +0.2048, -0.5342, -0.1123, -0.0499, -0.1345, +0.0267,
+ -0.7731, -0.0320, +0.1851, +0.1143, +0.0312, +0.0069, +0.2073,
+ +0.0478, +0.0664, -0.3389, +0.2681, -0.1528, +0.3933, +0.0777,
+ +0.1889, +0.2740, -0.2838, -0.0483, +0.2780, -0.0631, -0.0021,
+ +0.2336, +0.3078, -0.1664, +0.0241, -0.5676, +0.0183, +0.0869,
+ -0.3300, +0.0455, -0.0271, +0.1659, -0.2304, +0.1064, -0.3165,
+ -0.1034, -0.0027, -0.2941, -0.1458, +0.0648, +0.1050, +0.0824,
+ -0.2342, -0.6234, +0.1293, -0.0112, -0.4213, -0.1430, -0.0978,
+ -0.3229, +0.0542, +0.3499, +0.2255, +0.1985, -0.1539, +0.1177,
+ +0.0342, -0.5749, -0.4455, -0.0349, +0.0118, -0.1757, -0.3755,
+ +0.2552, -0.0067, -0.2466, +0.0227, +0.1964, +0.1425, -0.8570,
+ -0.3395, +0.2669, -0.3031, -0.1005, -0.0378, +0.1286, +0.0222,
+ +0.1333, -0.2285, -0.0157, -0.2054, -0.1904, +0.0256, -0.0028,
+ +0.1041, +0.0959, +0.1583, +0.1038, -0.3391, -0.1159, +0.0815,
+ -0.4441, +0.2713, -0.4762, +0.0379, -0.0479, -0.2772, +0.0133,
+ -0.2058, +0.3131, +0.0004, +0.0261, -0.1871, +0.3252, +0.1042,
+ +0.0255, -0.3935, -0.0056, -0.1552, -0.1384, -0.1413, +0.2543,
+ +0.2404, -0.0705, -0.0451, +0.0732, +0.2933, +0.2115, +0.1148,
+ -0.2568, +0.2483, -0.2113, +0.0656, -0.1139, -0.1590, +0.0919,
+ -0.0663, +0.2719, -0.2828, +0.0277, -0.0606, -0.0600, -0.4945,
+ -0.0344, -0.1378, -0.3805, -0.0176
+ ],
+ [
+ -0.0570, -0.3114, -0.1088, +0.6142, -0.1379, -0.0909, +0.3296,
+ -0.0470, -0.0442, -0.7245, +0.4978, -0.3704, -0.0556, -0.9845,
+ -0.5872, +0.2280, -0.7789, +0.0387, +0.2177, +0.1441, +0.1711,
+ +0.4705, +0.8632, +0.3682, +0.1355, +1.3679, -0.2215, -0.0370,
+ -0.1336, +0.5885, +0.6607, -0.1850, -0.2828, +0.1596, +0.1422,
+ -0.5338, +0.1196, +0.1801, +0.1746, -0.6810, -0.1652, -0.0237,
+ -0.1493, +0.2489, +0.0379, +0.6433, +0.1872, +0.4326, +0.2534,
+ +0.1013, +0.4340, -0.0254, -0.2332, -0.5027, +0.1654, +0.6060,
+ -0.2868, -0.0742, -0.3677, +0.0188, -0.1034, +0.0072, -0.6168,
+ -0.0069, +0.1889, +0.2089, -1.2578, -0.3993, -0.3688, +0.1227,
+ -0.0849, +0.3978, +0.5294, +0.4421, -0.3402, +0.1462, +0.1488,
+ -0.1681, +0.0587, +0.2754, -0.5148, -0.2919, +0.0246, +0.0277,
+ +0.1282, -0.5015, -0.2559, +0.1333, -0.9075, +0.0369, +0.2989,
+ +0.2742, -0.3045, +0.0530, +0.5996, -0.1369, -1.0727, +0.0708,
+ +0.5281, -0.6266, +0.2929, -0.0272, -0.6657, -0.0327, +0.7032,
+ -0.3803, -0.4939, -0.4937, +0.5844, -0.4650, -0.6580, -0.4147,
+ +0.0574, +0.1599, +0.4039, +0.1270, -0.2136, -0.3195, -0.1574,
+ +0.3678, -0.2304, -0.1422, +0.0063, -0.2868, +0.1114, -0.2380,
+ -0.1446, +0.6534, -0.7640, -0.4790, -0.2581, +0.0866, +0.6298,
+ -0.1627, +0.2434, -0.1345, -0.1591, -0.6833, +0.8013, -0.0074,
+ -0.3966, -0.3063, -0.2725, +0.1495, -0.0078, -0.2898, -0.2865,
+ +0.6035, -0.7516, +0.4026, -0.1695, -0.5334, +0.0071, -0.2942,
+ -0.4005, -0.1630, +0.4325, +0.7765, +0.2475, -0.4999, -0.7969,
+ -0.7106, +0.4207, +0.1617, -0.4988, +0.0723, +0.7424, -0.1637,
+ +0.1045, -0.5962, -0.1980, +0.2069, +0.1651, +0.3050, -0.4303,
+ +0.1358, -0.2130, -0.3275, +0.1884, +0.3995, -0.4926, -0.2890,
+ -0.2000, -0.2949, -0.2786, -0.1046, -0.4901, +0.3215, -0.6671,
+ -0.0014, -0.6554, +0.1843, -0.0903, -0.0866, -0.8480, -0.0981,
+ -0.0733, -0.1374, +0.3921, +0.1671, +0.0656, -1.0367, +0.5457,
+ -0.0115, -0.2121, +0.3420, -0.2665, +0.0299, -0.3441, +0.4883,
+ -0.1289, -0.5812, +0.8116, -0.1478, +0.0101, +0.3588, -0.6830,
+ -0.1244, +0.2684, -0.3833, +0.0715, +0.5570, +0.4727, -0.0386,
+ -0.4478, +0.4346, -0.2378, -0.2175, -0.5516, -0.0764, -1.6323,
+ +0.2628, +0.4238, +0.1281, +0.1813, +0.3879, -0.1268, +0.0123,
+ +0.3925, -0.1931, -0.6132, -0.5956, +0.6764, -0.0714, +0.0154,
+ -0.1122, -0.4323, +0.5535, -0.3156, -0.3578, -0.8526, -0.4097,
+ +0.2420, +0.1931, +0.6615, +0.4633
+ ],
+ [
+ +0.3856, +0.0380, +0.1607, +0.7211, -0.4803, +0.3282, +0.6278,
+ +0.2020, -0.8478, -0.0240, -0.2271, -1.1262, +0.1720, +1.0624,
+ -0.4353, -0.3814, +0.4174, +0.3153, -0.0629, +0.5575, +0.3262,
+ -0.2309, +0.7053, -0.7675, +0.0130, -0.4398, -0.4520, -0.4738,
+ -0.2739, +0.2262, +0.3351, -0.7933, +0.3686, +0.1975, +0.5455,
+ -0.3773, -0.1874, +0.0645, -0.6104, +0.9056, -0.0197, +0.7429,
+ -0.0564, -0.1760, -0.4114, -0.2636, -0.3710, +0.5700, -0.4883,
+ +0.4906, +1.3030, +0.1374, -0.5772, -0.2841, +0.6549, -0.2637,
+ -0.6877, +0.1885, -0.2468, -0.2661, -0.1269, -0.0954, +0.4093,
+ -1.0006, -1.0739, +0.5058, +0.1711, -0.5654, -0.9009, -0.3533,
+ +0.7245, -0.0761, -0.7570, -0.5107, +0.5003, -0.3738, +0.8248,
+ -0.0174, -0.0329, +0.1597, +0.3538, +0.1845, +0.5623, +0.1166,
+ -0.0666, -0.2745, -0.3009, +0.3987, -0.2977, -0.6311, +0.0018,
+ -0.2627, -0.6512, -0.0303, -0.9577, +0.2203, +0.2135, -0.0742,
+ -0.6742, -0.2723, -0.1118, +0.4371, +0.3550, +0.4606, +0.4340,
+ +1.0860, +0.1818, -0.5315, +0.4768, -0.1874, -0.2363, -0.6467,
+ +0.9317, -0.1335, +0.5472, +0.6879, +0.1606, +0.1596, -0.1357,
+ -0.0811, -0.3636, +0.7840, -0.1458, +0.4020, -0.0052, -0.1393,
+ +0.3154, -0.0006, -0.7112, +0.2714, +0.5062, +0.1726, +0.7692,
+ -0.1091, +0.3916, -0.2577, -0.5718, -0.4336, +0.1497, +0.4095,
+ +0.3539, +0.6999, -0.5753, -0.0278, -0.6541, +0.5542, -0.7776,
+ +0.0913, -0.6832, -0.6140, +0.0515, -0.2613, +0.1417, -0.9894,
+ -0.1342, -0.2246, -0.1429, -0.4141, +0.1981, -0.1309, +0.3413,
+ +0.3129, -0.1747, -0.5412, +0.6874, +0.3260, +0.0846, +0.3818,
+ +0.4490, +0.7462, +0.0062, -0.2363, -0.1671, -0.5198, -0.6330,
+ +0.9872, -0.2159, +0.4651, -0.2138, +0.3548, +0.7041, -0.2278,
+ -0.1848, -0.8821, +0.2462, -0.1612, +0.8281, +0.8352, -0.7345,
+ -0.1699, +0.3341, -0.4163, +1.0198, +0.2347, -0.2900, -0.3751,
+ +0.8562, -0.7091, -0.6140, +0.1578, -0.3085, +0.5008, -0.3238,
+ -0.1784, +0.1425, +0.2281, -0.6608, -0.4512, +0.6757, -0.2319,
+ +1.3040, -0.3273, +0.2071, -0.1651, +0.0148, +0.3103, +0.3019,
+ -0.1881, +0.2410, +0.0305, +0.0504, -0.3716, -0.1396, -0.2934,
+ +0.1656, -0.3740, -0.1310, +0.0817, -0.0037, +0.2901, -0.5307,
+ -0.4163, -0.7077, -1.1809, -0.6042, +0.0345, -0.5511, -0.2317,
+ +0.7121, +0.5965, -0.1168, -0.7979, -0.0691, -0.0206, +0.0990,
+ -0.5956, -0.2970, -0.8674, -0.1161, +0.4983, -0.9971, +0.5049,
+ +0.3464, -0.1332, -0.6007, -0.0100
+ ],
+ [
+ -0.3086, -0.2303, +0.3152, -0.1116, +0.0799, -0.3931, -0.1490,
+ -0.0247, -0.7502, -0.1217, +0.7861, -0.1143, -0.3911, -0.4594,
+ +0.1463, +0.0265, -0.0780, -0.6028, +0.4631, +0.7258, +0.4649,
+ +0.0420, -0.0493, +0.1636, -0.3396, -0.0729, +0.4166, -0.3020,
+ -0.0168, -0.4617, +0.0944, -0.2123, +0.7230, -0.2222, -0.3647,
+ -0.0116, -0.3939, -0.2826, +1.0357, +0.4180, -0.2008, +0.7345,
+ +0.0222, +0.0816, -0.3684, -0.1234, -0.4089, -0.0311, -0.1626,
+ -0.2367, -0.0980, -0.2955, -0.1024, -0.4637, -0.2925, +0.5904,
+ -0.5515, -0.2542, +0.0690, -0.1179, -0.2136, +0.2457, -0.1525,
+ -0.0990, -0.0583, +0.1767, +0.4226, -0.1596, +0.0185, +0.0476,
+ -0.0666, -0.0392, -0.3034, -0.2679, -0.5904, -0.0414, +0.5802,
+ -0.3043, +0.7735, -0.1095, +0.1673, +0.2152, +0.0611, -0.3035,
+ -0.2460, -0.2300, +0.4381, -0.1431, +0.4268, +0.1144, -0.1928,
+ -0.1918, -0.6915, -0.5794, -0.3670, +0.7585, -0.8027, +0.3487,
+ +0.5753, -0.2920, +0.3446, -0.1739, +0.6269, -0.1520, -0.2745,
+ +1.0809, -0.3024, +0.0255, +0.1935, +1.0626, +0.6935, +0.0820,
+ -0.6116, +1.3359, -0.4234, -0.6222, +0.0244, +0.0389, -0.6722,
+ +0.4178, -0.2680, -0.0337, +0.0640, -0.0816, -0.0498, -0.4453,
+ +0.0734, +0.1799, -0.0322, -0.6132, +0.3590, +0.1533, +0.4668,
+ +1.0410, -0.6774, +0.2069, -0.3858, +0.0929, +0.2870, -0.5417,
+ +0.2325, -0.5414, +0.1480, +1.1710, +0.2069, +0.4407, +0.1163,
+ +0.0144, -0.5544, -0.2193, +0.2130, -0.2111, -0.0325, +0.3058,
+ -0.2408, +0.3621, +0.1342, +0.2040, -0.0684, +0.4992, +0.0703,
+ +0.1867, -0.6955, +0.4513, -0.7907, +0.3006, -1.0133, +0.1236,
+ -1.0365, +0.0708, +0.4165, -0.3972, -0.9550, -0.0497, -0.7666,
+ +1.1159, -0.5457, -0.5034, -0.2620, +0.3694, -0.8464, +0.0237,
+ +0.0522, -0.0003, -0.0889, +0.1617, -0.0572, -0.7113, -0.3840,
+ +0.0955, -0.5163, +0.2279, -0.0807, -0.3170, -0.3465, +0.3036,
+ +1.0967, +0.4635, +0.3360, +0.1150, -0.0211, +0.2847, -0.2062,
+ -0.0093, +0.5722, -0.3048, +0.2928, +0.3035, -0.3387, -0.3379,
+ -0.1001, -0.2899, +0.4759, -0.7681, +0.0895, +0.2146, -0.4089,
+ -0.0256, -0.0714, -0.8717, -0.1449, -0.4994, +0.4098, -0.4314,
+ +0.0200, +0.0395, +0.5496, +0.3181, -0.0524, +0.3103, +0.4681,
+ +0.0415, +0.0460, +0.3279, +0.2327, +0.1861, +0.3333, -0.0774,
+ +0.1634, +0.0597, -0.0172, +0.7018, -0.2210, +0.4247, +0.1282,
+ -0.0706, +0.5843, +0.0847, +0.1637, +0.1443, -0.4523, -0.1132,
+ -0.1423, -0.4084, +0.2323, -0.3703
+ ],
+ [
+ -0.1628, -0.0910, +0.3645, -0.0508, -0.0480, -0.3354, +0.1378,
+ -0.0796, -0.0735, +0.5216, -0.4845, -0.1646, -0.0843, -0.4177,
+ -0.0659, +0.1129, -0.2721, +0.0506, -0.1478, -0.2329, -0.4058,
+ +0.3746, +0.1111, +0.0048, +0.3003, +0.1400, +0.0219, +0.0036,
+ -0.3503, -0.4100, -0.5064, +0.0641, -0.0306, +0.0931, -0.1036,
+ +0.1072, +0.2196, +0.2135, -0.0883, -0.0936, +0.4832, -0.2619,
+ +0.0382, -0.1628, +0.2677, -0.0128, +0.2590, -0.0291, +0.0483,
+ +0.0877, -0.5890, -0.2196, +0.6421, -0.2236, -0.1257, -0.1504,
+ -0.1872, +0.3704, +0.3330, -0.1955, +0.0496, -0.2220, +0.0055,
+ +0.3401, -0.0080, -0.2781, -0.1191, +0.1448, -0.2057, +0.1096,
+ -0.3750, +0.0790, -0.2106, +0.2074, -0.5412, -0.0403, -0.2812,
+ +0.0347, -0.3933, -0.0388, +0.0326, -0.1072, -0.3437, -0.3396,
+ -0.1000, +0.0953, +0.0622, +0.3081, +0.0067, +0.1591, -0.0479,
+ +0.0482, -0.0583, +0.0411, +0.2547, -0.1814, +0.0753, +0.3990,
+ +0.0501, +0.0626, +0.0417, -0.1376, -0.4501, -0.1439, -0.0770,
+ -0.2651, -0.1445, +0.0230, -0.0958, -0.2221, +0.1717, +0.1478,
+ -0.3690, -0.0121, -0.6698, -0.0107, +0.1424, +0.0987, -0.0837,
+ +0.3131, +0.0049, -0.3202, -0.0791, +0.0609, +0.3332, +0.1109,
+ +0.0441, +0.1337, +0.3522, +0.2834, -0.3200, +0.5293, -0.4299,
+ -0.3855, -0.1533, -0.0158, +0.1217, +0.0241, +0.0385, +0.1733,
+ -0.1477, -0.6579, -0.2818, +0.3793, +0.1597, -0.0041, +0.7934,
+ -0.0526, -0.0997, -0.1419, -0.1658, +0.0885, +0.1390, +0.1498,
+ +0.1663, +0.0392, +0.0062, -0.4296, -0.4038, -0.1783, -0.6737,
+ -0.2527, +0.0699, +0.2806, -0.3069, -0.3786, +0.0694, -0.4885,
+ -0.0376, -0.0348, +0.1368, +0.4004, -0.4894, +0.1556, -0.1203,
+ -0.3302, -0.0035, -0.3673, -0.1165, +0.0151, -0.1661, -0.0333,
+ +0.0094, -0.0662, +0.1448, +0.1488, +0.0889, +0.0471, -0.0258,
+ -0.0398, +0.0644, +0.2740, +0.1195, +0.1212, +0.5019, +0.3957,
+ -0.0550, +0.0132, +0.1896, -0.2745, +0.1156, +0.0533, +0.0720,
+ -0.1548, +0.0618, +0.0207, -0.4556, +0.0640, -0.1698, -0.3250,
+ -0.0661, +0.1830, -0.0418, -0.2160, +0.1792, -0.0936, +0.4091,
+ +0.1251, -0.3348, -0.4267, -0.1236, -0.3609, -0.1682, -0.2184,
+ -0.0190, +0.1700, -0.1136, +0.0990, +0.1668, -0.4809, -0.0527,
+ +0.2783, -0.1648, +0.0666, -0.4016, -0.0171, -0.0927, +0.0272,
+ -0.0748, -0.2201, -0.1642, -0.1352, -0.2004, -0.1135, +0.0900,
+ -0.4194, -0.0612, +0.0011, -0.1709, -0.4136, +0.1379, -0.6458,
+ +0.0194, +0.0137, -0.2739, +0.1318
+ ],
+ [
+ +0.2941, +0.0220, -0.1901, +0.4145, -0.0985, +0.1034, -0.1606,
+ -0.3785, +0.0137, -0.3654, -0.0186, -0.0143, +0.5334, -0.6222,
+ -0.4792, -0.1071, -0.2142, +0.1365, +0.0561, -0.1022, -0.1284,
+ +0.0839, +0.5839, +0.1329, -0.4641, -0.3027, -0.4039, -0.0029,
+ +0.2187, +0.1188, +0.5330, -0.0991, +0.3822, +0.0137, +0.0068,
+ +0.6088, -0.4833, +0.2309, -0.0574, -0.3048, -0.2147, +0.4370,
+ -0.3575, +0.0376, -0.3573, +0.0106, -0.1274, -0.0276, -0.2841,
+ +0.3764, +0.0159, -0.3053, +0.0185, -1.1135, -0.2184, +0.2868,
+ -0.1948, -0.3448, -0.2687, -0.2092, +0.3704, -0.5749, +0.4552,
+ +0.1527, -0.1372, -0.0008, -0.4404, +0.0628, +0.2003, -0.0796,
+ -0.1033, +0.2826, -0.1446, +0.4242, +0.2081, -0.1591, +0.1138,
+ +0.5412, +0.1826, -0.1263, -0.3358, -0.3514, +0.2250, +0.0796,
+ +0.0664, -0.2066, -0.1902, +0.0692, -0.8032, -0.1846, -0.2625,
+ -0.2155, +0.1517, +0.3779, +0.0002, -0.2571, -0.5203, +0.0563,
+ -0.0233, -0.4733, +0.0410, +0.1257, -0.3867, +0.6560, +0.3189,
+ -0.3361, -0.2162, +0.1337, +0.4443, -0.7335, -0.0340, -0.4568,
+ +0.0073, +0.2620, +0.0836, +0.5431, +0.2070, +0.1648, +0.4627,
+ +0.1931, -0.1628, +0.0428, -0.3230, -0.0696, -0.1291, -0.4876,
+ +0.2044, +0.0711, -0.3727, -0.9706, +0.2452, -0.2355, +0.3298,
+ -0.4576, -0.0451, +0.0020, +0.2921, -0.2879, +0.0644, -0.0059,
+ -0.2419, -0.6224, -0.2768, +0.0733, -0.0946, -0.2335, -0.2709,
+ +0.2540, -0.0022, +0.2774, +0.4233, -0.1358, -0.3038, -0.0732,
+ -0.2940, -0.0601, -0.0490, -0.0736, +0.2752, -0.2957, -0.4769,
+ -0.3418, +0.1144, +0.3930, +0.0899, -0.3893, +0.5775, -0.0518,
+ +0.1399, -0.7618, +0.4657, -0.3672, -0.0523, +0.3073, +0.5092,
+ -0.4134, +0.1720, +0.1293, -0.2622, -0.0149, +0.2017, +0.0231,
+ +0.0923, +0.0600, -0.0503, +0.0357, +0.0251, -0.0905, -0.2991,
+ -0.2840, -0.3063, -0.0383, -0.3224, +0.0856, -0.3379, -0.3238,
+ -0.3563, +0.0566, -0.2433, +0.5548, +0.2207, -0.3068, +0.1781,
+ -0.0277, -0.1033, -0.2069, -0.0852, -0.2720, +0.2266, -0.4455,
+ -0.4335, -0.1705, -0.5232, +0.3662, +0.1381, +0.0554, +0.1357,
+ +0.0538, +0.2623, +0.1238, +0.3759, +0.3043, -0.1773, -0.0940,
+ -0.2739, +0.1256, +0.1502, +0.1216, -0.0704, +0.2648, -0.8330,
+ -0.4135, -0.1039, +0.2272, -0.2854, -0.0453, -0.0962, +0.2040,
+ +0.0299, -0.1373, +0.0682, -0.1713, +0.0790, +0.3156, +0.2651,
+ -0.0075, -0.5342, -0.1626, +0.1009, -0.6587, +0.0495, -0.1856,
+ -0.0264, +0.2003, +0.0970, +0.5477
+ ],
+ [
+ -0.0843, -0.1361, +0.1912, -0.0316, +0.2018, +0.2220, +0.0896,
+ -0.1140, -0.3395, +0.1175, +0.0195, +0.1345, +0.7176, -0.0023,
+ -0.0623, -0.4285, -0.2533, +0.1653, -0.1892, -0.2591, -0.0222,
+ +0.4811, +0.3804, -0.6267, +0.0661, -0.2997, -0.1037, -0.2822,
+ +0.2179, +0.5097, -0.4284, +0.0234, -0.6456, -0.6748, -0.3709,
+ +0.2922, +0.0364, -0.0016, +0.2550, +0.1511, +0.8175, -0.3177,
+ -0.1618, +0.4160, +0.3002, +0.3207, -0.0940, +0.5733, -0.3308,
+ -0.3418, -0.1644, +0.8835, -0.2148, +0.5474, +0.7365, +0.1159,
+ +0.1067, -0.1683, +0.1514, +0.2793, -0.4968, +0.0015, +0.1992,
+ +0.3220, +0.2362, -0.0786, -0.0150, +0.5711, +0.3905, +0.0680,
+ +0.0436, -0.3998, -0.0811, +0.1959, -0.0094, -0.1109, +0.1172,
+ +0.1006, +0.3143, -0.6284, -0.4603, -0.3960, -0.2248, -0.2018,
+ -0.5141, +0.2275, -0.0848, +0.2220, -0.0761, -0.1556, +0.3155,
+ +0.1383, -0.3033, +0.0635, +0.3345, -0.1475, -0.4953, +0.1489,
+ -0.1825, +0.1450, -0.0456, +0.5178, +0.0491, +0.1811, +0.3586,
+ -0.0473, -0.4100, +0.2251, +0.1919, +0.4225, +0.2881, +0.6324,
+ +0.4945, +0.1178, +0.0491, +0.2128, +0.2993, -0.3837, -0.1172,
+ +0.0124, +0.0371, +0.2162, +0.2179, +0.1030, +0.0420, +0.0790,
+ +0.2328, +0.0990, -0.2153, +0.2067, -0.4667, -0.0281, +0.6701,
+ +0.0075, -0.0643, +0.3304, +0.3305, +0.0434, -0.0464, -0.5063,
+ -0.0471, +0.0516, +0.5822, +0.1257, +0.0462, -0.3386, -0.2149,
+ -0.2992, +0.0527, +0.0824, +0.2613, +0.0924, +0.4538, -0.0282,
+ +0.2392, +0.2144, +0.7229, +0.0431, +0.1915, -0.0507, -0.0767,
+ +0.1742, +0.1127, +0.0046, +0.1055, -0.1077, +0.1028, -0.1411,
+ +0.0271, -0.2468, +0.0078, +0.8218, +0.2284, -0.0697, -0.4858,
+ +0.1976, -0.0677, -0.1624, -0.5139, +0.2680, -0.1931, -0.1948,
+ -0.0986, +0.2728, -0.0106, +0.3472, +0.1390, +0.0482, +0.2783,
+ +0.1914, +0.3759, +0.7947, +0.1301, +0.2698, -0.2852, +0.1829,
+ -0.1792, -0.1965, -0.2229, -0.0290, -0.2295, -0.0527, +0.3266,
+ -0.6782, -0.0526, -0.6328, -0.3130, -0.1752, -0.6948, +0.1168,
+ -0.0447, +0.3023, +0.3295, -0.1169, +0.3917, -0.0284, -0.2013,
+ +0.1160, -0.4516, +0.2057, +0.1743, +0.2170, +0.0565, +0.0296,
+ -0.5088, +0.3356, +0.4120, +0.0360, +0.3437, -0.0255, +0.2936,
+ +0.4064, +0.2476, +0.2951, -0.2482, -0.0586, -0.1699, +0.2201,
+ +0.3305, -0.4814, +0.1987, +0.4157, -0.4161, -0.0944, +0.2747,
+ +0.3026, -0.0213, +0.1782, +0.0389, +0.1663, +0.0189, -0.2328,
+ +0.0940, +0.1628, -0.1109, +0.0429
+ ],
+ [
+ -0.0600, -0.1769, +0.3178, -0.1525, -0.0294, +0.1050, +0.1154,
+ -0.2197, -0.2699, +0.2520, +0.1588, +0.0701, +0.0655, -0.1306,
+ +0.0669, -0.1458, +0.0213, -0.1133, -0.1469, -0.1980, +0.0767,
+ +0.4692, +0.2127, -0.0638, -0.0231, +0.1741, -0.2636, +0.1368,
+ +0.0576, +0.0814, -0.1222, -0.0941, -0.2273, -0.3099, -0.5212,
+ -0.1896, +0.0668, +0.2728, +0.1492, -0.0924, +0.3509, -0.1409,
+ +0.0554, +0.2494, +0.2829, +0.1790, +0.0423, -0.1140, -0.4169,
+ +0.0750, -0.2323, +0.2672, -0.2353, -0.0255, +0.4265, -0.4377,
+ -0.2580, +0.2028, +0.3246, +0.3485, -0.2017, -0.5991, -0.3987,
+ -0.2159, +0.0497, +0.3947, -0.1314, +0.0913, -0.1660, -0.2475,
+ +0.2048, -0.0474, -0.1865, +0.3779, +0.0325, -0.1807, +0.1053,
+ +0.0971, +0.0080, -0.2218, +0.0966, -0.3792, -0.2775, +0.3460,
+ -0.1778, +0.2605, +0.1486, -0.1431, -0.0835, +0.2096, +0.1590,
+ -0.2703, +0.2127, +0.1101, +0.1465, -0.0891, -0.3222, +0.0569,
+ +0.1747, +0.2375, -0.2103, -0.0107, -0.1136, +0.0976, -0.1933,
+ +0.0705, -0.1542, +0.3702, +0.2005, -0.3519, -0.5233, +0.1416,
+ -0.1070, +0.1114, +0.2615, +0.2433, +0.5091, +0.0241, -0.2689,
+ +0.0094, -0.2657, +0.2700, +0.2896, -0.2416, -0.1381, +0.0172,
+ -0.0888, +0.2495, -0.1275, +0.1384, +0.2493, -0.1006, +0.1217,
+ +0.1860, +0.1730, +0.0144, +0.2743, +0.0139, +0.1954, +0.0334,
+ -0.5526, +0.1759, +0.2292, -0.1091, +0.0799, -0.1606, -0.0049,
+ -0.5978, +0.2569, -0.0102, -0.2593, -0.3201, +0.4080, -0.2339,
+ +0.1308, -0.4308, -0.2824, +0.0948, +0.7695, -0.4378, +0.1011,
+ +0.3593, -0.1474, -0.0904, +0.2863, -0.1272, +0.2722, -0.1589,
+ +0.3337, -0.3030, -0.2071, +0.1580, +0.0440, -0.0403, -0.0289,
+ +0.1730, -0.4066, -0.3634, -0.2886, -0.1604, -0.4222, +0.2973,
+ -0.3061, -0.4018, -0.1095, +0.1043, +0.4336, -0.2122, +0.3761,
+ +0.3251, +0.3403, +0.2832, -0.3653, +0.1285, +0.0947, -0.1028,
+ +0.0759, +0.0091, -0.1404, -0.3382, -0.0116, -0.0665, -0.0503,
+ -0.1227, -0.5904, -0.3311, +0.0857, -0.0388, +0.2615, +0.0180,
+ -0.0250, +0.0630, +0.1653, -0.0476, -0.0966, +0.2017, +0.0159,
+ -0.1519, +0.1055, +0.2485, -0.3718, +0.0591, +0.1435, -0.2155,
+ -0.2704, +0.1420, +0.0775, +0.2138, -0.1687, -0.0246, -0.2106,
+ -0.1691, -0.5890, -0.3299, -0.1939, +0.1105, +0.2724, -0.1152,
+ -0.1633, -0.1843, +0.0688, +0.1945, -0.0483, +0.2670, +0.2457,
+ +0.3271, +0.2259, -0.0493, -0.2296, -0.2250, -0.1003, +0.0057,
+ +0.0178, +0.0639, +0.2316, +0.2037
+ ],
+ [
+ +0.0248, -0.2448, +0.2173, +0.0365, +0.4262, -0.4215, -0.6964,
+ +0.3486, -0.1507, -0.2265, -0.0195, -0.3793, -0.1171, -0.6551,
+ -0.5025, +0.2703, +0.0195, +0.7401, -0.2249, +0.1624, -0.3559,
+ +0.1671, -0.3274, -0.0635, -0.0416, -0.3006, +0.1383, -0.7318,
+ +0.1632, -0.4247, +0.4741, +0.0844, -0.0632, -0.4722, -0.5054,
+ +0.4905, +0.5495, +0.6109, +0.0572, +0.3081, -0.0805, +0.6664,
+ -0.2181, +0.4078, +0.0260, -0.2802, +0.3432, +0.0367, -0.1726,
+ +0.1598, -0.1072, -0.3405, +0.3679, -0.1774, -0.1992, +0.3341,
+ +0.2926, +0.3086, -0.1737, +0.0513, -0.0194, +0.2091, +0.1393,
+ -0.0138, -0.2954, +0.5209, +0.0900, -0.0735, -0.3146, -0.1453,
+ -0.1853, +0.0767, +0.0836, -0.1402, -0.2091, +0.0431, -0.7069,
+ +0.4933, -0.0008, -0.3814, +0.2925, +0.1641, -0.4744, -0.1731,
+ +0.2785, +0.1059, -0.0128, -0.3355, -0.5360, +0.0049, -0.2881,
+ -0.3139, +0.3992, +0.6875, +0.0258, -0.1211, -0.1585, -0.0085,
+ -0.4538, -0.3041, +0.3345, -0.3850, +0.3599, -0.1343, +0.2121,
+ +0.0439, +0.1215, -0.1166, +0.4186, +0.1313, +0.4669, -0.1825,
+ +0.0541, +0.0689, -0.6265, -0.1030, +0.1540, +0.1679, +0.3563,
+ -0.0089, +0.2719, +0.0045, -0.3466, -0.3818, +0.1228, -0.3765,
+ -0.2083, -0.5209, -0.3701, -0.5017, -0.1476, -0.0075, +0.4262,
+ -0.0348, +0.4371, -0.2563, -0.0859, -0.0206, -0.2822, -0.2257,
+ +0.2358, +0.1265, -0.1517, +0.4696, -0.1107, -0.5551, +0.2680,
+ +0.1019, +0.2076, -0.0010, +0.2203, -0.6511, +0.3485, +0.0486,
+ +0.3844, -0.3445, +0.4878, +0.2653, -0.0398, -0.0927, -0.3188,
+ -0.2537, -0.3103, -0.3086, +0.0133, -0.1711, +0.2899, +0.3109,
+ +0.1202, -0.2733, -0.5331, -0.1647, -0.0174, +0.6839, +0.0462,
+ +0.3668, -0.4232, -0.2460, +0.1788, -0.2271, +0.1934, -0.4205,
+ -0.2482, +0.1871, +0.1725, +0.0195, +0.1671, -0.0748, +0.1594,
+ -0.4028, -0.5530, -0.1366, +0.0947, -0.5861, +0.1717, +0.4299,
+ +0.1769, -0.1222, -0.1205, +0.9211, -0.1561, +0.3052, +0.1364,
+ -0.0049, +0.3333, +0.0219, -0.2358, +0.0258, -0.4461, +0.0581,
+ -0.0489, +0.0986, +0.1190, +0.1363, -0.3278, -0.2261, +0.4565,
+ -0.1150, -0.1474, +0.2775, -0.3371, -0.3235, -0.0857, +0.0439,
+ -0.3381, -0.0338, -0.0612, +0.3220, -0.1914, -0.1077, +0.2115,
+ -0.3086, -0.0831, -0.0529, -0.4690, +0.3315, -0.3761, -0.1943,
+ -0.2522, -0.4119, -0.6374, +0.1982, -0.5021, -0.1276, -0.2247,
+ -0.4073, +0.1517, -0.2968, -0.1528, -0.0687, -0.0439, -0.3185,
+ +0.4746, +0.1704, +0.7913, +0.8537
+ ],
+ [
+ -0.0125, +0.0339, +0.0942, +0.1065, -0.2941, +0.1880, +0.4836,
+ +0.3091, +0.0001, -0.3102, -0.0984, -0.0082, +0.1226, +0.1562,
+ +0.0370, +0.2486, -0.1902, +0.0980, +0.0569, +0.2838, -0.5228,
+ -0.0240, +0.2401, -0.1335, +0.4315, +0.1599, -0.2099, -0.2030,
+ -0.2261, -0.2225, +0.2794, +0.2605, +0.2303, -0.2839, -0.0076,
+ +0.2088, +0.0420, +0.3520, +0.1360, -0.3324, +0.0211, +0.2809,
+ -0.0747, +0.0811, -0.1446, -0.1106, +0.2177, +0.4078, +0.2303,
+ +0.3201, +0.0872, -0.4772, +0.0007, +0.3134, -0.0706, -0.1251,
+ +0.2119, -0.4185, -0.4953, +0.1104, -0.2654, +0.1992, +0.2499,
+ +0.0032, -0.0832, +0.1699, +0.0300, +0.1022, -0.4310, -0.1854,
+ +0.2048, +0.0844, +0.1295, -0.0258, -0.1136, -0.1858, +0.0968,
+ +0.0200, -0.2542, -0.3440, +0.5220, +0.4656, +0.2522, +0.1347,
+ -0.1479, +0.2996, -0.2121, +0.1431, -0.1702, +0.2667, -0.1621,
+ -0.0515, +0.4094, +0.1556, -0.3823, +0.0293, +0.1679, +0.3139,
+ -0.0769, -0.0349, +0.1449, +0.0096, -0.0654, +0.0196, +0.3611,
+ +0.5908, -0.2116, -0.0168, -0.2191, -0.0160, -0.0665, -0.2013,
+ -0.2676, -0.0631, -0.3607, -0.0609, -0.2878, +0.5278, -0.1225,
+ +0.3201, +0.3847, +0.0811, -0.0579, +0.0506, +0.1614, +0.1437,
+ +0.0211, +0.2910, -0.2963, +0.1751, +0.4307, +0.0372, -0.2564,
+ +0.3257, +0.0670, +0.2396, -0.0817, +0.1785, +0.1020, -0.1030,
+ +0.3187, +0.0634, -0.3035, +0.1635, +0.2071, -0.0078, -0.0155,
+ -0.1278, +0.1929, +0.2105, -0.2946, -0.3796, +0.2026, -0.3876,
+ -0.0989, +0.3802, -0.3621, +0.1792, -0.2667, +0.3769, +0.1683,
+ -0.0891, +0.2939, -0.3115, -0.1034, +0.2173, +0.0341, +0.0104,
+ -0.3272, +0.2046, -0.3682, +0.1443, -0.4883, +0.1637, +0.0262,
+ +0.5948, +0.3948, -0.2208, -0.1766, -0.1092, +0.0519, -0.1109,
+ -0.4795, -0.1470, -0.0981, +0.0981, +0.2791, -0.0836, -0.4717,
+ -0.3330, -0.3765, +0.1027, +0.1449, -0.4796, -0.1172, +0.3163,
+ +0.2038, -0.0142, -0.4739, +0.0642, -0.0241, -0.4661, -0.2000,
+ -0.4040, -0.1623, -0.1735, +0.2648, +0.2086, -0.0743, +0.1319,
+ -0.0413, +0.3020, -0.0398, +0.1025, -0.1678, -0.0976, -0.2039,
+ -0.0569, -0.0547, +0.1647, +0.0540, -0.1578, -0.6153, -0.2088,
+ +0.0829, -0.1087, +0.0918, -0.0570, -0.0744, +0.2033, +0.1149,
+ +0.1478, +0.0851, -0.0758, +0.1421, -0.2630, -0.2184, +0.0669,
+ -0.0678, -0.4329, -0.3416, +0.1028, -0.2887, -0.5655, +0.1929,
+ -0.3164, +0.3300, +0.1481, +0.4201, -0.4805, +0.0117, -0.1674,
+ +0.3126, +0.1827, +0.1008, +0.0737
+ ],
+ [
+ -0.1361, -0.0976, +0.2548, -0.0476, -0.4532, -0.6810, +0.2308,
+ +0.6115, -0.2814, +0.2722, +0.2492, -0.0879, -0.3156, +0.1095,
+ +0.4353, +0.5543, -0.4512, +0.3759, -0.1941, +0.2486, +0.2180,
+ +0.1404, +0.0420, +0.0321, -0.0613, +0.3774, +0.0299, +0.0147,
+ -0.5387, -0.1061, -0.0624, -0.0693, -0.4877, +0.0218, -0.0675,
+ -0.1379, +0.5339, +0.2936, +0.3321, -0.0093, +0.4609, +0.0401,
+ +0.1017, +0.0602, -0.2272, +0.2902, -0.1290, +0.0461, +0.1839,
+ -0.4958, -0.4016, +0.0207, +0.0800, -0.0977, -0.1117, -0.3743,
+ +0.2381, +0.0804, +0.0160, +0.2193, +0.0624, -0.2670, -0.2765,
+ -0.1272, -0.2503, -0.0461, -0.0810, +0.1734, -0.5187, +0.0158,
+ +0.0383, -0.0880, +0.2478, +0.3498, +0.3950, +0.0148, +0.1859,
+ +0.2575, -0.0965, +0.0871, +0.5933, -0.5955, +0.0979, -0.6478,
+ -0.2096, +0.0386, +0.4747, -0.4868, +0.0970, +0.0629, +0.1542,
+ +0.0641, +0.0440, -0.1722, -0.0876, -0.0216, -0.4929, -0.0594,
+ -0.1472, +0.1473, -0.2534, -0.1252, -0.2922, +0.3834, -0.0433,
+ +0.1348, +0.2073, +0.6652, +0.1094, -0.2942, -0.3063, +0.0313,
+ +0.0364, +0.1433, +0.3182, +0.1789, -0.0668, +0.4142, -0.1710,
+ +0.3241, +0.1707, -0.5370, +0.0198, -0.4291, -0.2010, -0.0989,
+ +0.0338, -0.0907, +0.4200, +0.1040, -0.1108, +0.3516, -0.2389,
+ +0.1904, +0.1677, -0.4324, +0.0204, -0.2520, -0.3342, +0.3865,
+ -0.5099, -0.3145, +0.2533, +0.2054, -0.0024, +0.3825, +0.0516,
+ -0.2741, -0.0854, -0.1404, +0.3892, +0.0950, -0.5328, +0.0325,
+ +0.4394, -0.2918, -0.2817, +0.0056, +0.3267, +0.0249, -0.4757,
+ -0.1443, +0.2780, +0.0383, +0.1080, -0.1130, +0.0432, +0.2240,
+ -0.3109, +0.2280, -0.1656, +0.3653, +0.1266, -0.0294, +0.2328,
+ +0.0724, -0.1120, +0.0199, +0.6213, -0.0422, -0.0816, -0.1795,
+ -0.1076, +0.1642, -0.1244, +0.3217, -0.3620, -0.1502, -0.5481,
+ -0.6521, +0.1581, -0.5252, -0.0355, -0.1297, -0.0878, -0.0257,
+ +0.0288, -0.0401, -0.3398, -0.3273, -0.0481, -0.4680, +0.0941,
+ -0.1850, +0.5048, +0.2087, +0.1509, +0.0988, -0.2888, -0.5772,
+ +0.3615, +0.3422, +0.1228, +0.1141, -0.1387, -0.2812, +0.0682,
+ +0.4771, +0.3319, -0.0814, +0.0206, +0.5814, -0.0499, +0.0058,
+ -0.4338, -0.1293, -0.2039, -0.1165, -0.1489, -0.4010, +0.3295,
+ -0.4514, -0.1156, -0.3898, +0.1227, -0.0742, +0.1991, +0.3631,
+ +0.0632, -0.5420, -0.0657, -0.2362, -0.0365, +0.0654, -0.0587,
+ -0.7026, -0.0105, -0.0963, +0.0904, -0.2143, +0.0118, +0.4974,
+ -0.6794, +0.2728, +0.1461, -0.4021
+ ],
+ [
+ +0.2911, +0.0252, +0.0441, -0.1234, +0.1550, -0.2065, +0.1747,
+ +0.1595, +0.1185, +0.1842, +0.1109, +0.2428, +0.0372, +0.0421,
+ -0.0559, +0.4316, +0.1375, +0.1832, +0.2081, +0.0060, +0.3478,
+ +0.0078, +0.4174, -0.2214, +0.2263, -0.1045, -0.1597, +0.0060,
+ +0.1511, +0.0521, +0.0738, +0.0968, -0.1308, -0.0186, -0.3695,
+ -0.2996, +0.3190, -0.2862, +0.1596, -0.4530, +0.2555, -0.0150,
+ -0.3202, -0.0093, -0.0696, +0.4508, +0.2378, -0.2935, -0.0845,
+ -0.2027, -0.3102, +0.0103, -0.1468, +0.6637, +0.1318, -0.3989,
+ -0.1223, +0.2322, +0.2325, +0.1941, +0.2911, +0.1567, -0.0603,
+ -0.2620, -0.2573, +0.0699, -0.0802, +0.1799, +0.0001, +0.0352,
+ +0.0766, -0.1832, +0.1431, +0.2031, +0.2651, +0.0714, -0.2598,
+ +0.0053, +0.1373, +0.1325, +0.1409, -0.2189, +0.0365, -0.1192,
+ +0.2667, -0.0102, +0.1253, -0.0278, -0.0346, +0.1614, +0.0764,
+ -0.1752, +0.3285, -0.1769, +0.0560, +0.3775, -0.2392, -0.0972,
+ -0.2325, -0.2187, -0.0783, +0.2324, +0.1628, +0.0399, -0.0534,
+ -0.1589, +0.0373, +0.2408, +0.0807, +0.1918, +0.1144, +0.2444,
+ +0.3656, +0.1358, +0.2533, +0.3330, +0.2993, +0.0931, -0.0197,
+ +0.2733, +0.2069, +0.2868, -0.1247, -0.2558, -0.2353, +0.2030,
+ +0.2879, +0.1017, -0.2530, +0.0451, -0.4580, +0.2718, -0.4685,
+ -0.0309, -0.1339, -0.1899, +0.1198, -0.3026, -0.0639, +0.1232,
+ +0.0415, -0.2986, -0.2040, -0.0716, +0.1659, -0.1350, -0.1966,
+ -0.2942, -0.2841, -0.3668, +0.9108, +0.1547, -0.2661, +0.0232,
+ +0.1595, +0.2270, -0.3725, +0.0234, -0.1675, -0.2936, -0.1094,
+ -0.0938, -0.0266, -0.1504, +0.0602, +0.4208, -0.1584, +0.4186,
+ +0.0688, +0.1242, -0.1871, +0.6453, +0.0872, -0.2200, -0.1441,
+ -0.1716, +0.1579, -0.4258, -0.1333, +0.1831, +0.2060, -0.2931,
+ -0.3437, +0.1329, -0.3451, +0.2567, -0.0931, +0.3409, -0.0909,
+ +0.1106, -0.1024, -0.1636, +0.1012, +0.2364, -0.0400, +0.3681,
+ -0.2308, -0.0585, -0.1258, +0.1280, +0.0825, -0.2495, -0.2131,
+ -0.0132, +0.2915, -0.0689, -0.1753, +0.0512, -0.1871, -0.0144,
+ +0.0385, +0.1749, +0.1746, -0.1735, +0.1271, -0.1452, -0.1364,
+ +0.3078, -0.1171, +0.1335, -0.0730, +0.1279, -0.1821, -0.1351,
+ -0.0292, -0.1827, +0.0275, -0.1182, -0.1565, +0.0669, -0.1174,
+ -0.4445, +0.3324, +0.0200, +0.4529, +0.2224, +0.0731, +0.1084,
+ +0.0158, -0.3577, +0.0603, +0.0354, +0.0818, +0.3384, +0.1224,
+ +0.0543, -0.0367, -0.0182, -0.0817, +0.0739, +0.3456, +0.2242,
+ +0.1394, +0.1080, +0.4645, -0.0836
+ ],
+ [
+ -0.0479, +0.1331, -0.0916, -0.0002, -0.1733, -0.1774, +0.4257,
+ +0.1671, -0.2073, +0.2273, +0.3339, +0.0408, +0.1382, +0.0528,
+ +0.0805, +0.3353, +0.0578, +0.0059, +0.0316, +0.1117, -0.1136,
+ +0.3098, -0.0467, +0.3397, -0.2236, -0.0664, -0.2431, +0.4334,
+ -0.3122, +0.5193, +0.0094, +0.0254, -0.1745, +0.2182, +0.0422,
+ -0.0916, +0.0505, +0.3262, +0.1174, -0.3048, -0.1399, -0.0850,
+ +0.1519, +0.3870, +0.0971, -0.0171, -0.0356, +0.1490, -0.4502,
+ -0.1160, +0.0318, +0.0634, -0.0023, -0.0194, -0.2932, -0.0333,
+ +0.3558, +0.3744, -0.2504, -0.0194, +0.0595, -0.0212, +0.2327,
+ -0.1196, +0.1403, +0.4866, -0.2335, -0.1282, +0.1314, -0.3898,
+ +0.0061, -0.1864, -0.2772, +0.0064, -0.1581, -0.0937, +0.0922,
+ +0.0080, +0.2430, -0.1993, -0.3810, +0.0056, -0.2256, +0.1696,
+ +0.0573, +0.1619, +0.1918, -0.1466, -0.0888, -0.1172, +0.1264,
+ -0.1207, -0.0221, +0.1458, -0.1771, +0.1786, +0.0579, +0.2019,
+ -0.2409, +0.1583, +0.1189, +0.4001, -0.5152, +0.4519, -0.0767,
+ +0.1069, +0.0321, +0.2578, -0.0971, -0.1077, -0.0422, -0.1098,
+ +0.1311, -0.0872, -0.1170, +0.1748, -0.3340, -0.5122, +0.0460,
+ +0.0176, +0.1353, -0.0354, +0.1726, +0.1428, +0.2590, +0.5661,
+ +0.3093, -0.0381, +0.3977, +0.1259, +0.5698, +0.4974, -0.0609,
+ -0.0936, -0.4606, +0.0318, -0.5266, -0.0934, -0.3129, +0.0124,
+ -0.3269, -0.1724, -0.4367, -0.2131, +0.1322, +0.1437, -0.0196,
+ +0.0439, +0.0736, -0.3361, +0.2174, +0.4335, -0.2091, +0.1897,
+ +0.3060, -0.0883, +0.2073, -0.1840, -0.1963, -0.1535, -0.2841,
+ +0.1253, +0.1264, -0.1940, -0.2254, +0.1820, -0.1039, -0.0036,
+ +0.3465, +0.0028, +0.1394, +0.1971, +0.2045, -0.0696, -0.1166,
+ +0.1119, +0.1891, -0.1620, +0.0795, -0.1819, -0.3050, +0.2498,
+ -0.0021, +0.2290, -0.5197, +0.2111, -0.0612, +0.0092, -0.2305,
+ -0.3659, +0.0075, +0.3581, +0.0471, +0.1735, +0.1062, -0.0882,
+ -0.1167, -0.0042, +0.4123, -0.0168, +0.0636, +0.2696, +0.5927,
+ -0.2619, -0.1943, -0.0427, +0.0867, +0.0194, +0.0851, +0.0975,
+ -0.0781, -0.1522, -0.3116, +0.1528, -0.1430, +0.1754, -0.1765,
+ +0.4800, -0.0084, -0.0873, -0.1647, +0.1148, +0.2186, +0.0590,
+ -0.0251, -0.1672, -0.0842, +0.0781, +0.0659, +0.2357, +0.1831,
+ +0.0591, +0.1442, +0.1315, +0.0251, -0.2479, -0.0610, -0.0266,
+ +0.1820, -0.3100, -0.2956, +0.2264, -0.3252, -0.0502, +0.0081,
+ +0.0171, -0.0082, -0.1259, -0.1426, -0.0384, -0.1705, +0.2844,
+ -0.0812, +0.4512, +0.1431, -0.2101
+ ],
+ [
+ +0.3975, +0.0603, +0.2624, +0.4018, +0.1623, -0.0238, +0.1034,
+ +0.2576, +0.0364, -0.3271, -0.4375, +0.2982, -0.6016, +0.1980,
+ +0.0986, +0.6358, +0.6067, -0.3525, +0.1575, +0.0705, -0.0740,
+ +0.1200, +0.1813, +0.0418, -0.1777, -0.5141, -0.3394, +0.1700,
+ -0.3651, -0.3544, -0.0387, +0.1712, -0.1980, +0.1041, +0.0161,
+ +0.6207, +0.1048, +0.1848, +0.0753, +0.2312, -0.3344, +0.1452,
+ +0.2946, +0.3253, +0.0775, +0.1658, -0.4919, -0.2192, -0.0671,
+ -0.1306, -0.1427, -0.2229, +0.1491, +0.1053, -0.0729, -0.2558,
+ -0.3453, +0.2334, +0.1523, +0.4557, +0.1303, -0.1611, +0.1525,
+ -0.3323, +0.0807, -0.0636, -0.0087, +0.0266, +0.1338, +0.1611,
+ -0.3803, -0.0139, +0.2500, +0.1019, +0.6161, -0.1879, -0.2951,
+ -0.2619, +0.0861, -0.0798, -0.6109, -0.6078, +0.2102, -0.0896,
+ +0.5327, +0.0187, +0.5059, -0.0105, +0.1004, +0.2203, +0.0590,
+ -0.0620, +0.3079, +0.0536, -0.1042, +0.7077, -0.1788, -0.0468,
+ -0.3501, +0.2258, -0.0149, +0.4304, +0.0227, -0.2189, -0.3309,
+ -0.2264, +0.1553, +0.0774, +0.0090, +0.2321, -0.3405, +0.1789,
+ +0.0719, +0.0029, -0.0421, +0.1266, -0.1958, +0.3099, -0.1819,
+ +0.1510, +0.0047, +0.3718, -0.1612, +0.0734, +0.4715, +0.6387,
+ +0.4123, -0.1210, +0.0085, -0.2726, +0.2627, +0.2969, +0.2179,
+ +0.2094, +0.1807, +0.3879, -0.5351, -0.5429, -0.5244, -0.1714,
+ +0.3948, -0.0217, +0.5449, -0.3176, +0.4858, +0.1822, -0.1967,
+ -0.1345, -0.0321, -0.2816, -0.0004, -0.0433, -0.3497, -0.3879,
+ +0.1900, -0.1076, -0.1775, -0.6605, -0.4304, -0.1296, -0.3042,
+ +0.3626, -0.1161, -0.1033, +0.1811, +0.0216, -0.0146, -0.0116,
+ -0.0426, -0.1701, +0.0427, +0.3073, -0.1439, +0.2131, -0.2708,
+ -0.0942, -0.0583, -0.3204, -0.0184, -0.1194, +0.1047, +0.0952,
+ -0.0431, +0.1094, -0.0274, -0.3901, -0.2028, +0.1787, -0.1761,
+ -0.1447, +0.3204, +0.0693, -0.6784, -0.1707, -0.1779, -0.2513,
+ -0.1666, -0.1050, +0.0455, +0.0593, -0.0933, -0.3976, -0.1421,
+ -0.2670, +0.6564, -0.2088, -0.2548, +0.4063, -0.4954, +0.1265,
+ +0.0968, -0.0323, -0.0741, -0.0125, -0.0264, +0.1841, -0.0046,
+ -0.2472, +0.0703, -0.1902, -0.3295, -0.0920, +0.2232, -0.3756,
+ -0.0381, -0.6690, -0.2531, -0.0335, -0.2410, +0.0129, -0.2026,
+ -0.0618, -0.1672, -0.0934, -0.2651, -0.1886, +0.3258, +0.2041,
+ +0.1016, -0.1330, -0.2496, -0.3590, +0.1134, +0.2793, -0.1895,
+ +0.0942, -0.0140, +0.1660, -0.0332, -0.1366, +0.0506, +0.2313,
+ -0.3251, +0.2350, +0.1984, -0.3045
+ ],
+ [
+ -0.1244, +0.0467, -0.2788, +0.4575, -0.0748, -0.4002, +0.8065,
+ -0.4954, +0.4621, -0.0297, +0.1578, +0.5572, -0.4810, -0.3364,
+ +0.1981, -0.4577, -0.5189, -0.2748, -0.3190, -0.1295, -0.2100,
+ -0.3129, +0.0677, -0.3496, +0.2366, -0.4851, +0.1440, -0.3993,
+ -0.3010, +0.1903, -0.0104, +0.2706, +0.0560, +0.1651, -0.3059,
+ +0.1723, -0.0381, +0.0744, +0.3331, +0.0662, +0.2514, -0.1483,
+ -0.1333, -0.2432, -0.1971, -0.2435, -0.4451, +0.0307, +0.2830,
+ +0.1034, +0.4785, -0.0338, +0.4945, -0.2218, -0.4259, +0.1723,
+ -0.3336, -0.1547, -0.5019, +0.7082, -0.5717, +0.4096, -0.6571,
+ +0.0823, -0.0680, -0.1518, +0.1608, +0.4834, -0.2698, -0.4448,
+ -0.1332, -0.1917, +0.0868, -0.1208, +0.5762, -0.2558, +0.1775,
+ +0.0565, -0.0321, -0.5963, -0.2200, +0.6051, -0.6825, +0.0358,
+ +0.1749, +0.6319, -0.8650, -0.2608, -0.0685, +0.2391, -0.0369,
+ -0.0770, -0.4179, -0.0079, +0.2566, +0.3069, -0.1205, -0.0178,
+ -0.6410, +0.1569, -0.3519, -0.2583, -0.3258, -0.7489, -0.2438,
+ -0.3257, -0.3815, -0.9372, +0.0860, +0.2511, -0.3017, +0.0428,
+ -0.2221, +0.3140, +0.2347, -0.1383, +0.0511, -0.6644, -0.5659,
+ -0.4956, +0.1200, +0.0444, +0.1911, +0.0424, -0.0573, +0.2888,
+ -0.0837, -0.4370, -0.1554, +0.2436, -0.3111, -0.1141, +0.0500,
+ +0.4466, -0.1981, -0.4976, -0.2438, +0.3547, -0.3850, -0.4817,
+ +0.3871, +0.2476, -0.0043, -0.3596, -0.5270, +0.3349, -0.0573,
+ -0.2888, +0.3322, -0.5017, +0.1827, -0.0712, +0.2914, +0.5111,
+ -0.2119, +0.2552, -0.1014, -0.0706, -0.3091, -0.4019, +0.3362,
+ -0.4000, -0.4460, -0.0660, -0.0115, -0.0576, -0.1440, +0.1168,
+ -0.2178, -0.2009, -0.2137, +0.2927, +0.2332, -0.6983, -0.2708,
+ +0.2801, -0.3586, -0.0667, +0.0526, -0.2045, -0.1303, -0.5292,
+ +0.4341, +0.1684, +0.4273, +0.0900, -0.4618, -0.0819, -0.0289,
+ -0.4542, +0.0024, +0.2126, -0.2633, +0.0579, +0.0425, -0.0113,
+ +0.0473, -0.6465, +0.0824, -0.0409, +0.1870, -0.3765, -0.2056,
+ -0.2201, -0.3408, +0.1940, -0.0177, +0.0060, +0.3177, -0.2964,
+ +0.1934, +0.6009, -0.3270, -0.0354, -0.2978, +0.0542, +0.0680,
+ +0.0100, +0.1105, -0.0325, -0.2642, +0.0597, -0.4088, +0.0358,
+ +0.3133, +0.3854, -0.0946, -0.0004, -0.0382, -0.3050, -0.2804,
+ -0.4568, -0.0950, -0.4881, +0.0035, +0.0202, -0.1340, -0.1794,
+ +0.6133, +0.2774, +0.0348, +0.0286, -0.4590, +0.1485, -0.7287,
+ +0.4565, -0.1745, -0.3535, -0.4678, +0.3834, -0.6188, -0.7744,
+ +0.3191, -0.0715, +0.1052, -0.0231
+ ],
+ [
+ +0.0580, -0.3371, +0.3239, +0.3150, -0.3001, +0.1801, -0.0312,
+ -0.5783, -0.0172, -0.2807, +0.0673, +0.4073, +0.2058, -0.0427,
+ +0.3201, -0.2968, +0.0349, -0.0799, -0.0138, -0.1815, -0.0677,
+ +0.0024, +0.2618, -0.0787, +0.3508, -0.4335, -0.5828, -0.2823,
+ -0.1908, -0.1853, +0.1219, +0.0701, -0.2294, +0.2899, -0.1157,
+ +0.1798, +0.3162, +0.0430, +0.5583, +0.1997, +0.1252, +0.0226,
+ +0.0324, -0.4922, -0.0369, -0.0692, -0.4051, -0.1870, +0.0089,
+ +0.3477, -0.0689, +0.1811, +0.2633, -0.2877, -0.1416, +0.1487,
+ +0.2070, +0.5753, +0.2179, +0.3493, -0.0858, -0.1485, +0.1173,
+ -0.2726, +0.0917, +0.2187, +0.2546, -0.0227, -0.0932, -0.4266,
+ -0.0505, -0.1081, -0.0286, -0.1489, +0.1425, -0.2813, +0.5944,
+ +0.0710, -0.2507, -0.3329, +0.3650, +0.1446, -0.2549, +0.4105,
+ +0.0349, +0.3155, -0.0624, +0.5752, -0.1162, +0.0195, -0.1993,
+ +0.0881, +0.0697, +0.4865, +0.2223, +0.0368, +0.1157, +0.1420,
+ +0.4291, +0.1668, +0.0772, +0.1248, -0.1832, +0.3463, +0.2325,
+ -0.1066, -0.0909, -0.1951, +0.1902, +0.3861, -0.0333, -0.0321,
+ -0.3942, +0.0205, +0.0115, +0.3744, -0.3810, -0.2990, -0.1335,
+ -0.2115, -0.1880, +0.6321, +0.1321, -0.2987, -0.0758, +0.1898,
+ -0.4732, +0.5376, -0.0909, +0.0027, +0.3838, +0.3588, -0.0469,
+ +0.1783, +0.1699, +0.1422, -0.0621, -0.3444, -0.4191, -0.3353,
+ +0.1657, +0.2193, +0.1733, -0.1795, -0.1521, +0.2495, +0.0659,
+ -0.2625, -0.0148, -0.1001, -0.0658, +0.1761, +0.3362, -0.1943,
+ -0.6844, +0.0543, -0.1504, -0.0522, +0.4026, -0.0019, +0.2111,
+ +0.0205, +0.0599, +0.0294, -0.2959, +0.3209, +0.0298, +0.2731,
+ +0.1676, +0.1578, -0.1474, +0.0302, +0.1557, -0.1848, -0.3529,
+ +0.3117, -0.4560, -0.1120, +0.1324, -0.1800, +0.1793, -0.2910,
+ -0.1240, -0.1297, +0.2881, +0.0235, -0.1947, -0.4855, -0.0345,
+ -0.3622, -0.2499, +0.0088, -0.1905, +0.0603, +0.1892, -0.0315,
+ +0.0295, -0.2410, +0.0864, +0.0888, -0.0964, +0.1514, +0.0060,
+ -0.0862, -0.4172, +0.0968, +0.3526, -0.2188, +0.0880, -0.1246,
+ +0.2900, -0.1955, +0.2456, -0.2717, -0.3450, +0.2010, -0.0474,
+ -0.4630, +0.1374, +0.1800, -0.1061, +0.2078, -0.2144, +0.0447,
+ -0.0025, -0.0561, +0.4208, +0.2254, -0.0628, +0.2521, -0.2476,
+ +0.0794, +0.2266, -0.2359, +0.2156, +0.2297, +0.3097, +0.2366,
+ -0.0859, -0.2971, -0.2814, +0.2527, -0.1882, +0.1252, -0.1642,
+ +0.1704, +0.4092, -0.0192, +0.2157, -0.2505, -0.3426, -0.3608,
+ +0.2457, +0.1501, -0.1108, -0.2853
+ ],
+ [
+ +0.7381, -0.2475, -0.0494, -0.8059, -0.3116, +0.1576, +0.1347,
+ -0.0784, +0.0452, -0.2930, -0.1851, -0.6253, +0.0669, -0.6952,
+ -0.1905, +0.1123, +0.0303, +0.0440, +0.0817, +0.2308, -0.0063,
+ +1.0707, -0.2214, +0.0562, -0.0705, +0.1031, +0.1280, +0.0245,
+ +0.1798, +0.0761, +0.0530, +0.6943, -0.0402, -0.2658, +0.7095,
+ -0.0842, +0.1608, -0.4585, +0.4220, -0.1964, +0.5404, +0.1161,
+ +0.0050, +0.4415, +0.5303, +0.0945, +0.0919, +0.6751, -0.1676,
+ +0.5655, -0.0321, -0.3334, -0.0581, +0.1706, -0.2093, -0.1301,
+ +0.2631, -0.4652, +0.0640, +0.3510, -0.2780, +0.3195, +0.4595,
+ -0.2393, -0.6972, -0.0133, -0.1362, -0.1866, +0.1914, -0.2980,
+ +0.6745, +0.1496, +0.0493, +0.0787, +0.3799, -0.4630, -0.8067,
+ -0.0254, -0.0671, +0.4575, -0.2982, -0.3343, -0.0386, -0.5071,
+ -0.1302, -0.0116, +0.1203, +0.1037, +0.0925, +0.3226, -0.4569,
+ +0.5480, +0.3634, +0.4034, -0.0447, -0.2874, -0.3197, +0.1841,
+ +0.0943, +0.2061, -0.0682, -0.1927, -0.3331, +0.5746, +0.5211,
+ +0.1638, -0.7889, -0.1275, +0.4053, +0.3205, +0.3071, -0.3261,
+ +0.4975, +0.3669, +0.2436, +0.0290, +0.0485, +0.0254, -0.9289,
+ -0.0045, -0.1394, +0.3343, -0.5084, -0.3056, +0.0270, -0.0177,
+ -0.4645, -0.4447, +0.2515, -0.1789, -0.0150, +0.1901, -0.3010,
+ +0.2151, +0.0271, +0.3128, -0.4510, +0.1436, +0.1326, -0.5074,
+ -0.1928, -0.2072, -0.0506, +0.0585, +0.2597, +0.0557, +0.1554,
+ +0.0637, +0.1753, +0.1603, -0.0491, +0.0947, -0.0947, -0.0386,
+ +0.0485, +0.1325, +0.3477, +0.0992, -0.3166, +0.2578, -0.3771,
+ -0.6604, +0.3837, +0.4531, -0.1933, +0.0080, +0.2843, -0.1099,
+ -0.2604, +0.1090, -0.2726, -0.0214, +0.1486, +0.6095, +0.0327,
+ +0.2487, -0.2636, -0.0398, -0.0023, -0.2461, +0.4543, +0.3383,
+ +0.0459, +0.3432, +0.3111, -0.0287, -0.3101, -0.1319, +0.0269,
+ +0.0879, +0.1646, -0.3670, -0.0204, -0.1816, +0.3627, +0.3105,
+ -0.1901, -0.8469, -0.1429, -0.0095, +0.7778, -0.0932, -0.0653,
+ -0.2607, -0.2949, +0.2495, -0.1045, -0.6736, -0.0541, -0.6866,
+ +0.1623, +0.4817, -0.3854, -0.1670, -0.4186, -0.2369, +0.1780,
+ -0.5476, +0.2418, +0.0207, +0.1405, -0.3712, -0.2743, +0.0896,
+ +0.3807, +0.7793, +0.1667, +0.0631, -0.2508, +0.6040, -0.1580,
+ -0.2618, +0.2751, +0.2168, +0.3795, -0.2427, -0.4092, +0.2154,
+ -0.8448, +0.3266, +0.5106, -0.6358, -0.2464, -0.4913, -0.4326,
+ -0.4836, -0.7830, +0.5032, +0.1403, +0.1921, -0.4615, +0.3502,
+ +0.5148, +0.0262, -0.0378, +0.0218
+ ],
+ [
+ -0.0206, +0.0659, -0.2565, -0.1178, -0.0108, -0.5836, +0.2226,
+ -0.0939, -0.0271, +0.2265, +0.0943, -0.1793, +0.1053, -0.1203,
+ -0.0704, +0.2342, +0.1546, +0.4810, -0.1052, +0.1559, -0.0555,
+ +0.2432, +0.2105, -0.3110, +0.0955, +0.1117, +0.3404, +0.0115,
+ -0.2706, +0.1904, +0.3692, +0.2379, +0.1437, +0.0253, +0.3716,
+ +0.1286, +0.2525, -0.2104, +0.2484, -0.3496, +0.1212, -0.2015,
+ -0.1019, +0.2766, +0.2695, +0.1454, -0.5423, +0.2566, -0.0013,
+ +0.1011, -0.1921, -0.0071, -0.0599, +0.2944, -0.2065, +0.1577,
+ -0.0255, +0.2411, +0.0634, -0.0065, -0.1555, -0.1093, +0.3201,
+ +0.1953, +0.0549, +0.0787, -0.0385, -0.3140, +0.2594, -0.0827,
+ +0.3342, +0.0012, -0.0240, +0.1015, +0.0216, +0.0185, -0.1822,
+ +0.2033, -0.0328, -0.1944, -0.2264, +0.0489, +0.2461, +0.1915,
+ +0.1118, -0.2512, +0.3018, -0.0487, -0.2431, -0.0076, -0.0899,
+ -0.1716, +0.2301, +0.1369, -0.3787, -0.1428, -0.0987, -0.2805,
+ -0.1682, +0.4088, -0.0173, +0.2908, -0.2743, +0.0587, +0.4514,
+ -0.0456, -0.4386, +0.3342, +0.0661, +0.0353, +0.4922, -0.7322,
+ +0.3238, -0.2757, -0.0458, -0.0987, +0.0529, -0.1216, -0.2411,
+ +0.1616, -0.0720, +0.5098, -0.1742, -0.2574, +0.0332, -0.0881,
+ -0.2096, +0.0546, +0.1921, -0.3496, +0.2334, -0.4729, +0.1516,
+ -0.0504, +0.1546, +0.1410, -0.1773, +0.5221, -0.3395, -0.3449,
+ +0.3083, +0.0403, -0.1190, -0.0325, +0.2385, +0.0123, +0.2955,
+ -0.1028, -0.0572, -0.0628, -0.3075, -0.0982, -0.1004, +0.3240,
+ -0.0951, +0.5076, -0.1176, +0.3036, -0.0862, +0.1839, -0.3230,
+ -0.5516, +0.1847, -0.0974, -0.3160, +0.5997, -0.2010, -0.1829,
+ +0.0963, +0.3688, -0.1199, +0.2221, +0.2468, +0.1372, +0.1562,
+ +0.4491, +0.0962, -0.1357, -0.1821, -0.1760, +0.2399, -0.4287,
+ +0.1030, -0.1147, +0.3199, -0.0476, -0.3862, -0.3519, +0.4984,
+ -0.1864, +0.0967, +0.0678, -0.0255, +0.0495, -0.0430, +0.3054,
+ +0.2907, -0.4478, +0.1105, -0.1157, +0.2442, -0.3512, +0.0636,
+ -0.2319, +0.0601, +0.3072, -0.2897, -0.4553, +0.0210, +0.0958,
+ -0.4464, +0.4383, +0.2507, +0.1024, -0.0568, -0.3112, -0.2059,
+ -0.4570, +0.2250, -0.2215, +0.1468, +0.1813, -0.2931, +0.1007,
+ -0.0960, +0.2029, +0.4445, -0.0166, -0.1324, -0.0913, +0.1978,
+ -0.2619, +0.0271, +0.2970, -0.0730, +0.0342, -0.1097, +0.0822,
+ -0.1587, +0.0859, +0.2537, -0.0574, -0.0527, -0.5641, -0.1083,
+ -0.0059, -0.1982, +0.1345, +0.0167, +0.0796, +0.2063, -0.1226,
+ +0.2049, +0.0640, +0.1948, +0.2156
+ ],
+ [
+ +0.5519, +0.0513, -0.2814, -0.1081, +0.4918, +0.3216, +0.0762,
+ +0.0575, -0.2296, +0.1430, -0.0473, -0.2251, +0.3829, -0.5347,
+ +0.4668, -0.6335, +0.2985, -0.0935, +0.4089, -0.2893, -0.3299,
+ -0.3789, -0.3584, +0.0124, -0.0628, -0.1894, -0.5388, +0.0133,
+ +0.0361, -0.2352, -0.0468, -0.6312, +0.4365, -0.1059, +0.0632,
+ -0.4930, -0.2637, +0.3447, -0.1379, +0.5067, +0.0147, +0.2901,
+ -0.1365, -0.0063, -0.2201, -0.4227, -0.0173, -0.2490, +0.3692,
+ +0.0920, +0.4893, +0.5749, -0.1984, +0.3157, +0.0180, -0.0667,
+ +0.0169, -0.0173, -0.1439, -0.1318, +0.3033, -0.0239, -0.1698,
+ +0.0777, -0.3522, -0.1974, -0.0287, -0.0749, +0.2130, -0.2972,
+ +0.3312, -0.0111, +0.3668, -0.2288, +0.1613, -0.1882, +0.1315,
+ -0.1463, +0.5001, -0.0885, +0.3079, -0.4730, +0.0129, -0.4098,
+ -0.2915, -0.1633, +0.4581, +0.3639, +0.0429, +0.0489, -0.5022,
+ -0.2359, -0.7827, -0.4324, -0.0656, +0.2880, +0.2235, +0.3295,
+ -0.4484, -0.0991, +0.3212, +0.2464, -0.2285, -0.0386, -0.0746,
+ +0.2591, -0.0314, -0.1551, +0.0027, +0.0949, -0.1944, +0.3021,
+ +0.0144, +0.2922, +0.4638, -0.6117, +0.2648, +0.4724, +0.4701,
+ -0.4681, +0.2530, +0.1654, +0.1597, -0.5759, +0.3194, +0.3979,
+ -0.2799, -0.1007, -0.1350, +0.2451, -0.3349, +0.4901, -0.4146,
+ -0.0482, -0.2564, -0.3343, +0.1317, -0.2191, +0.1227, +0.1225,
+ +0.2376, +0.0775, +0.4042, +0.2867, -0.0208, +0.0251, +0.0629,
+ +0.2248, +0.3367, -0.4687, +0.6583, -0.2974, -0.3763, -0.3273,
+ -0.2385, +0.3309, +0.0276, +0.2650, +0.1817, -0.1479, +0.0767,
+ +0.0040, +0.0864, +0.0370, -0.3777, +0.0365, -0.2231, +0.1891,
+ -0.7009, -0.0407, +0.2263, -0.2734, -0.2038, -0.3759, +0.1326,
+ -0.0957, -0.0955, -0.3577, +0.2432, -0.3343, -0.0818, +0.4028,
+ +0.2523, -0.2782, -0.2638, +0.5693, -0.0417, -0.1251, +0.3552,
+ -0.2030, +0.3901, +0.6543, -0.0449, +0.1659, -0.5343, +0.1039,
+ -0.2405, -0.1986, +0.3727, +0.0126, -0.0750, -0.1492, -0.1449,
+ +0.5876, +0.1234, -0.5702, +0.1546, +0.2700, +0.3258, +0.4746,
+ -0.0436, +0.2323, -0.2355, -0.4237, +0.1582, +0.2140, +0.5732,
+ +0.3075, -0.3210, +0.3381, +0.3614, -0.0347, +0.4458, -0.0468,
+ -0.0211, -0.6787, -0.2945, -0.5741, -0.0622, +0.5319, +0.3267,
+ +0.0316, +0.1697, -0.0413, +0.1485, -0.0395, -0.2128, +0.2895,
+ -0.3552, -0.1553, -0.3712, +0.1985, +0.5970, +0.4085, +0.0845,
+ +0.0485, +0.5842, +0.0358, -0.3295, +0.0578, -0.0269, -0.3693,
+ -0.3669, +0.1904, +0.2907, +0.1336
+ ],
+ [
+ -0.0663, -0.3474, +0.2937, -0.3453, +0.5875, +0.0839, +0.2786,
+ -0.4704, -0.0538, +0.4598, -0.2641, +0.2168, +0.2352, -0.0699,
+ -0.1660, +0.0367, +0.3793, +0.1119, +0.2799, -0.0936, -0.2325,
+ +0.1220, +0.3516, +0.3244, -0.0093, +0.3741, -0.0405, +0.1817,
+ +0.1862, -0.1718, +0.3106, -0.0407, +0.0567, +0.2398, -0.3312,
+ +0.0257, -0.3013, +0.0906, -0.0941, +0.1860, -0.0730, +0.2885,
+ -0.2410, -0.2040, -0.3055, -0.1838, +0.7850, -0.1954, -0.1275,
+ +0.0687, +0.3292, +0.3618, -0.0271, +0.2285, +0.0405, +0.0039,
+ +0.3536, -0.0453, +0.0397, +0.2821, +0.5155, -0.3573, -0.3295,
+ +0.1070, -0.1557, -0.0199, +0.2729, -0.1590, -0.1519, +0.2035,
+ -0.0600, -0.1351, -0.2425, -0.2450, +0.2618, +0.1039, -0.0239,
+ +0.0207, -0.0275, +0.1956, +0.1542, -0.1087, -0.1858, -0.1258,
+ -0.2261, +0.1710, -0.0095, +0.2291, +0.1807, -0.0717, -0.2777,
+ -0.4251, -0.2181, -0.2523, +0.0932, -0.3342, +0.2693, -0.0931,
+ -0.3272, +0.3386, -0.1731, +0.0882, -0.0388, +0.3526, +0.1001,
+ -0.0724, +0.0580, +0.1069, -0.0739, -0.0173, -0.1927, -0.0398,
+ -0.1471, +0.2138, +0.2972, -0.0540, -0.0702, +0.3311, +0.3107,
+ -0.4498, -0.0410, -0.1421, +0.2008, -0.3581, -0.0654, +0.3527,
+ -0.3508, +0.5676, +0.3380, +0.2792, +0.3364, -0.1180, -0.0956,
+ -0.0945, +0.3532, -0.2808, +0.1156, -0.3018, -0.1284, +0.1322,
+ -0.2177, -0.3536, -0.1163, +0.1442, +0.0544, -0.0520, -0.0935,
+ -0.0389, +0.2355, -0.1508, +0.0334, +0.1625, -0.0570, +0.0922,
+ -0.2637, +0.0786, -0.1576, -0.3297, +0.4285, -0.2155, +0.2264,
+ -0.2432, -0.1515, -0.2511, -0.4285, +0.0903, +0.3151, +0.1654,
+ -0.0998, -0.1048, +0.1084, -0.2451, -0.3192, -0.2839, +0.1695,
+ +0.0071, +0.1145, -0.4226, +0.2563, +0.1695, +0.1237, +0.2135,
+ +0.1209, +0.2015, -0.0175, +0.0028, +0.2071, +0.1469, -0.1188,
+ -0.2060, -0.2925, -0.0588, +0.0473, +0.2574, -0.1653, +0.0977,
+ -0.4298, -0.2020, -0.2299, +0.1185, +0.3264, -0.0511, -0.0698,
+ +0.1839, +0.1456, -0.1438, -0.1972, -0.0161, +0.2833, -0.2013,
+ -0.0045, -0.0018, -0.0231, -0.1224, +0.0642, +0.3147, +0.1657,
+ +0.2248, -0.0007, +0.0951, -0.1961, +0.1023, +0.1240, +0.1744,
+ +0.0264, -0.1413, +0.0181, -0.2669, -0.4848, +0.0801, +0.3102,
+ +0.1198, +0.2436, +0.1273, +0.4990, -0.0604, +0.0977, +0.0166,
+ +0.1470, -0.1536, -0.2691, -0.1054, +0.1312, +0.4211, +0.0988,
+ +0.2298, +0.2502, -0.2912, -0.1419, +0.2418, +0.2973, -0.2015,
+ -0.1817, -0.0262, -0.1974, -0.0795
+ ],
+ [
+ -0.2097, +0.1729, +0.1217, +0.1132, -0.0596, -0.2502, +0.2017,
+ +0.1972, -0.0804, +0.2506, +0.4203, +0.0047, +0.2293, +0.3884,
+ +0.0636, +0.1996, +0.0480, +0.0913, -0.0187, -0.4314, -0.0188,
+ -0.0248, -0.0407, -0.1030, -0.0792, -0.0918, +0.3159, +0.0902,
+ -0.1493, +0.2896, -0.0594, -0.1055, -0.0553, +0.4742, -0.0574,
+ +0.0155, -0.0710, -0.1234, +0.3404, +0.0636, -0.2277, -0.0430,
+ +0.1607, +0.1531, +0.0073, -0.0407, +0.2017, +0.3172, -0.5818,
+ +0.3355, +0.0280, -0.0795, -0.2449, -0.1919, +0.3268, +0.1312,
+ -0.1493, -0.0656, -0.1482, -0.1045, -0.2848, +0.3498, +0.3616,
+ -0.4391, +0.0634, +0.2900, -0.4208, -0.2300, -0.1560, -0.2766,
+ -0.1878, -0.0083, -0.0358, -0.2226, +0.3990, +0.0566, +0.4359,
+ -0.0416, -0.1255, -0.0053, -0.1905, -0.1912, -0.1385, +0.0038,
+ +0.1298, -0.1782, -0.3861, +0.0321, +0.1969, +0.2704, -0.1199,
+ +0.1919, -0.1319, -0.0604, -0.0543, -0.0601, -0.1589, +0.2349,
+ -0.1380, -0.2177, +0.0393, +0.1172, +0.2216, +0.3722, -0.1225,
+ +0.1798, +0.0511, +0.1885, +0.3714, -0.2291, -0.0178, +0.2587,
+ +0.1974, -0.2691, -0.2672, -0.0804, -0.2566, +0.1140, +0.0702,
+ -0.1479, -0.0766, +0.1301, -0.1145, +0.2643, +0.2521, +0.5178,
+ +0.0466, -0.1019, +0.0245, -0.0204, -0.1585, -0.2132, +0.2078,
+ -0.0992, +0.1706, -0.0786, -0.1297, -0.1287, +0.4405, +0.1151,
+ +0.0983, -0.0388, +0.2761, -0.0276, -0.0164, -0.0871, +0.1687,
+ +0.0014, +0.0995, -0.0913, +0.3643, -0.4339, +0.0070, -0.1230,
+ +0.3374, +0.2993, +0.0263, -0.0087, +0.3070, -0.0454, -0.1270,
+ +0.4292, -0.1709, +0.2164, -0.1621, -0.5785, -0.1937, -0.3957,
+ +0.3361, -0.1170, +0.1993, +0.1888, -0.1823, -0.2302, -0.0885,
+ +0.2479, -0.0229, -0.3401, -0.3067, +0.1078, -0.2817, -0.2539,
+ -0.1013, +0.5285, -0.3843, +0.0568, -0.3106, +0.0533, +0.3640,
+ -0.0927, -0.5513, -0.0362, +0.0053, +0.1241, +0.1022, -0.1230,
+ +0.1791, -0.0647, +0.1766, -0.0644, -0.2788, +0.2589, -0.0948,
+ -0.1154, +0.0718, -0.3298, +0.1239, +0.3155, +0.2845, -0.1631,
+ +0.1506, +0.0343, +0.3193, +0.3269, -0.4261, +0.0917, -0.1276,
+ +0.6166, +0.1516, -0.0073, +0.1164, -0.1068, +0.1024, -0.0546,
+ +0.0823, +0.1792, -0.4155, +0.1751, +0.2966, -0.3977, -0.1986,
+ -0.3103, +0.0695, +0.0647, -0.1709, +0.1093, +0.2011, -0.5787,
+ +0.0172, -0.0608, +0.3439, -0.0277, +0.2463, -0.1530, -0.2043,
+ +0.2256, +0.1863, +0.2290, +0.0408, +0.0741, -0.2031, +0.3496,
+ -0.0224, +0.3403, -0.0695, +0.1074
+ ],
+ [
+ -0.0003, -0.3044, +0.4460, +0.1808, +0.0575, +0.3863, +0.3343,
+ -0.0873, +0.0772, +0.0417, -0.2723, +0.2732, +0.2943, -0.0961,
+ +0.2566, +0.0375, +0.0300, +0.5390, +0.2300, +0.2941, -0.3558,
+ +0.1914, +0.0620, -0.0483, -0.2449, -0.1154, -0.1646, +0.6449,
+ -0.1792, +0.1099, +0.1142, -0.0761, +0.1167, +0.0152, +0.3108,
+ +0.5886, +0.2649, +0.1822, -0.3308, +0.0202, -0.3642, -0.2656,
+ +0.6961, +0.1750, +0.0493, -0.2683, -0.2037, -0.3239, -0.3731,
+ +0.1197, +0.2602, -0.5951, +0.0618, -0.2428, +0.0832, +0.3814,
+ -0.3129, +0.1019, -0.0127, -0.0651, -0.1155, -0.0557, +0.1840,
+ +0.0163, +0.0133, -0.6342, -0.3788, -0.2772, +0.0301, -0.1676,
+ -0.3078, -0.0301, +0.1685, -0.1506, +0.0278, -0.1542, +0.1565,
+ -0.6516, -0.1237, +0.0929, -0.2329, -0.1984, -0.4724, +0.2307,
+ +0.3782, +0.4176, +0.4383, -0.3455, +0.3168, +0.1180, +0.2909,
+ -0.1012, +0.1286, -0.0347, -0.2117, +0.0111, -0.0285, +0.1317,
+ +0.1310, +0.2168, -0.1906, +0.3162, +0.0639, -0.0704, -0.2262,
+ +0.1623, -0.4405, +0.3805, +0.0383, -0.0340, -0.7635, +0.0810,
+ +0.0497, -0.2813, -0.3334, -0.1317, -0.1793, +0.2184, +0.1701,
+ -0.6818, -0.0908, -0.0421, -0.0849, -0.0449, +0.1266, -0.3249,
+ +0.0535, -0.0865, -0.3225, -0.2194, -0.2844, -0.1194, -0.0899,
+ +0.0359, +0.1564, -0.0033, -0.4960, -0.0576, +0.1548, -0.2170,
+ +0.4585, +0.3145, +0.0617, -0.0532, +0.1724, -0.0141, +0.1699,
+ -0.4904, +0.4061, -0.2469, -0.1990, +0.2468, +0.0400, -0.0165,
+ -0.3423, +0.3232, -0.4064, -0.0525, -0.4683, +0.2054, -0.1599,
+ -0.0302, -0.1733, +0.0794, +0.1102, -0.2173, +0.0244, -0.3933,
+ -0.1153, -0.0233, +0.5126, +0.0037, -0.2264, -0.2053, -0.0165,
+ +0.1438, -0.5592, -0.0604, -0.3643, -0.0868, -0.0800, -0.2152,
+ -0.2482, -0.1522, -0.0747, -0.6181, +0.1722, -0.1270, -0.2769,
+ -0.2791, +0.2759, -0.2312, -0.4696, -0.1414, -0.0734, -0.3751,
+ +0.2078, -0.2445, +0.2426, +0.0533, -0.1425, +0.3050, -0.0827,
+ -0.5703, +0.1974, -0.1613, -0.3847, +0.2888, -0.0833, -0.0521,
+ +0.1316, -0.2689, -0.0090, +0.3293, +0.1631, +0.1408, -0.2444,
+ -0.0232, +0.2931, +0.0770, +0.0145, -0.1422, +0.2749, +0.1730,
+ +0.1402, +0.0209, -0.3114, +0.2974, +0.3669, +0.2171, -0.0237,
+ -0.1884, +0.0323, +0.1172, +0.2836, -0.0257, +0.4679, +0.1863,
+ +0.1192, +0.4333, +0.1319, -0.0990, +0.2281, +0.0288, -0.3451,
+ -0.3312, -0.1227, +0.5827, -0.3799, +0.4705, +0.3426, +0.1792,
+ -0.4163, +0.4064, +0.0575, -0.0937
+ ],
+ [
+ +0.0611, +0.3078, -0.1742, +0.2253, -0.4689, -0.1905, -0.3324,
+ -0.1328, +0.4608, -0.3198, -0.2465, -0.0288, +0.1197, -0.5908,
+ +0.3047, -0.0921, -0.1324, -0.2190, +0.4715, -0.1399, -0.1553,
+ -0.0099, -0.9663, -0.1458, -0.2057, -0.3101, -0.0829, -0.2965,
+ -0.8199, -0.4384, +0.4178, +0.0461, -0.3854, -0.3726, +0.3608,
+ -0.0623, -0.2017, -0.2245, -0.6420, -0.0401, -0.2116, +0.1069,
+ +0.2786, -0.0822, -0.4163, -0.4312, +0.1290, -0.3507, +0.0898,
+ +0.0773, +0.3763, -0.4004, -0.0178, -0.6708, +0.2680, +0.4420,
+ +0.1213, +0.0530, +0.3676, +0.1269, +0.1466, -0.2989, +0.4742,
+ -0.3132, +0.0904, +0.0000, +0.4407, -0.3638, +0.0135, +0.4315,
+ -0.2404, -0.1172, -0.2249, +0.2325, +0.0726, -0.1253, -0.1858,
+ +0.5537, -0.0504, -0.9185, -0.0784, -0.0081, +0.0234, +0.1326,
+ -0.1351, +0.2210, -0.0699, +0.0861, +0.3462, +0.8427, +0.1939,
+ +0.3911, -0.3045, -0.0151, -0.2161, +0.1299, -0.0528, +0.0737,
+ -0.1087, -0.4404, +0.1146, -0.7538, -0.0746, -0.1742, -0.2862,
+ +0.1254, +0.0625, -0.9375, +0.3686, +0.2854, +0.1226, -0.1359,
+ +0.2138, +0.1159, -0.2702, +0.2378, -0.1893, +0.0742, -0.0629,
+ -0.4931, +0.1946, +0.0666, +0.0595, -0.2730, -0.2086, -0.2011,
+ +0.0994, -0.6447, -0.3034, +0.4399, -0.0323, -0.8062, +0.2143,
+ -0.2933, -0.8614, +0.2216, -0.6174, +0.3424, -0.3845, -0.1546,
+ -0.2461, -0.3759, -0.0275, +0.1786, +0.1448, -0.1917, +0.0765,
+ +0.1404, -0.3502, +0.2456, -0.1461, -0.2474, +0.1245, +0.0020,
+ -0.1272, -0.4356, -0.3834, -0.1794, -0.0142, -0.2149, +0.3772,
+ +0.2140, -0.0896, -0.0987, +0.1417, +0.4623, +0.0911, +0.2603,
+ +0.3035, -0.0827, -0.0475, -0.0204, +0.0262, -0.1349, -0.3267,
+ +0.1301, -0.0057, +0.0480, -0.6501, +0.1047, +0.2006, +0.3080,
+ -0.1755, -0.1978, -0.5803, -1.1720, +0.1803, -0.0135, -0.0410,
+ -0.1853, -0.4568, -0.4508, +0.2594, -0.0582, -0.0565, -0.5740,
+ +0.1930, +0.5278, +0.0094, -0.6138, -0.4217, +0.2114, -0.0352,
+ +0.3174, +0.0062, -0.1661, -0.2995, -0.6589, -0.2840, +0.2203,
+ +0.1942, -0.0672, +0.0641, -0.5811, +0.0498, -0.4309, -0.4020,
+ +0.4601, -0.1588, +0.0766, -0.1776, +0.3328, -0.5007, +0.0958,
+ +0.0832, +0.1465, -0.2590, -0.7014, -0.3533, +0.3146, -0.1766,
+ -0.8621, +0.2161, -0.1767, -0.2962, -0.1483, +0.2304, -0.9708,
+ -0.2495, +0.1152, +0.0527, -0.1122, -0.2209, +0.0535, -0.1199,
+ +0.2872, -0.4190, -0.1181, +0.2871, -0.1416, +0.1468, +0.1890,
+ -0.3637, +0.2674, -0.2951, -0.5520
+ ],
+ [
+ +0.3224, -0.3127, +0.1477, +0.4042, -0.2816, +0.1801, -0.3632,
+ -0.4932, +0.3709, -0.0116, +0.1003, -0.0342, -0.1900, -0.2473,
+ +0.4070, +0.3534, +0.0446, -0.5582, +0.4056, +0.2565, -0.0216,
+ -0.1793, -0.0214, +0.0586, +0.5041, -0.0780, +0.3289, -0.4695,
+ -0.0019, -0.1165, +0.1928, +0.0276, -0.0934, -0.0401, +0.2345,
+ -0.2896, +0.1065, -0.0970, +0.2237, +0.3538, +0.0806, +0.1541,
+ +0.4284, -0.2360, -0.0456, +0.0949, -0.0767, -0.2645, +0.2787,
+ +0.0931, +0.1863, -0.0527, +0.3325, -0.1285, -0.1237, +0.4867,
+ +0.1638, +0.5354, +0.3012, -0.1084, +0.1007, +0.1260, +0.0695,
+ -0.2001, +0.2486, -0.3006, +0.1528, -0.4508, -0.0287, +0.2927,
+ -0.3191, -0.1170, +0.0527, -0.1668, -0.2379, -0.0629, -0.0162,
+ +0.3974, -0.5739, -0.3054, +0.0959, +0.1848, +0.3932, -0.0600,
+ -0.0137, -0.6117, -0.2887, +0.1422, +0.3672, +0.1573, -0.0439,
+ +0.2197, -0.1045, +0.1218, +0.2470, -0.3030, +0.0290, -0.2101,
+ -0.2285, -0.1076, +0.3314, -0.0303, -0.2679, -0.0188, -0.0019,
+ +0.0514, -0.1176, -0.4099, -0.0185, +0.3927, +0.0246, +0.3295,
+ +0.1434, +0.1825, -0.1085, +0.1551, -0.3395, +0.0757, +0.1600,
+ -0.3613, +0.3572, +0.0125, +0.0061, +0.1241, -0.0557, +0.0449,
+ +0.1740, -0.0347, -0.3372, -0.1299, +0.0773, +0.3050, +0.2442,
+ -0.0268, +0.4932, -0.0212, -0.7499, -0.1609, +0.2292, -0.0242,
+ -0.4588, -0.0083, -0.2593, -0.1930, -0.0839, +0.0332, +0.0602,
+ +0.2326, -0.0420, -0.1836, +0.0801, +0.3550, -0.0732, +0.2023,
+ +0.0618, +0.2686, +0.3199, -0.0585, +0.0699, +0.4110, +0.0118,
+ -0.0995, -0.2929, -0.2489, +0.0978, +0.0877, -0.0767, +0.0659,
+ -0.2370, +0.0765, -0.1233, +0.2962, +0.1523, +0.0544, -0.2004,
+ -0.3175, +0.0601, +0.5150, +0.0255, +0.0057, +0.2318, -0.0558,
+ -0.4948, -0.4292, -0.1899, -0.4096, +0.1288, +0.1194, +0.0070,
+ -0.0548, +0.1307, -0.1176, +0.1721, -0.2888, +0.2454, -0.2094,
+ -0.0900, -0.2116, +0.4802, +0.4547, -0.1396, -0.1156, -0.4985,
+ -0.1793, -0.2882, +0.0199, -0.4122, -0.0101, -0.0266, +0.1625,
+ +0.2353, -0.3339, +0.2636, -0.2425, -0.2090, -0.1268, -0.0383,
+ +0.0191, -0.0739, -0.1670, +0.0690, -0.0317, -0.1051, -0.1572,
+ +0.0167, -0.0760, +0.0480, -0.4994, +0.0660, +0.2312, -0.4430,
+ +0.5670, +0.4197, +0.0942, +0.0800, +0.0784, +0.0543, -0.0619,
+ +0.1259, -0.0537, +0.0592, +0.1902, -0.0528, +0.1624, -0.0941,
+ -0.0937, +0.2642, +0.1356, +0.2628, -0.0354, +0.2153, +0.1671,
+ -0.0721, +0.4179, -0.3169, -0.0289
+ ],
+ [
+ -0.5803, -0.0273, -0.0867, -0.2584, +0.0324, +0.5024, +0.2084,
+ -0.1799, +0.1409, -0.6306, +0.0890, +0.1275, +0.0616, +0.0344,
+ +0.0807, -0.0372, +0.0265, -0.1669, -0.2355, +0.0271, -0.7700,
+ +0.1172, -0.0231, -0.2389, +0.0853, -0.5193, +0.4735, -0.0984,
+ +0.8684, +0.7334, +0.3930, -0.0315, +0.2018, -0.0346, -0.8833,
+ +0.0193, +0.5264, -0.1244, +0.1678, +0.2494, +0.0423, +0.2485,
+ -0.1706, +0.2937, -0.6983, -0.7671, +0.1922, -0.5751, -0.0333,
+ +0.1523, +0.5973, -0.0412, -0.1279, -0.3813, -0.0872, +0.1495,
+ +0.1821, +0.6008, -0.4524, +0.4405, +0.6326, -0.2808, -0.2926,
+ +0.4507, +0.0868, +0.1535, -0.2036, -0.1044, -0.2049, +0.4605,
+ -0.3767, +0.3232, +0.0216, +0.2235, -0.1168, -0.3464, +0.2172,
+ +0.1721, +0.2620, -0.5405, +0.2447, +0.0913, -0.1686, +0.2218,
+ +0.2892, +0.4072, -0.3119, -0.8141, -0.5237, -0.2244, -0.0809,
+ -0.0767, +0.2571, -0.2712, +0.2743, +0.2806, -0.5054, +0.3266,
+ -0.2475, +0.1132, +0.1580, -0.5744, +0.6102, +0.3380, -0.3990,
+ +0.1183, -0.0317, +0.2527, +0.2397, +0.1724, +0.3687, +0.1003,
+ +0.4660, +0.6658, +0.1793, +0.2163, +0.4701, +0.3775, +0.2500,
+ +0.4531, +0.1673, -0.4755, -0.1397, +0.5405, -0.5446, +0.1288,
+ +0.0967, +0.2088, +0.3100, +0.2587, -0.0596, +0.2117, +0.0903,
+ -0.4571, -0.3911, +0.1151, -0.1371, -0.0751, -0.5101, +0.9461,
+ -0.2897, +0.4531, +0.1608, -0.4687, -0.1213, -0.5739, -0.0733,
+ +0.3992, -0.2095, +0.3293, -0.0643, -0.5819, -0.3289, +0.1431,
+ +0.1823, +0.2308, +0.0626, +0.2265, -0.2274, -0.1451, +0.1298,
+ +0.2444, +0.3809, +0.1196, +0.2863, -0.0854, -0.0057, +0.0601,
+ +0.0965, -0.7362, -0.1561, +0.3504, +0.1185, +0.3864, -0.3101,
+ -0.4990, +0.3772, +0.4807, +0.0461, +0.9313, +0.0836, -0.2765,
+ +0.2350, +0.0832, +0.2205, -0.5168, -0.1647, +0.1240, +0.5142,
+ +0.0643, -0.1902, +0.0209, +0.1553, -0.1786, +0.0356, +0.2483,
+ +0.3052, +0.1525, -0.4210, +0.3188, -0.2613, +0.5367, +0.4172,
+ +0.0167, +0.1076, -0.7111, +0.2268, +0.4572, -0.0538, +0.4088,
+ -0.4665, -0.2512, -0.0689, +0.2433, -0.3109, +0.0256, -0.2157,
+ +0.3432, +0.3144, -0.3142, +0.6272, +0.2602, -0.2451, -0.0987,
+ -0.2741, -0.0236, +0.2398, -0.0648, -0.0188, -0.3843, +0.3367,
+ +0.1920, +0.4231, -0.3188, +0.0820, +0.3757, +0.4807, -0.1248,
+ +0.3980, -0.0158, -0.5703, +0.1927, -0.6508, -0.1380, -0.0500,
+ +0.3608, +0.1018, +0.3031, +0.7349, -0.2402, +0.2606, +0.4573,
+ -0.1254, -0.6462, +0.3231, +0.3154
+ ],
+ [
+ +0.0149, -0.0283, +0.0292, +0.0228, -0.2204, +0.0025, -0.1869,
+ +0.1630, -0.1096, -0.0707, +0.2569, -0.0258, -0.0743, +0.2652,
+ +0.1330, -0.3632, -0.4221, -0.4973, +0.0707, +0.0312, -0.1621,
+ -0.0081, -0.0504, -0.0034, -0.3477, +0.2506, +0.3567, -0.1004,
+ -0.0023, +0.0513, -0.0193, +0.1204, +0.2787, -0.0471, -0.0686,
+ -0.1681, +0.1938, +0.2302, +0.0325, +0.0863, -0.2133, +0.2352,
+ -0.0514, +0.0857, -0.0373, -0.3076, +0.0739, -0.0005, -0.1691,
+ +0.1977, +0.2865, -0.0232, -0.1837, -0.1503, -0.2634, -0.3663,
+ +0.3594, +0.2725, +0.0468, +0.1010, -0.0176, -0.0638, +0.1523,
+ -0.1746, -0.1516, +0.3473, -0.4868, +0.2359, -0.2848, -0.0089,
+ +0.2509, -0.1903, +0.0904, -0.0008, -0.0443, -0.3106, +0.1641,
+ -0.1648, -0.0804, +0.1817, +0.1874, +0.2325, +0.0388, -0.2293,
+ +0.0438, -0.0323, +0.3212, -0.3971, +0.1317, -0.1043, +0.1733,
+ -0.3115, -0.1521, -0.0278, +0.1597, +0.1488, +0.2086, +0.3062,
+ +0.1483, -0.0037, +0.0211, +0.4898, +0.1590, -0.4147, +0.1122,
+ +0.4511, +0.4929, +0.2055, -0.1063, -0.2175, -0.1760, +0.2200,
+ +0.3597, +0.0898, -0.0207, +0.0137, +0.4418, +0.2735, +0.1716,
+ +0.2474, +0.1682, +0.0975, +0.0733, +0.4200, -0.3772, +0.0910,
+ +0.2955, +0.0999, -0.3352, +0.3816, +0.0081, -0.1290, +0.0712,
+ +0.2741, -0.2172, +0.1118, -0.3487, -0.4790, -0.3282, +0.2295,
+ +0.2731, +0.1193, +0.5220, -0.1749, +0.3679, -0.4365, +0.1776,
+ +0.4369, +0.0663, +0.2523, +0.0318, -0.2594, -0.0968, -0.1865,
+ +0.1813, +0.0345, +0.0566, +0.1780, +0.2866, -0.0196, +0.2674,
+ +0.1790, -0.1964, -0.1468, +0.3044, -0.0378, +0.2500, +0.2037,
+ -0.1253, -0.5152, -0.3690, -0.0885, -0.3400, +0.2524, +0.0910,
+ -0.3584, -0.2269, -0.0640, -0.0404, +0.4809, -0.2771, -0.0946,
+ +0.0924, -0.0384, -0.1648, -0.3782, +0.4143, +0.1945, -0.0368,
+ +0.2829, -0.0968, -0.2018, +0.1974, -0.0393, -0.0609, +0.0347,
+ -0.0810, +0.1275, -0.2494, +0.0792, -0.2517, -0.0751, -0.0438,
+ +0.2531, -0.2712, -0.3991, -0.2440, +0.4161, +0.0998, +0.1292,
+ -0.0100, -0.1110, -0.0403, -0.1242, -0.2749, +0.4414, -0.3737,
+ +0.0662, +0.3098, -0.2940, -0.1035, +0.0787, -0.2168, +0.1684,
+ -0.0599, +0.1484, -0.1814, -0.0735, +0.1977, -0.1252, -0.3795,
+ -0.0251, +0.4081, -0.3642, -0.1602, +0.1218, -0.0431, +0.0123,
+ -0.0645, +0.0157, -0.2527, +0.2099, +0.0956, -0.3961, -0.0332,
+ +0.1681, +0.5391, -0.0096, +0.5405, -0.3352, +0.1402, -0.0295,
+ -0.0723, +0.2783, +0.0030, +0.2798
+ ],
+ [
+ -0.0354, +0.0453, +0.3500, -0.3471, -0.2109, -0.1173, -0.3520,
+ -0.0333, -0.0067, +0.3466, +0.0650, -0.2510, -0.4762, -0.0643,
+ -0.2253, +0.1201, -0.2505, -0.0481, +0.0518, -0.3525, -0.1378,
+ +0.0982, -0.5547, +0.2424, -0.1063, -0.2991, +0.4079, -0.1162,
+ -0.0661, +0.2924, -0.3963, +0.2862, +0.1332, -0.0872, -0.1993,
+ +0.1340, -0.3032, -0.1052, -0.1286, -0.3403, +0.1369, +0.1253,
+ -0.1515, -0.2172, +0.2381, -0.4324, -0.0409, -0.3135, -0.0799,
+ -0.4632, -0.5431, -0.1894, +0.2509, +0.5030, -0.2823, +0.3794,
+ -0.0391, -0.1346, +0.2211, -0.0250, -0.3781, +0.3886, +0.5035,
+ +0.0534, +0.1245, +0.1264, -0.0116, +0.0133, -0.1717, +0.3956,
+ +0.0467, +0.1601, +0.3756, +0.0925, +0.0328, +0.2124, +0.6018,
+ +0.1404, +0.0594, +0.1382, -0.5218, +0.2223, +0.0790, -0.0674,
+ -0.0832, -0.3092, +0.3593, -0.3136, +0.1884, -0.2425, -0.5318,
+ -0.1218, +0.2421, -0.3231, -0.7911, -0.4926, +0.3991, -0.2189,
+ -0.1681, -0.5131, +0.0509, +0.0338, -0.1953, +0.1520, -0.2028,
+ -0.0616, +0.4112, +0.1993, +0.1682, +0.1303, -0.1001, -0.1197,
+ -0.2874, +0.3450, +0.1934, +0.3140, -0.6519, +0.0112, +0.0481,
+ -0.0431, -0.7008, -0.1956, -0.0524, +0.1107, +0.0457, +0.2703,
+ -0.2400, +0.0137, -0.5900, +0.0930, +0.0433, +0.0270, -0.3728,
+ +0.3152, +0.5378, +0.1319, -0.0989, +0.1903, +0.2497, +0.0627,
+ -0.0222, -0.6911, -0.2004, +0.9832, -0.2162, +0.7030, +0.2834,
+ -0.3340, -0.2094, +0.3005, -0.1364, +0.6207, +0.1348, -0.0796,
+ +0.3638, -0.0591, -0.3195, -0.0862, -0.0592, +0.4195, +0.3004,
+ +0.3248, -0.2234, -0.1877, +0.7093, -0.1116, -0.7692, -0.3403,
+ +0.5564, +0.3110, +0.1635, +0.0245, +0.1445, -0.3785, -0.1565,
+ +0.1251, +0.1432, -0.2219, -0.1753, +0.1186, -0.5071, -0.4024,
+ -0.3913, -0.2113, +0.1187, -0.3587, -0.2125, -0.1784, -0.1304,
+ +0.0333, +0.6733, +0.2380, -0.0781, +0.3920, +0.5218, -0.5096,
+ -0.0453, -0.1092, -0.2755, -0.2618, +0.2256, -0.2251, -0.2685,
+ -0.6291, +0.4639, -0.0920, +0.4521, +0.0293, +0.0722, +0.3435,
+ -0.2480, -0.1396, -0.0924, +0.1203, -0.1185, -0.0110, +0.5724,
+ -0.1400, -0.1099, +0.6710, +0.1855, -0.9102, +0.1814, +0.0835,
+ +0.4068, -0.1440, -0.2479, +0.5081, -0.2556, +0.2026, -0.4832,
+ -0.3482, +0.1707, -0.3255, +0.1505, -0.3818, -0.0001, -0.0519,
+ -0.1092, +0.0822, +0.5690, -0.5227, +0.1843, +0.5351, +0.4847,
+ +0.0426, +0.2993, -0.1047, +0.5704, -0.1589, -0.4606, +0.2568,
+ +0.1225, +0.0552, +0.1132, -0.2106
+ ],
+ [
+ -0.0355, +0.3622, -0.1122, -0.0303, -0.4921, +0.1137, -0.1361,
+ +0.0401, +0.0725, -0.1617, +0.1317, -0.1431, +0.1153, +0.3067,
+ -0.4288, +0.1733, -0.3218, -0.0858, -0.1087, -0.2338, -0.0811,
+ +0.0730, -0.2743, +0.1327, +0.3564, -0.5947, +0.0407, +0.4382,
+ +0.1483, -0.0121, +0.1343, -0.1675, -0.3163, -0.1488, +0.1189,
+ +0.0350, -0.0097, -0.1976, +0.2417, +0.0877, +0.2365, +0.0743,
+ -0.1832, -0.1173, -0.1580, -0.5560, -0.0276, +0.3173, -0.0094,
+ +0.0388, -0.1414, -0.2771, +0.2711, +0.2469, -0.1703, +0.1818,
+ +0.0264, -0.2214, +0.5135, -0.2963, +0.0303, -0.2954, -0.4191,
+ +0.2253, -0.1221, +0.0004, +0.7831, -0.1942, +0.2980, +0.0941,
+ -0.1158, +0.0762, -0.4350, +0.2548, +0.1551, +0.0626, -0.1493,
+ +0.2065, -0.1857, +0.3529, +0.0159, -0.0789, +0.0286, +0.3495,
+ -0.4227, -0.2727, -0.4004, -0.0161, +0.0784, +0.0005, -0.5149,
+ +0.2267, +0.1262, +0.2041, -0.2295, -0.0231, -0.0952, -0.3389,
+ -0.0382, -0.7448, +0.3889, -0.2127, +0.0199, +0.4035, -0.0883,
+ -0.5268, -0.0065, -0.1990, +0.0788, -0.0710, +0.0046, +0.0501,
+ +0.2624, +0.1142, +0.0861, +0.0973, -0.0997, -0.1003, +0.1973,
+ +0.0342, -0.4391, -0.1778, +0.1548, -0.1463, +0.4342, +0.0971,
+ +0.1819, +0.3409, +0.5878, +0.2337, +0.2358, +0.3475, +0.1530,
+ -0.0638, +0.3338, +0.0206, -0.5476, +0.0459, +0.2077, +0.0189,
+ -0.2543, -0.1159, -0.0761, +0.1582, +0.2011, +0.3916, +0.3256,
+ +0.1015, -0.0287, +0.1276, +0.1682, +0.0129, +0.1087, -0.1810,
+ -0.0576, +0.1725, +0.1025, +0.1324, +0.0085, +0.2264, +0.0824,
+ +0.2827, -0.6279, +0.1958, +0.0485, -0.0216, -0.1729, -0.1706,
+ +0.1623, +0.1096, +0.0931, -0.2832, +0.1802, -0.0646, -0.1355,
+ +0.0594, +0.3365, -0.5376, -0.3364, -0.0848, -0.2613, +0.2620,
+ -0.1301, -0.1667, +0.0069, -0.0479, -0.1272, +0.1957, +0.0804,
+ -0.3009, +0.4240, +0.1106, -0.1548, +0.1902, +0.2378, +0.0324,
+ +0.0166, -0.0790, -0.2156, -0.0279, +0.3249, -0.2199, -0.2090,
+ -0.3370, +0.1200, +0.0100, +0.3260, -0.1957, -0.1774, +0.0949,
+ +0.1212, -0.1598, -0.5556, +0.0015, -0.2261, +0.1006, +0.2085,
+ -0.0848, -0.3551, +0.2949, +0.0054, -0.3264, +0.0888, +0.0342,
+ +0.2470, -0.1530, +0.1504, +0.0761, +0.4616, +0.3578, -0.1200,
+ -0.1338, -0.0620, +0.0946, +0.2839, +0.0636, -0.0184, +0.2804,
+ -0.0567, -0.1815, +0.2045, -0.3143, -0.0527, +0.1029, +0.0471,
+ -0.0471, +0.0808, -0.1168, -0.4076, +0.0829, -0.3031, +0.4676,
+ +0.0224, -0.2077, +0.1978, -0.1999
+ ],
+ [
+ -0.1010, -0.2404, -0.2849, +0.1455, +0.1378, +0.1926, +0.2361,
+ -0.2937, +0.2064, +0.0421, +0.1812, +0.3691, -0.3486, -0.1022,
+ -0.0744, +0.1229, -0.4386, +0.0125, -0.3881, -0.2996, -0.2048,
+ -0.0510, -0.0781, -0.3222, -0.1134, +0.4023, -0.0872, -0.2938,
+ -0.2908, +0.1103, +0.0489, +0.0848, -0.0176, -0.1458, +0.2423,
+ -0.2866, +0.0703, +0.1127, -0.0908, -0.1242, -0.0303, +0.0013,
+ +0.3948, -0.0005, -0.3593, -0.0699, +0.0717, -0.1636, +0.0218,
+ -0.1483, -0.0507, -0.3385, +0.2285, +0.1355, -0.2551, +0.1935,
+ -0.0375, -0.3576, -0.1881, -0.1769, +0.0818, -0.5925, -0.3859,
+ -0.0831, -0.2700, +0.4297, +0.0970, +0.1278, -0.1513, +0.0816,
+ -0.1888, +0.1098, +0.3399, -0.0018, +0.2739, +0.0184, +0.0993,
+ -0.0991, +0.1596, +0.5928, -0.0822, -0.2233, +0.3677, +0.3220,
+ +0.1140, -0.1767, +0.5258, +0.4774, -0.0458, -0.0948, -0.4548,
+ -0.2476, -0.0233, -0.0541, +0.0045, +0.2602, +0.4560, -0.0344,
+ +0.1204, +0.1533, -0.1514, +0.3085, +0.2845, +0.3404, -0.4993,
+ -0.0295, +0.0624, -0.1884, +0.2009, -0.1249, -0.0573, -0.1487,
+ -0.2205, +0.0016, -0.0881, +0.1541, +0.0690, +0.0145, +0.0524,
+ +0.3216, -0.1606, +0.1517, +0.0081, +0.4805, +0.0226, -0.0203,
+ +0.0023, -0.0584, +0.1681, -0.0201, -0.0608, +0.1595, +0.3428,
+ -0.2155, +0.2397, +0.0575, +0.7541, +0.0353, +0.3523, -0.1614,
+ +0.2833, -0.1922, -0.0940, -0.0291, -0.5722, -0.1692, +0.2149,
+ +0.0178, -0.4139, +0.1471, +0.2255, +0.1661, +0.2754, -0.1459,
+ -0.4383, -0.3946, +0.6009, -0.0886, +0.0474, +0.0736, +0.2629,
+ -0.0619, +0.4421, +0.1605, -0.2438, +0.3361, -0.2058, +0.0710,
+ -0.1289, +0.0594, -0.2340, -0.2595, -0.0250, +0.2283, -0.0586,
+ +0.0627, -0.2667, +0.0925, +0.1576, +0.1741, +0.8442, +0.5583,
+ -0.0159, -0.2321, -0.0409, +0.0735, -0.0223, +0.1001, -0.0379,
+ -0.0188, +0.3270, -0.0840, -0.1032, -0.2846, +0.1852, -0.2949,
+ -0.2839, +0.2000, +0.0629, -0.1761, +0.1738, +0.0466, +0.3147,
+ +0.0903, +0.3592, -0.0907, +0.1427, +0.0810, +0.4527, -0.0541,
+ +0.1086, +0.1319, -0.0877, +0.1123, +0.4379, +0.1703, +0.1027,
+ +0.2658, +0.1417, -0.2404, -0.2094, +0.2889, +0.0311, +0.2736,
+ +0.2997, +0.0053, +0.0980, -0.1896, +0.1880, -0.1268, +0.2664,
+ -0.2131, +0.0449, +0.5181, +0.3755, +0.1311, +0.1349, -0.3928,
+ -0.0983, -0.0195, -0.2122, -0.2219, +0.0039, -0.0009, -0.1480,
+ -0.0794, -0.1908, +0.1162, -0.1523, -0.1697, +0.3557, +0.0493,
+ +0.2932, +0.0499, -0.4129, +0.0758
+ ],
+ [
+ -0.0468, -0.1803, +0.1076, +0.3251, +0.6184, -0.3114, -0.1230,
+ +0.3713, -0.4464, +0.0684, +0.3383, +0.3221, -0.2729, +0.2946,
+ +0.1943, +0.1954, -0.6578, -0.0570, -0.0339, -0.2920, +0.0423,
+ -0.5298, +0.4007, -0.5820, -0.0377, +0.0406, -0.2370, -0.4655,
+ -0.0046, +0.5069, -0.0471, +0.0535, +0.1463, +0.3264, +0.4456,
+ +0.0105, +0.3068, -0.0262, +0.0298, +0.0183, +0.3544, +0.5920,
+ -0.1028, +0.0257, -0.1456, +0.4452, -0.4759, +0.1087, +0.3227,
+ +0.1700, +0.2066, -0.6348, +0.0231, +0.5112, +0.6282, +0.3323,
+ +0.4566, -0.0154, -0.2268, +0.0425, +0.2978, -0.1051, +0.2577,
+ +0.5342, -0.7325, +0.1593, +0.4029, +0.0706, -0.3219, +0.3941,
+ -0.1809, +0.2960, +0.7586, +0.8630, -0.5558, +0.0672, -0.2114,
+ -0.8054, +0.6901, +0.4814, +0.2078, +0.3896, +0.2214, -0.4920,
+ +0.9965, -0.7324, -0.6585, +0.5329, +0.7044, -0.6737, +0.0255,
+ -0.1597, +0.2869, -0.5315, -0.0708, -0.0608, -0.1456, -0.1391,
+ +0.2564, +0.4272, +0.8474, +0.1289, -0.4975, -0.2000, +0.2369,
+ -0.0471, +0.6356, +0.0456, +0.4963, -0.6084, +0.0811, -0.1642,
+ -0.2298, -0.2015, +0.2522, +0.4432, -0.4480, -0.8622, +0.0647,
+ +0.1456, -0.0836, -0.0173, +0.3379, -0.5648, -0.0681, -0.5624,
+ +0.1191, +0.0971, +0.1196, +0.1649, -0.3151, -0.1059, -0.4016,
+ +0.1005, +0.4878, -0.0364, -0.0470, +0.3035, +0.1903, -0.3378,
+ +0.1568, -0.0147, +0.1942, -0.5899, -0.2620, -0.2944, +0.5645,
+ +0.0389, -0.3849, -0.4410, +0.2850, -0.1466, +0.5244, -0.2212,
+ -0.1834, +0.1653, +0.0254, +0.0407, +0.0358, +0.4145, +0.5616,
+ -0.1249, +0.1544, +0.3584, -0.7873, +0.6443, -0.5025, +0.2097,
+ -0.1029, -0.1549, -0.2047, -0.0593, +0.2371, +0.6084, +0.6281,
+ +0.6733, -0.0301, +0.0384, +0.3657, -0.1154, -0.5736, +0.5779,
+ -0.4174, -0.1531, -0.0563, -0.1114, -0.1184, -0.1867, +0.3557,
+ -0.4798, -0.0917, +0.0213, -0.2287, -0.2391, +0.0658, -1.0389,
+ -0.3860, -0.4087, -0.1438, +0.1826, +0.1439, +0.0826, +0.6390,
+ +0.2824, +0.2706, -0.5583, +0.3452, -0.2026, +0.0264, +0.2765,
+ -0.0574, +0.1179, +0.2400, +0.3694, +0.1398, -0.0551, +0.4724,
+ -0.0146, +0.0828, -0.1048, -0.7036, +0.2830, +0.1624, +0.0022,
+ +0.0491, +0.3424, +0.0850, -0.0712, -0.4055, -0.1021, -0.0042,
+ -0.3948, -0.9802, -0.0024, +0.1138, -0.6403, -0.0022, -0.8502,
+ +0.0091, +0.5823, -0.3955, -0.1233, -0.2180, -0.3058, -0.9293,
+ +0.0442, -0.0494, -0.5554, -0.1709, +0.1602, -0.1647, -0.6202,
+ -0.3488, +0.0541, -0.5352, +0.1713
+ ],
+ [
+ +0.0434, -0.3968, -0.1349, -0.2066, +0.3152, -0.0083, +0.2409,
+ -0.3602, -0.0166, -0.3587, -0.7228, +0.2045, -0.1413, -0.3595,
+ -0.0951, +0.3833, -0.2863, +0.1655, +0.0306, -0.0000, +0.1136,
+ +0.1681, -0.1042, +0.3163, +0.1026, +0.1338, +0.5371, +0.3121,
+ -0.2184, -0.1777, +0.1852, -0.5399, -0.1528, -0.2153, -0.2149,
+ +0.0972, +0.2558, -0.1794, +0.1174, -0.0328, -0.2456, -0.1888,
+ +0.2037, +0.0165, +0.1809, +0.2236, -0.2411, -0.2453, +0.2664,
+ -0.0525, +0.0902, +0.1405, -0.0758, +0.1247, +0.1022, +0.3313,
+ +0.4122, -0.0819, -0.0913, -0.0533, -0.1639, +0.1616, -0.0751,
+ +0.2544, +0.0883, -0.2207, -0.1827, +0.0533, -0.1477, -0.2653,
+ -0.2350, +0.6668, +0.2252, -0.3081, -0.3665, +0.0026, +0.0920,
+ -0.1562, -0.0314, +0.0379, -0.2651, +0.1148, -0.5456, +0.0571,
+ +0.1669, +0.1868, +0.2954, +0.3341, +0.0854, -0.0493, -0.0501,
+ -0.1120, -0.1885, +0.0989, -0.0145, +0.1403, -0.3893, +0.1667,
+ +0.6599, -0.2808, +0.3894, +0.2285, -0.2094, -0.1589, +0.4491,
+ -0.0021, -0.2059, -0.0030, +0.2450, -0.2107, -0.0648, +0.0584,
+ -0.1049, +0.0746, +0.2399, +0.2282, +0.0306, +0.5307, -0.0164,
+ +0.1248, +0.2186, -0.0220, -0.1162, +0.5217, +0.1629, -0.0953,
+ -0.2606, +0.2256, +0.0594, +0.4022, -0.0169, +0.4560, -0.0626,
+ +0.1872, -0.0363, +0.3869, +0.1683, +0.3439, -0.1965, -0.1233,
+ -0.2428, -0.3865, -0.3022, -0.1513, -0.2319, +0.0000, +0.2206,
+ -0.0137, -0.1011, +0.2059, -0.1762, -0.4659, +0.2081, -0.3539,
+ -0.0841, -0.1500, +0.4548, +0.3499, -0.2080, +0.3888, +0.2226,
+ -0.2984, -0.4921, -0.3772, -0.0471, -0.0440, -0.0105, +0.1756,
+ -0.3131, -0.0878, +0.7077, +0.3702, +0.1133, -0.2221, +0.1952,
+ +0.0806, -0.2353, +0.2592, +0.2637, -0.6006, +0.2933, -0.4829,
+ +0.4448, -0.0385, -0.3345, -0.1955, -0.0801, +0.0901, -0.1696,
+ -0.3215, +0.3141, +0.5010, +0.0102, -0.0129, -0.2312, +0.0084,
+ -0.0576, +0.4211, -0.2397, -0.0064, +0.3961, -0.0321, -0.1348,
+ -0.0105, +0.0683, +0.0717, -0.3076, +0.0072, -0.2908, +0.1944,
+ -0.4525, +0.4002, -0.4078, +0.4851, -0.4503, -0.4731, -0.0486,
+ +0.0489, +0.0492, -0.0522, -0.3638, -0.1330, -0.5329, -0.1299,
+ +0.0669, -0.2405, +0.4118, -0.0958, -0.1522, -0.2151, -0.0750,
+ -0.0031, -0.1397, +0.1805, -0.0993, -0.2138, +0.5460, +0.4139,
+ +0.2523, +0.2470, +0.1786, -0.3776, -0.2915, +0.0429, -0.0625,
+ -0.0230, -0.2243, +0.0370, +0.4230, +0.0268, +0.1411, +0.5420,
+ +0.1266, -0.0715, +0.0100, -0.1583
+ ],
+ [
+ -0.0856, +0.1478, +0.2785, -0.0657, +0.1545, +0.1689, -0.1283,
+ +0.4019, +0.1912, -0.1993, -0.2968, -0.0713, -0.1384, -0.0585,
+ +0.1859, -0.1121, +0.2789, -0.6703, +0.0369, -0.2677, +0.2354,
+ +0.0859, +0.1691, +0.1177, +0.4367, -0.1944, +0.1313, +0.0345,
+ +0.3538, +0.2729, -0.0549, -0.8789, -0.3384, +0.0929, +0.0006,
+ +0.1985, +0.1025, -0.0835, -0.3176, -0.0434, -0.1049, +0.0199,
+ +0.2184, -0.4230, +0.0097, +0.1678, +0.5019, +0.1112, -0.2290,
+ -0.4790, -0.1312, +0.0389, -0.0391, -0.2474, -0.2959, +0.2159,
+ +0.0441, +0.0862, -0.2301, -0.0838, +0.3966, +0.2530, -0.2189,
+ +0.1688, +0.1591, +0.1861, -0.3146, +0.3129, +0.1761, -0.1694,
+ +0.1243, +0.5333, +0.3268, -0.6051, -0.1596, -0.1461, -0.1474,
+ -0.0511, +0.0185, -0.0473, -0.3436, +0.0696, -0.0586, +0.5214,
+ +0.3185, -0.2699, +0.3036, +0.0976, -0.0414, +0.1253, -0.3417,
+ -0.3601, -0.3066, -0.1276, +0.1276, +0.2614, -0.2289, -0.0838,
+ -0.5791, +0.1228, +0.2188, -0.1403, -0.5108, -0.0042, -0.2635,
+ -0.1724, -0.0935, +0.1031, +0.0405, +0.0990, +0.0993, -0.2823,
+ -0.0210, +0.0794, +0.4503, +0.5037, +0.0093, +0.0860, -0.3676,
+ -0.0706, +0.2548, -0.0475, +0.3295, -0.1392, +0.1828, +0.0132,
+ +0.1810, +0.2123, -0.4686, +0.0295, +0.4871, +0.0510, +0.3081,
+ -0.4667, -0.3504, -0.1607, +0.2874, -0.1792, -0.4659, -0.0761,
+ -0.0962, +0.0650, -0.1850, +0.2290, -0.2686, +0.0044, +0.2452,
+ +0.0938, -0.1060, -0.0672, -0.2507, -0.2213, -0.4228, +0.2368,
+ -0.0212, +0.0515, +0.0144, +0.2502, -0.2411, -0.1577, +0.1654,
+ -0.2035, +0.1488, +0.1289, +0.4932, +0.2637, +0.1076, +0.5758,
+ -0.1948, -0.0004, -0.1230, +0.1666, -0.0507, -0.0315, +0.0948,
+ -0.1583, +0.8365, -0.5093, +0.2411, +0.2074, +0.0961, -0.1875,
+ +0.2806, -0.0420, +0.1372, -0.0757, -0.1236, -0.3455, +0.1362,
+ -0.2789, +0.2951, +0.4255, +0.0779, -0.2744, -0.3579, -0.1468,
+ -0.2699, +0.3013, -0.6950, -0.4577, -0.1276, -0.0866, -0.0794,
+ +0.0145, -0.0166, +0.0164, +0.0345, +0.0089, +0.0295, -0.1214,
+ -0.2517, +0.5609, -0.3563, +0.4615, -0.1071, +0.1822, -0.3121,
+ +0.2674, -0.3350, -0.2546, -0.3108, -0.0827, +0.1112, -0.4741,
+ +0.4961, -0.3827, +0.3214, -0.0214, +0.2837, +0.2449, -0.0901,
+ +0.0207, +0.1853, +0.3550, -0.0331, +0.6148, -0.0934, +0.1115,
+ +0.0347, +0.1423, +0.2681, +0.1036, -0.2877, -0.3500, -0.3821,
+ +0.0184, -0.3467, +0.1867, +0.6907, +0.0475, -0.5266, +0.1676,
+ +0.1046, +0.2239, -0.0536, +0.1539
+ ],
+ [
+ -0.0844, -0.3474, -0.0897, +0.1492, -0.4280, -0.1678, -0.3024,
+ +0.4074, -0.3629, -0.2004, +0.1868, +0.1184, -0.0086, -0.0451,
+ +0.3128, -0.1078, +0.0704, -0.0958, +0.2218, -0.1937, -0.3028,
+ +0.2372, -0.4567, +0.2715, +0.0018, +0.0344, +0.3235, -0.2282,
+ +0.0839, +0.2394, -0.2440, -0.2340, +0.0998, -0.0844, -0.1730,
+ -0.1000, +0.2880, -0.3090, +0.1695, +0.3572, +0.0307, -0.0739,
+ -0.1133, -0.1782, -0.2876, -0.0359, -0.3327, +0.1698, -0.3572,
+ +0.1098, +0.1340, +0.0604, -0.0513, +0.1150, +0.2439, +0.0899,
+ -0.5564, +0.0675, -0.3053, +0.0340, +0.2903, -0.0247, -0.4335,
+ +0.0542, -0.2079, -0.1710, +0.1518, -0.2401, -0.2369, -0.1225,
+ -0.5155, +0.0449, +0.2075, -0.4325, -0.6876, +0.1819, -0.3930,
+ -0.2237, -0.2683, +0.4713, -0.0287, +0.0986, -0.7589, -0.0699,
+ -0.1480, +0.0169, -0.1973, -0.4215, -0.1522, +0.0113, -0.1273,
+ -0.1016, -0.0639, +0.3509, -0.2240, -0.1146, -0.6177, +0.3497,
+ +0.0372, +0.0542, +0.1487, -0.0626, -0.0458, +0.1751, +0.1285,
+ -0.4678, +0.0586, +0.1874, -0.0348, -0.0960, +0.0458, +0.0459,
+ +0.0862, -0.0687, -0.2644, +0.1326, -0.1289, -0.4631, -0.2240,
+ -0.2605, +0.1904, +0.0466, -0.6984, -0.1629, -0.3469, +0.0080,
+ +0.1777, +0.2707, +0.1424, +0.0567, -0.3038, -0.2561, -0.4254,
+ -0.5804, +0.0237, -0.3453, -0.4146, +0.0453, -0.1700, -0.2211,
+ -0.1830, +0.1386, +0.0974, -0.2867, -0.1311, +0.2497, -0.1554,
+ -0.1106, -0.0011, +0.0374, -0.1288, +0.0673, -0.1604, -0.3713,
+ -0.2043, -0.2112, +0.5406, -0.0867, +0.3670, -0.4745, -0.2994,
+ -0.1433, -0.0713, +0.0591, -0.0761, +0.3913, -0.2590, +0.0657,
+ +0.0527, +0.0918, -0.0480, -0.1542, +0.2264, +0.0627, -0.2540,
+ +0.1928, -0.4839, -0.4015, -0.2736, -0.3463, +0.1071, -0.1021,
+ +0.1950, -0.9547, +0.0687, +0.0291, +0.2292, +0.1111, +0.0181,
+ -0.4079, -0.1859, -0.0060, -0.1915, -0.1541, -0.1969, +0.0345,
+ -0.1558, -0.6596, -0.0265, -0.2989, +0.1218, +0.6290, -0.3345,
+ +0.1225, -0.2464, -0.3944, -0.3526, +0.2880, -0.2926, +0.1864,
+ -0.1420, +0.3058, +0.4685, +0.1149, -0.2107, +0.0171, -0.0748,
+ +0.0790, -0.3467, +0.2248, +0.0542, -0.0743, +0.2650, -0.5654,
+ -0.2655, +0.4095, -0.2855, -0.3975, -0.2072, -0.0676, +0.2310,
+ -0.0036, +0.2007, +0.1200, +0.0486, +0.0304, +0.4052, -0.1677,
+ -0.1908, -0.0181, +0.3009, +0.5420, -0.5680, -0.2664, +0.3837,
+ +0.1885, +0.0908, -0.3664, +0.0211, -0.1291, -0.1372, +0.4594,
+ +0.2679, -0.3230, -0.0231, -0.1443
+ ],
+ [
+ +0.1188, -0.0062, -0.1855, +0.0061, +0.0306, -0.0784, -0.0046,
+ +0.0331, -0.0294, -0.0984, -0.0919, -0.0323, +0.2738, -0.0880,
+ +0.0371, -0.1605, +0.0143, -0.0569, +0.2232, +0.0354, -0.0566,
+ +0.1567, -0.0185, +0.0081, -0.1761, -0.0795, +0.1846, +0.1453,
+ -0.0407, -0.2160, -0.0459, -0.0277, +0.0894, -0.1279, -0.0910,
+ +0.1040, +0.0504, -0.2097, -0.0634, +0.0084, -0.1961, +0.1012,
+ +0.1308, +0.2605, -0.0705, -0.0478, -0.2174, +0.2493, -0.2422,
+ -0.1305, +0.0405, +0.0641, -0.1725, -0.0818, -0.2816, +0.0841,
+ +0.3524, +0.0472, -0.0587, +0.0883, -0.0404, +0.1379, -0.2522,
+ -0.0918, +0.1629, +0.2672, +0.0629, +0.0421, -0.1408, +0.1162,
+ +0.4380, +0.0535, +0.0310, -0.0877, -0.1680, +0.0768, -0.0017,
+ -0.0234, -0.1326, -0.0905, +0.0225, +0.1534, -0.3547, -0.0126,
+ +0.2719, +0.2255, +0.2082, +0.0991, -0.1591, -0.0375, +0.1838,
+ -0.1323, -0.1685, +0.0670, -0.0271, +0.1774, -0.1511, -0.1249,
+ -0.0076, +0.2603, -0.0498, +0.4234, +0.1259, +0.0072, -0.1172,
+ -0.1527, +0.1257, -0.1016, -0.0718, -0.1387, -0.0541, -0.1035,
+ +0.3143, +0.0014, +0.0494, +0.1847, -0.0088, -0.1042, -0.2360,
+ +0.0559, -0.1222, -0.0523, -0.2117, -0.0481, +0.1020, -0.1081,
+ +0.1276, -0.0923, +0.2182, +0.2122, -0.4165, +0.3006, -0.0619,
+ -0.1256, -0.0520, -0.2651, +0.1489, -0.0744, -0.1675, -0.0369,
+ -0.1036, -0.1059, -0.0107, -0.0155, -0.0360, +0.1124, +0.1453,
+ -0.1140, -0.0969, +0.0473, +0.0795, -0.0893, -0.1323, -0.2102,
+ +0.3700, +0.0070, +0.2332, -0.3127, +0.2441, +0.0592, +0.1080,
+ -0.0951, +0.1115, +0.1210, -0.0443, +0.3194, -0.0297, -0.1664,
+ +0.1317, -0.0076, -0.1066, +0.0799, +0.1736, -0.1156, +0.0316,
+ -0.0194, +0.1922, +0.1214, +0.0565, -0.1967, +0.0512, -0.3551,
+ +0.5148, -0.3325, -0.1339, -0.0176, -0.0343, -0.0769, +0.0491,
+ +0.1307, -0.2277, -0.0290, +0.0137, -0.0868, +0.2483, -0.0012,
+ -0.1753, +0.0822, -0.1489, -0.1712, +0.2157, +0.2645, -0.0124,
+ -0.0948, -0.0568, -0.1064, -0.4283, +0.1993, +0.0347, -0.0106,
+ -0.0786, +0.1873, +0.0116, +0.2466, -0.2081, +0.0319, -0.0489,
+ +0.1163, -0.1659, +0.1652, +0.0900, -0.0880, +0.1234, +0.0172,
+ -0.0558, +0.0468, +0.1217, +0.1276, -0.4597, -0.2922, -0.1088,
+ +0.2172, -0.0321, +0.0119, +0.2671, +0.3911, +0.0646, +0.0570,
+ -0.0646, +0.1160, +0.0275, -0.0507, +0.0738, -0.1869, +0.0136,
+ -0.0425, +0.1594, +0.0189, -0.1377, +0.0037, +0.3298, -0.4311,
+ +0.0769, -0.0184, -0.1103, +0.0244
+ ],
+ [
+ +0.1054, -0.2168, +0.3055, -0.1927, +0.4667, +0.0062, -0.0394,
+ -0.0066, +0.0748, +0.2722, +0.1231, -0.4803, -0.3702, -0.4034,
+ +0.2811, -0.1451, -0.2890, +0.0938, +0.3394, +0.2368, +0.3143,
+ -0.3831, -0.0124, +0.0447, +0.3256, -0.0822, +0.1423, -0.1473,
+ +0.1624, -0.0504, -0.3621, -0.1886, -0.3732, +0.0208, -0.1155,
+ -0.2275, -0.1666, -0.2031, +0.1617, -0.3938, -0.1407, +0.0080,
+ -0.0580, +0.0384, +0.0658, -0.1640, -0.2468, -0.1383, +0.0596,
+ +0.1068, +0.0534, -0.0051, -0.3557, -0.0406, -0.0507, +0.1816,
+ +0.6789, -0.1818, +0.1339, +0.1081, +0.0070, -0.0684, -0.2302,
+ +0.0372, +0.6024, +0.3344, -0.1124, +0.3763, +0.1331, -0.3067,
+ +0.1826, -0.1368, -0.0467, +0.0766, -0.3554, -0.1818, -0.0986,
+ +0.0499, +0.2472, -0.1546, +0.1109, -0.0436, -0.1748, +0.1036,
+ +0.1237, -0.2409, +0.0438, -0.5612, -0.0766, +0.0434, +0.0672,
+ -0.2422, +0.0780, -0.1071, -0.0339, +0.3233, -0.2388, -0.0255,
+ -0.1036, +0.3328, -0.0563, +0.8040, -0.5256, -0.0498, -0.4856,
+ -0.0392, -0.0712, -0.2621, -0.2574, +0.2102, -0.2959, +0.0252,
+ +0.0019, -0.1644, -0.1745, -0.1622, +0.1824, -0.2087, +0.1812,
+ -0.1774, -0.3812, -0.1082, -0.0959, +0.2566, +0.2259, -0.1851,
+ +0.3297, -0.0968, +0.3032, +0.1812, +0.0655, -0.1436, -0.3918,
+ -0.2189, +0.2596, -0.1304, +0.1238, -0.1444, -0.2449, -0.0436,
+ -0.1132, +0.3240, +0.0263, -0.0106, +0.0406, +0.4209, -0.0316,
+ -0.0954, +0.5860, +0.4458, +0.1500, -0.3507, -0.1574, +0.0575,
+ -0.3635, +0.0061, +0.2587, -0.0712, -0.0532, -0.1439, -0.4468,
+ -0.0377, +0.3117, -0.4202, -0.0904, -0.0639, -0.1331, +0.0928,
+ +0.1268, -0.0187, -0.1143, +0.1903, +0.0173, +0.3476, +0.0337,
+ -0.0970, -0.1437, -0.0459, -0.1899, -0.0688, -0.2715, +0.1964,
+ -0.2309, +0.0410, +0.0591, -0.0484, +0.1132, -0.0666, -0.4161,
+ -0.3532, +0.2478, -0.4591, +0.3771, -0.2481, +0.3671, +0.5620,
+ +0.1931, -0.1757, -0.0949, +0.0013, +0.0432, -0.3041, +0.0795,
+ +0.2424, +0.3880, -0.2640, -0.0703, -0.0955, +0.3911, -0.0092,
+ -0.0215, +0.1020, -0.0816, +0.5155, +0.1905, +0.0905, -0.0211,
+ +0.0291, +0.1083, -0.2923, -0.0677, +0.1323, +0.0813, +0.1232,
+ +0.3196, +0.0985, +0.2345, +0.2325, +0.1330, -0.4605, -0.0187,
+ -0.0423, -0.1833, +0.5139, -0.1893, -0.1392, -0.0291, -0.4728,
+ +0.1218, -0.1672, -0.0034, -0.2759, +0.0834, +0.0443, -0.1188,
+ +0.2753, +0.1841, +0.0355, +0.1480, -0.0975, +0.2347, -0.3679,
+ -0.1949, +0.2217, -0.2040, +0.1008
+ ],
+ [
+ +0.3394, -0.7614, +0.2214, -0.0855, +0.1614, +0.1544, -0.2578,
+ -0.0026, +0.0793, -0.3764, +0.6935, -0.1747, +0.3017, -0.5659,
+ +0.4088, -0.3397, +0.0083, -0.0262, +0.1206, +0.1305, +0.4384,
+ -0.0426, -0.1596, -0.2370, +0.5147, +0.2141, -0.0156, -0.1807,
+ -0.4023, +0.1593, -0.6592, -0.0338, -0.3846, -0.7189, -0.3224,
+ +0.1704, +0.0438, -0.0268, -0.1999, +0.2407, -0.6428, +0.5990,
+ -0.1621, -0.1820, +0.2747, -0.5300, -0.1427, -0.7566, +0.4896,
+ -0.4544, +0.4176, +0.3437, -0.4714, +0.1215, -0.5182, -0.1339,
+ -0.4483, +0.2899, +0.5122, +0.1295, +0.1649, +0.1705, +0.2041,
+ -0.1614, +0.1871, +0.2149, -0.1200, +0.2660, -0.0501, -0.1457,
+ -0.5291, -0.5227, -0.0281, +0.4277, +0.3698, -0.2083, -0.4078,
+ -0.2390, +0.2048, +0.4018, +0.2991, +0.4258, -0.2820, +0.1101,
+ +0.4753, -0.2546, +0.3167, +0.1833, -0.2245, -0.0669, -0.2413,
+ +0.0229, -0.1720, -0.1400, -0.3102, +0.1771, +0.1776, +0.4946,
+ -0.3560, -0.2972, -0.1236, +0.2733, -0.6177, -0.2299, +0.1100,
+ -0.3703, +0.0889, -0.2761, -0.4925, -0.0626, -0.3893, -0.0899,
+ -0.0676, -0.0853, -0.2297, +0.0095, -0.1208, -0.5865, +0.6617,
+ -0.4572, -0.2909, -0.2341, +0.0815, -0.1485, -0.2683, -0.1679,
+ -0.0129, +0.0477, +0.1809, -0.2123, -0.3615, -0.6727, +0.0831,
+ +0.3760, +0.0771, -1.4335, -0.1328, -0.4613, -0.1139, +0.2321,
+ +0.1380, -0.1703, +0.5679, +0.1268, -0.3508, +0.6495, -0.1023,
+ +0.6463, +0.1550, +1.1874, -0.6792, +0.0565, -0.3362, +0.1157,
+ +0.4535, +0.4557, -0.2579, -0.3490, -0.1606, -0.0600, -0.3668,
+ -0.2549, -0.2206, -0.2502, +0.2149, +0.1647, -0.0841, -0.0877,
+ +0.3362, +0.1809, +0.0896, -0.3949, -0.1881, +0.5513, +0.1961,
+ +0.3686, -0.3547, -0.4208, +0.4066, -0.2038, +0.3193, -0.5107,
+ -0.0533, -0.5291, +0.0475, +0.0730, +0.0105, -0.3940, -0.1920,
+ -0.2656, +0.3453, +0.2038, +0.3677, -0.5476, +0.3070, +0.1598,
+ +0.5035, -0.2558, -0.0726, +0.0814, -0.1602, +0.1250, -0.6546,
+ +0.0126, -0.0443, +0.0209, -0.4783, -0.6256, -0.4328, +0.0440,
+ -0.4465, -0.3143, +0.2611, +0.1469, -0.4565, -1.1730, +0.2640,
+ +0.2994, +0.7914, -0.3757, +0.5256, +0.0436, -0.0332, +0.1276,
+ +0.0059, +0.1051, +0.2218, +0.3520, -0.0248, -0.3851, +0.1581,
+ -0.3110, -0.6304, +0.0452, +0.2547, -0.0698, +0.8202, -0.4308,
+ +1.2043, -0.4712, +0.1173, -0.3822, -0.3770, -0.0086, +0.1568,
+ +0.4548, -0.4026, +0.1963, +0.4417, -0.6008, +0.5816, -0.1452,
+ +0.0417, +0.1982, -0.3800, -0.2664
+ ],
+ [
+ -0.2992, -0.0651, +0.2159, +0.0240, +0.0736, -0.4168, -0.5236,
+ +0.1070, +0.0535, +0.3093, +0.2249, +0.2270, -0.3072, -0.0049,
+ -0.1310, -0.2224, +0.1580, +0.4033, +0.5195, -0.1055, +0.2601,
+ -0.1190, -0.3645, +0.0051, +0.2045, +0.3766, -0.0244, -0.5023,
+ -0.0240, -0.1550, +0.2681, +0.3682, -0.1841, -0.0522, +0.2098,
+ +0.2268, -0.1093, +0.2332, +0.5778, +0.6197, +0.2322, +0.0085,
+ +0.1506, +0.3598, -0.0317, +0.5181, -0.0356, -0.0515, -0.2531,
+ +0.3544, -0.1317, -0.4739, -0.1546, -0.3621, -0.1195, -0.1657,
+ +0.3775, +0.2377, +0.2617, -0.5888, +0.2719, -0.0414, +0.2364,
+ +0.1782, +0.1752, -0.2697, +0.2526, -0.4014, +0.1016, -0.2323,
+ +0.1804, +0.2456, -0.5135, +0.4187, +0.1828, +0.0881, +0.3396,
+ -0.3524, +0.2835, +0.1598, +0.3014, +0.3287, -0.1001, -0.5764,
+ +0.5307, +0.3432, +0.1786, +0.1841, +0.3194, +0.0322, +0.0635,
+ -0.1484, -0.1721, +0.2902, +0.0985, -0.2712, +0.0447, -0.2040,
+ +0.3322, -0.3784, +0.4789, +0.1240, +0.0907, -0.4958, +0.0231,
+ +0.3108, +0.1237, +0.3056, -0.0658, +0.3824, -0.2770, -0.1186,
+ +0.2047, +0.1621, +0.2605, +0.0635, +0.0690, -0.1246, +0.3525,
+ +0.3477, -0.1305, +0.3089, -0.1852, -0.0984, +0.3058, +0.2318,
+ +0.0024, -0.0468, +0.3999, +0.3441, -0.2823, +0.0867, +0.3494,
+ +0.0294, -0.2707, +0.1037, +0.0623, +0.2920, -0.0737, -0.2443,
+ +0.1817, +0.5216, -0.1961, +0.2754, -0.3191, -0.1483, +0.1877,
+ +0.2167, -0.0089, -0.2084, +0.1375, +0.5702, -0.2180, +0.0258,
+ +0.5848, +0.0790, +0.0788, -0.4052, +0.2006, +0.5514, +0.2136,
+ -0.0307, -0.0158, +0.2657, -0.2026, +0.1168, +0.2559, -0.2174,
+ +0.0156, -0.0384, +0.1042, +0.1578, -0.5233, -0.1059, -0.0075,
+ +0.4496, -0.1021, +0.4807, -0.2985, +0.4535, +0.4438, +0.0698,
+ +0.0586, -0.0216, -0.0365, -0.1558, +0.2064, +0.2944, -0.0148,
+ -0.3029, +0.3201, +0.0180, -0.1867, +0.5149, -0.3466, +0.3419,
+ -0.1637, -0.1427, -0.1105, +0.0022, +0.3945, +0.1162, +0.0346,
+ +0.3303, -0.1833, +0.1308, -0.3093, +0.0348, -0.0904, -0.2031,
+ +0.0814, -0.3449, -0.1796, -0.3040, -0.3401, +0.1225, -0.1545,
+ +0.5068, +0.3989, -0.0013, +0.5641, -0.3532, -0.1942, -0.1687,
+ -0.1114, -0.1999, -0.0661, +0.2681, +0.2743, +0.4534, -0.2305,
+ +0.4529, +0.0423, +0.0636, +0.3217, -0.2737, -0.0687, +0.4375,
+ +0.0141, -0.0618, +0.2720, -0.2361, +0.2434, -0.1013, -0.2688,
+ -0.1412, +0.2729, +0.0794, -0.1377, +0.5015, +0.2502, -0.2067,
+ -0.1218, -0.6458, -0.0523, -0.0650
+ ],
+ [
+ +0.3441, +0.2829, -0.1503, -0.0332, +0.1858, +0.1395, +0.0879,
+ -0.1205, -0.1095, +0.1852, +0.1222, +0.0559, -0.4706, +0.0324,
+ -0.1134, -0.0665, -0.3218, +0.1018, +0.2539, +0.0300, +0.2705,
+ -0.1099, +0.1179, -0.1600, +0.1179, -0.2765, +0.1150, -0.2641,
+ -0.2885, +0.1065, +0.1017, +0.2576, -0.1618, -0.3436, +0.1729,
+ +0.0816, -0.4718, -0.1865, +0.0193, +0.1006, +0.3371, +0.1657,
+ +0.3770, +0.1948, -0.3284, +0.4507, -0.6109, -0.0043, -0.1162,
+ +0.5108, -0.0104, -0.0478, -0.1986, +0.7830, -0.2516, -0.0317,
+ +0.1780, +0.0521, -0.4717, +0.2174, +0.1625, -0.5251, +0.3654,
+ +0.0506, +0.0803, -0.0040, +0.2544, +0.0186, +0.2581, +0.6387,
+ +0.0425, +0.5194, -0.1895, +0.2762, -0.0024, +0.2617, +0.1806,
+ +0.0780, +0.2480, -0.0483, -0.1712, -0.0462, -0.6504, -0.1070,
+ -0.0228, +0.2949, -0.2238, -0.0048, +0.1718, +0.1315, -0.1787,
+ -0.1962, +0.1789, -0.0566, -0.3448, -0.1039, +0.5405, +0.1158,
+ -0.1730, -0.2223, -0.7140, +0.0533, +0.5751, -0.0426, -0.3939,
+ +0.2308, -0.2111, +0.3114, -0.3711, -0.0791, +0.1444, +0.0691,
+ -0.4759, +0.0175, -0.3883, -0.5391, -0.5098, -0.2830, +0.0391,
+ +0.0104, -0.1874, +0.0947, -0.5966, -0.3012, +0.5591, -0.0172,
+ +0.7039, -0.2962, +0.0215, +0.2526, -0.1035, -0.3527, -0.1393,
+ +0.2405, +0.0787, -0.1479, +0.0842, +0.0582, +0.2952, -0.4363,
+ -0.1011, +0.2056, +0.3146, +0.0389, -0.0858, -0.1660, +0.3535,
+ +0.4799, -0.4005, +0.0061, +0.0206, +0.2809, -0.4679, +0.0673,
+ +0.1444, +0.4264, +0.1073, -0.0798, +0.2253, +0.2579, -0.2576,
+ -0.6007, +0.2503, +0.1877, +0.1759, -0.0705, -0.0339, +0.0163,
+ -0.2833, +0.0496, -0.0724, +0.2122, -0.3213, -0.3731, -0.1660,
+ +0.7755, +0.5124, -0.3694, +0.0588, +0.6647, -0.1604, +0.0630,
+ +0.4835, -0.0083, +0.0906, -0.0258, +0.1266, +0.2651, +0.2562,
+ -0.1427, -0.0474, -0.4239, -0.7708, +0.0567, -0.0012, +0.2501,
+ +0.3560, +0.2524, -0.0227, +0.3620, -0.1382, +0.0917, -0.5030,
+ -0.3181, +0.2090, -0.1478, +0.1735, +0.1747, +0.2128, -0.3544,
+ -0.0411, -0.2734, +0.1527, +0.1054, -0.0259, -0.0187, +0.3115,
+ +0.4073, +0.0994, +0.0935, +0.6014, -0.0894, +0.0277, -0.1051,
+ -0.1312, -0.1745, +0.3722, -0.0633, +0.0195, -0.1503, -0.2477,
+ +0.4542, +0.2569, -0.0691, -0.4412, -0.3885, +0.0734, -0.0987,
+ -0.2265, -0.3065, -0.3015, -0.1369, -0.0411, -0.0006, -0.3387,
+ -0.1562, +0.2495, +0.1843, -0.2748, +0.2291, +0.1961, -0.4904,
+ -0.0636, -0.4188, -0.1648, +0.0309
+ ],
+ [
+ -0.1101, +0.2888, -0.0570, -0.2413, -0.0390, +0.2698, +0.1938,
+ +0.0145, +0.0237, -0.2956, -0.4008, -0.0022, +0.0345, -0.1847,
+ +0.2073, +0.0978, -0.0419, -0.3933, -0.2629, +0.0098, -0.3885,
+ +0.1342, -0.0587, -0.1620, -0.3930, +0.1811, +0.1102, -0.1745,
+ -0.2421, +0.2253, -0.1974, +0.1268, +0.0282, -0.2039, +0.0702,
+ -0.2754, -0.0110, -0.0924, +0.2770, +0.0063, -0.0631, +0.0970,
+ -0.7981, +0.6435, +0.0694, -0.1290, -0.4013, -0.2976, -0.1189,
+ -0.0855, -0.0435, +0.2674, +0.0120, -0.1390, +0.1714, -0.0429,
+ +0.1475, -0.0044, +0.1297, +0.3749, -0.0918, -0.5348, +0.0863,
+ -0.3325, -0.4748, -0.1736, -0.3445, -0.1265, -0.1200, -0.0806,
+ -0.1163, +0.0163, +0.2598, -0.1576, -0.2488, -0.2472, +0.2509,
+ -0.4404, -0.1876, +0.3221, -0.3592, -0.1262, +0.3532, +0.0683,
+ +0.2758, -0.1483, -0.2939, -0.1960, -0.4137, +0.0178, -0.7016,
+ +0.3077, -0.2093, -0.0895, -0.2004, -0.3399, +0.0842, -0.0058,
+ -0.2212, +0.2213, +0.4328, +0.1054, +0.0692, +0.1697, -0.3399,
+ -0.6201, -0.2515, -0.1451, -0.3156, +0.0578, +0.0930, -0.3049,
+ +0.3093, -0.0713, +0.1023, +0.1076, +0.1541, +0.0090, -0.0674,
+ -0.2613, +0.5020, -0.0728, +0.0510, +0.3646, -0.2715, -0.2480,
+ -0.1565, -0.0924, +0.1268, +0.3606, -0.0366, +0.2756, -0.3328,
+ -0.1564, -0.1865, +0.2388, -0.0115, +0.1762, +0.0824, +0.1327,
+ -0.1527, -0.2355, -0.4851, -0.1165, +0.4048, -0.1261, -0.0750,
+ +0.0529, +0.0781, -0.1981, -0.1395, -0.1394, +0.1320, -0.3198,
+ -0.0006, +0.1270, -0.4287, -0.6049, +0.2057, +0.3400, -0.3563,
+ -0.4932, -0.5145, -0.1045, +0.1827, -0.3174, +0.0244, +0.0332,
+ +0.2180, +0.4740, -0.0398, -0.1993, -0.3635, +0.2097, -0.6872,
+ +0.2724, -0.1679, +0.0348, +0.3445, +0.1957, -0.3088, -0.1068,
+ -0.2200, -0.3352, -0.1096, +0.0410, +0.0512, +0.3525, +0.0330,
+ -0.5465, -0.2135, -0.1984, -0.2308, +0.5293, +0.1617, +0.2654,
+ -0.1835, +0.1527, -0.2546, -0.1011, -0.4182, +0.3049, +0.1546,
+ +0.0340, -0.3729, -0.0622, +0.1132, -0.0512, -0.2418, +0.5127,
+ +0.3217, -0.2271, -0.3689, -0.3579, -0.2182, -0.2907, -0.1061,
+ -0.0115, -0.1363, +0.0616, -0.3810, +0.2862, +0.1817, +0.1519,
+ -0.0023, +0.2365, -0.2017, +0.4321, +0.5002, -0.2249, +0.2603,
+ +0.1545, +0.2074, -0.0076, +0.3339, +0.2493, -0.0047, -0.1137,
+ +0.0961, -0.0032, -0.4285, -0.1184, +0.0864, -0.0413, -0.0146,
+ +0.1829, +0.1736, +0.5632, +0.1765, +0.0709, -0.2767, -0.3822,
+ +0.0837, -0.0828, -0.1817, -0.4356
+ ],
+ [
+ +0.0509, +0.2549, -0.0917, +0.0055, -0.1253, -0.2132, +0.1324,
+ +0.1052, +0.1497, -0.1908, -0.0401, -0.0706, +0.0651, +0.1787,
+ -0.1051, +0.0126, +0.0923, +0.1210, -0.1329, +0.0673, -0.0865,
+ -0.0131, -0.2468, -0.0502, -0.4783, -0.0405, +0.0969, -0.0889,
+ -0.3024, +0.0693, -0.0800, -0.0309, +0.2216, +0.0338, +0.0138,
+ -0.1827, +0.3096, -0.0509, +0.1161, -0.0364, -0.0345, +0.1886,
+ +0.0345, +0.0415, +0.0310, -0.0568, +0.0756, -0.2673, +0.4001,
+ +0.0710, -0.2191, -0.0395, +0.0336, +0.0451, -0.1021, -0.0249,
+ -0.0280, -0.1428, +0.0277, +0.0195, +0.0316, +0.1818, +0.2445,
+ -0.1122, -0.1844, -0.0665, +0.1236, +0.2563, -0.5410, -0.0603,
+ +0.3191, -0.0136, -0.1709, -0.1540, +0.1974, -0.1454, -0.1034,
+ -0.0974, -0.0698, +0.0841, -0.0363, -0.1820, +0.2072, -0.1064,
+ -0.0869, -0.1811, -0.1966, +0.1278, +0.0298, -0.2119, -0.1671,
+ -0.2875, -0.0361, -0.0482, +0.0314, +0.0290, +0.0851, +0.0537,
+ +0.0957, +0.2396, +0.1253, +0.0739, +0.1998, -0.0330, -0.1236,
+ -0.0330, -0.1687, +0.0705, +0.0731, -0.0384, -0.0285, -0.1246,
+ +0.0957, -0.0006, +0.0445, -0.0565, +0.0416, +0.1593, +0.1834,
+ +0.0946, -0.0487, +0.0335, +0.0907, +0.2604, -0.2899, -0.2021,
+ -0.3221, +0.0609, -0.0346, +0.0620, +0.0226, +0.0928, -0.2789,
+ -0.0239, -0.0884, -0.0846, -0.1203, +0.1690, +0.0817, -0.0668,
+ -0.1689, -0.0252, +0.1500, +0.0080, +0.0213, -0.0426, +0.0002,
+ +0.0008, +0.3091, -0.0535, +0.0746, +0.0195, +0.2861, -0.4008,
+ -0.2297, -0.0856, +0.1802, -0.1335, -0.1767, -0.4181, +0.0338,
+ -0.0447, -0.4958, +0.2912, +0.0691, +0.1188, -0.0518, -0.2267,
+ -0.1507, +0.0251, -0.0474, -0.0816, -0.1468, +0.0212, -0.1467,
+ -0.1739, +0.0645, -0.1244, +0.0266, -0.1640, -0.2757, -0.3275,
+ -0.0195, +0.0605, +0.1956, -0.0616, -0.1276, +0.1034, -0.1577,
+ -0.4807, -0.0699, +0.1038, -0.3131, +0.3759, +0.0188, -0.1638,
+ +0.1375, -0.0620, +0.0319, +0.0859, +0.0839, -0.1305, +0.4374,
+ +0.2390, -0.0321, -0.0078, +0.3058, +0.0666, -0.2315, +0.0097,
+ -0.0036, -0.1209, -0.3647, -0.1463, +0.1597, -0.5550, -0.1898,
+ +0.0746, -0.0216, +0.1312, -0.1723, -0.1189, +0.0156, +0.2415,
+ -0.0221, +0.0615, +0.1584, -0.0553, +0.2352, +0.1394, +0.1370,
+ -0.2963, +0.0449, -0.1839, +0.3226, -0.0966, +0.4623, -0.0386,
+ -0.0344, -0.1119, -0.0139, +0.0523, -0.0863, +0.1050, +0.0226,
+ +0.0937, -0.0856, +0.3126, +0.0949, +0.2978, -0.2201, -0.0661,
+ +0.2530, +0.0930, -0.0358, -0.0728
+ ],
+ [
+ +0.0133, -0.2384, -0.0061, -0.0901, -0.1275, -0.1155, -0.2142,
+ -0.1617, +0.3009, -0.0036, -0.0136, -0.0096, -0.3440, -0.0666,
+ +0.1599, -0.0057, -0.2449, +0.2083, -0.0132, -0.0672, +0.0751,
+ -0.0280, -0.1097, -0.2804, -0.0946, +0.0997, -0.1202, -0.0579,
+ -0.1848, +0.0839, -0.0730, +0.0810, +0.1752, +0.1299, +0.0543,
+ +0.2047, +0.2369, +0.0868, -0.4617, -0.3397, +0.1840, -0.1539,
+ +0.1362, -0.2022, -0.0365, +0.1864, -0.4431, +0.1442, -0.1381,
+ -0.2529, +0.0283, -0.3730, -0.1827, -0.4236, -0.1750, -0.0424,
+ -0.1016, +0.1586, -0.1437, -0.0213, +0.3303, -0.1499, -0.0556,
+ +0.0507, -0.0538, -0.0622, +0.2669, +0.0454, -0.0731, +0.1335,
+ +0.2288, -0.0877, -0.0884, +0.0883, -0.1660, +0.0539, -0.0647,
+ -0.1985, +0.0427, +0.1618, +0.0732, -0.1073, -0.0604, -0.2294,
+ -0.0829, +0.0373, -0.2572, -0.1134, -0.1325, -0.0592, -0.2515,
+ -0.7041, +0.1332, -0.2625, -0.3124, +0.0847, -0.2374, +0.0154,
+ +0.2717, +0.0413, -0.2797, -0.3216, +0.0994, -0.2653, -0.1076,
+ -0.2748, -0.1153, +0.0928, -0.0615, -0.1129, -0.0233, +0.0454,
+ -0.5039, +0.2351, +0.0766, -0.0882, -0.1210, -0.5043, -0.0870,
+ +0.2185, +0.2934, +0.1159, +0.3287, +0.0840, -0.2659, -0.4456,
+ +0.1535, +0.4992, +0.4418, -0.0713, -0.0580, -0.3314, -0.1225,
+ -0.1038, +0.1139, +0.2054, +0.1049, -0.0219, -0.1247, +0.0612,
+ +0.0055, +0.0180, +0.0207, -0.0282, +0.1353, +0.0653, +0.1345,
+ +0.1435, +0.0643, +0.0131, -0.1639, +0.1931, +0.3108, -0.1027,
+ +0.3498, -0.0372, +0.0780, +0.0271, +0.0456, +0.0713, -0.1977,
+ +0.1929, -0.3310, -0.4828, -0.3361, +0.1634, +0.2493, -0.1914,
+ -0.1188, -0.0863, +0.1576, -0.0852, +0.3123, +0.0625, +0.1785,
+ -0.2350, -0.2904, -0.2623, +0.3570, -0.0630, +0.0245, -0.4582,
+ -0.2041, +0.0670, +0.0551, +0.1855, +0.1265, -0.0155, -0.2492,
+ +0.2700, +0.1065, +0.0067, +0.1265, +0.0670, -0.0494, -0.2904,
+ +0.3440, -0.1183, +0.0556, -0.1526, -0.0097, +0.1318, -0.1130,
+ +0.2119, -0.0430, -0.1200, -0.0621, -0.2154, +0.2679, -0.0248,
+ -0.1998, -0.2859, -0.2692, -0.3040, -0.3696, -0.0085, -0.3063,
+ -0.5537, -0.1833, -0.1371, -0.2980, +0.0445, -0.0327, +0.3345,
+ -0.0481, -0.1551, +0.0561, -0.0279, +0.1251, +0.0571, +0.2553,
+ -0.2445, -0.1182, +0.1923, +0.0178, -0.1569, -0.0934, +0.0127,
+ +0.2180, +0.2012, +0.0539, +0.1074, +0.0909, +0.0018, -0.0202,
+ -0.2950, -0.1744, +0.0324, +0.0047, +0.0917, -0.2003, -0.1513,
+ -0.2091, -0.0636, +0.0784, +0.0418
+ ],
+ [
+ -0.2106, -0.5721, -0.0255, -0.1498, +0.1872, +0.3760, -0.1564,
+ +0.0184, +0.0084, -0.0493, -0.0988, -0.0707, -0.1691, +0.1350,
+ -0.3833, +0.2407, -0.1562, -0.0640, -0.0549, +0.0372, -0.0310,
+ -0.0492, +0.0252, +0.1114, +0.1642, +0.0543, +0.0866, +0.2849,
+ +0.4380, -0.0755, +0.0529, -0.0072, -0.0424, -0.5035, +0.0025,
+ -0.2118, -0.1066, -0.0997, -0.3320, +0.4686, +0.2913, -0.2035,
+ -0.1154, -0.2489, +0.1538, -0.0449, -0.4716, -0.0805, -0.0606,
+ +0.1385, -0.0411, -0.4550, +0.1078, -0.3315, -0.5334, +0.0061,
+ -0.8814, +0.0727, +0.1807, +0.1161, -0.1132, -0.4640, -0.2277,
+ -0.2282, -0.2055, -0.5139, +0.0047, -0.0208, +0.1003, -0.2417,
+ +0.0952, +0.2703, -0.1661, +0.1264, -0.4941, +0.0922, +0.1002,
+ -0.1667, -0.1846, +0.0267, +0.0046, -0.3622, -0.0821, -0.1047,
+ -0.2113, -0.1532, +0.2937, -0.0069, +0.1870, +0.0629, +0.0534,
+ -0.3144, -0.2376, +0.4708, -0.0426, +0.1698, +0.1616, -0.1427,
+ -0.0134, -0.1560, -0.0194, +0.1307, -0.0201, +0.0507, +0.1696,
+ +0.3215, -0.3706, +0.3820, +0.3235, -0.2105, -0.0798, -0.0110,
+ +0.0270, -0.1236, +0.1016, +0.3631, -0.1671, +0.0517, -0.0126,
+ -0.4177, +0.0929, -0.0079, -0.4019, +0.1569, +0.1172, +0.0554,
+ +0.2186, -0.0931, -0.1609, -0.0355, -0.4825, -0.9546, +0.1382,
+ +0.2313, -0.7419, -0.0895, -0.1796, -0.0352, -0.0448, +0.1210,
+ -0.1250, +0.1624, -0.1704, -0.0683, -0.1812, -0.0288, -0.0914,
+ +0.3675, -0.3053, +0.1319, -0.4109, -0.0725, +0.0943, -0.3600,
+ -0.1820, -0.7750, -0.4543, -0.1667, +0.0541, +0.1525, +0.3136,
+ +0.2429, +0.0330, +0.0671, -0.0504, +0.2418, -0.0134, -0.0162,
+ +0.0131, -0.0574, -0.0483, -0.1079, -0.0850, +0.0559, +0.0030,
+ -0.2679, -0.1837, -0.4726, +0.0286, +0.0347, +0.0651, -0.0097,
+ -0.0460, -0.2189, -0.1798, -0.0577, -0.0150, +0.4606, -0.5806,
+ -0.0051, -0.2598, -0.2094, -0.6703, +0.2159, +0.0723, +0.0526,
+ -0.2678, +0.0617, -0.1728, +0.1177, +0.2750, +0.0184, -0.4359,
+ -0.0940, +0.0947, -0.2164, -0.4097, +0.2435, -0.1214, +0.2233,
+ +0.1313, -0.6796, +0.1504, +0.0502, -0.1445, -0.3432, +0.0023,
+ -0.3242, -0.0105, -0.0249, +0.3985, -0.1757, -0.0498, -0.0050,
+ +0.2735, -0.1137, +0.1709, +0.2007, -0.5754, -0.1786, -0.0405,
+ +0.0717, -0.6758, -0.1847, -0.4255, -0.3366, +0.0736, -0.3934,
+ -0.0511, -0.2154, -0.0673, -0.1232, -0.0641, +0.0687, -0.0759,
+ +0.0476, +0.1716, +0.2402, +0.0314, -0.0472, -0.9131, -0.6135,
+ -0.1311, +0.0928, +0.0507, -0.1242
+ ]])
-weights_dense1_w = np.array([
-[ +0.3543, -0.3833, +0.3987, +0.1828, +0.5746, +0.3807, +0.1427, +0.2510, -0.3705, -0.2212, +0.0019, +0.7898, +0.2609, -0.5883, -0.1780, +0.1319, +0.4746, -0.5833, -0.4251, +0.5949, +0.6170, -0.2344, +0.1624, -0.7524, -0.1314, +0.3180, -0.3183, -0.5343, +0.6109, -0.0071, +0.0890, +0.1470, +0.3201, -0.1915, -0.1192, -0.2254, +0.1921, +0.5020, +0.8814, +0.7632, +0.2973, -0.0293, +0.0134, -0.1171, +0.4190, +0.2720, -0.1020, +0.2688, -0.3085, -0.0548, +0.4256, +0.5690, -0.2243, +0.4055, +0.7467, +0.2371, -0.1666, -0.3083, -0.2019, -0.1256, -0.2922, -0.0295, -0.1915, +0.4345, +0.4745, +0.4599, +0.7173, +0.1671, -0.1942, +0.6437, +0.1593, -0.2243, -0.3772, +0.0888, +0.0181, +1.5305, +0.1103, -0.0983, +0.5553, -0.2304, +0.1091, -0.7436, -0.4132, -0.0910, -0.3729, +0.5907, -0.0080, -0.3815, +0.4647, -0.4074, +0.2752, +0.2604, +0.2102, +0.1988, +0.5086, +0.1865, -0.5980, +0.1655, +0.3442, -0.0285, +0.4722, -0.4559, -0.8286, +0.2297, +0.1441, +0.5148, +0.9493, +0.3310, +0.1502, +0.1993, +0.4227, +0.8433, -0.3427, +0.7080, +0.3844, +0.4788, +0.0027, +0.0413, -0.2622, -0.2789, -0.1309, -0.0235, +0.9649, -0.3073, +0.4120, -0.1224, +0.3168, -0.4171, +0.2409, +0.8089, +0.2216, +0.7449, +0.1001, -0.0277, -0.2632, +0.0697, +0.2002, +0.4163, -0.1231, +0.3181, +0.4182, +0.9432, +0.5265, +0.0247, +0.0824, +0.2249, -0.5920, +0.1227, -0.4454, +0.2406, +0.2175, +0.4905, +0.2078, +0.1180, -0.2074, +0.2553, -0.4872, +1.0349, +0.0574, -0.0449, -0.3136, +0.1975, -0.1428, +0.1385, +0.0113, -0.0366, -0.2522, +0.7889, -0.5059, +1.0163, +0.4410, +0.0459, -0.2020, +0.3168, -0.8575, +0.4499, -0.0539, -0.0231, -0.0449, +0.0083, +0.0040, +1.1597, -0.3938, +0.0570, +0.2773, +0.7838, +0.5444, +0.3460, +0.0922, -0.0916, -0.1977, -0.2641, +0.5723, +0.1033, -0.6443, +0.1281, +0.4627, +0.6561, +0.0765, +0.2997, +0.4318, -0.4581, +0.0353, +0.1669, +0.0664, -0.0233, +0.0447, +0.3139, +0.0570, +0.0322, +0.7074, -0.0692, +0.0741, +0.1177, +0.7109, +0.1507, -1.0050, +0.0803, +0.1696, -0.7228, -0.3827, +0.3475, -0.0327, +0.0961, +0.5664, +0.2477, +0.3436, -0.0406, +0.2801, +0.1499, +0.0971, -0.2689, +0.0691, -0.1481, -0.1288, +0.5560, +0.2778, +0.2370, +0.1795, +0.3816, +0.8086, +0.2443, -0.2036, +0.8701, +0.3228, +0.0493, +0.4232, +0.2833, +0.1421, +0.0004, -0.3722, -0.8666, -0.1084, -0.2561, -0.2230, -0.0161],
-[ +0.0958, -0.1782, +0.3288, +0.0482, +0.0290, -0.3382, +0.3124, +0.1661, +0.0309, +0.0167, +0.3039, -0.2731, +0.2352, -0.0909, +0.0472, -0.0685, +0.2378, +0.0030, -0.0057, -0.2164, +0.1759, +0.2240, +0.1018, +0.3923, +0.2377, +0.2124, -0.2076, +0.2497, +0.2697, -0.2019, -0.1881, -0.0446, -0.4666, +0.4909, -0.0879, -0.3494, -0.3057, -0.0409, +0.0555, -0.1819, -0.0586, -0.2323, +1.0968, -0.1451, +0.0927, +0.1340, -0.3688, -0.0321, -0.1371, +0.2704, -0.2831, +0.0576, +0.2786, -0.4570, +0.0034, -0.1193, -0.2615, +0.1571, -0.0981, +0.1934, +0.2114, +0.4198, +0.0797, +0.0997, -0.0848, -0.1339, +0.2575, -0.0421, +0.2907, +0.2311, +0.2077, -0.1234, +0.2197, +0.3210, +0.2515, -0.1523, +0.0573, +0.0863, +0.0221, -0.1319, +0.1101, -0.1512, -0.0253, +0.3307, +0.3122, +0.2278, +0.0856, +0.0814, -0.2028, -0.0373, -0.2210, +0.2000, +0.1657, -0.0533, +0.1978, -0.2226, +0.0377, +0.4188, +0.0766, +0.2088, +0.2568, -0.0574, -0.3792, +0.2971, -0.1956, -0.0845, -0.1638, -0.0269, -0.2203, +0.5461, +0.0076, +0.3380, -0.2262, +0.1973, -0.2503, -0.1507, -0.2942, +0.1642, -0.2460, -0.1684, -0.0207, +0.0026, +0.3213, -0.0170, +0.5102, -0.2842, +0.2971, -0.2165, +0.1205, -0.0015, +0.0166, +0.1441, -0.1231, +0.0713, +0.1159, -0.3383, +0.0572, -0.0782, -0.0589, +0.2331, -0.0825, -0.0095, -0.1379, -0.0909, +0.0111, -0.0969, +0.1849, -0.1454, +0.1298, -0.1478, -0.1134, -0.0017, +0.4045, +0.1368, -0.2911, +0.0401, -0.0180, +0.5063, +0.3238, +0.1427, -0.1532, -0.0783, -0.1042, -0.0411, +0.0817, -0.1855, +0.0211, +0.0212, +0.0748, -0.1480, -0.0379, +0.0186, +0.0107, -0.0290, +0.0324, +0.0711, +0.2620, +0.1047, -0.4431, -0.1354, +0.0647, +0.1472, -0.0249, -0.3687, +0.4135, +0.1640, -0.1606, +0.1635, -0.2894, +0.1293, +0.1063, -0.3286, -0.5707, -0.1076, +0.2624, +0.0245, -0.3619, +0.0624, -0.1214, +0.3565, -0.2067, +0.2906, +0.2800, +0.0814, +0.4657, +0.1716, -0.2339, +0.1425, -0.2436, -0.0386, +0.6793, +0.0337, +0.3238, +0.2363, -0.1065, -0.3087, -0.1684, -0.0784, +0.1175, +0.1939, +0.5676, -0.1382, -0.1300, +0.6986, -0.1262, -0.1023, -0.6929, +0.0871, -0.2003, -0.2158, -0.4234, +0.1276, +0.2671, +0.1822, +0.7594, +0.1000, +0.4422, +0.0027, +0.0716, +0.2667, +0.1928, +0.2579, -0.1292, -0.1112, -0.0446, -0.1893, +0.5958, -0.0906, +0.1439, +0.3357, +0.4613, +0.2427, -0.2639, -0.2407, -0.0296, +0.1122],
-[ -0.5187, +0.2287, +0.2752, +0.1228, -0.4072, +0.0853, -0.0049, -0.0030, -0.0514, +0.2529, +0.0103, +0.3002, -0.1213, -0.3048, +0.1508, +0.0940, +0.1131, -0.0398, -0.1921, +0.0943, +0.3511, +0.1262, -0.1832, -0.0754, -0.3122, -0.1396, -0.1342, +0.0026, +0.1042, +0.1073, -0.3781, +0.1753, -0.1475, -0.0098, -0.1979, -0.0963, +0.0744, +0.1211, -0.4690, -0.0567, -0.2050, +0.0610, +0.0799, -0.0853, +0.1085, -0.2187, -0.0474, +0.0588, -0.4914, -0.3591, -0.0325, -0.1640, -0.1259, +0.2144, +0.2286, -0.0006, -0.2550, -0.1209, +0.0025, -0.2094, +0.0772, -0.3342, -0.1242, +0.1456, -0.2479, -0.0827, -0.2497, +0.1308, -0.1004, -0.0134, +0.0534, +0.0458, -0.5951, +0.0508, +0.2547, +0.0729, +0.0317, -0.1115, +0.3033, -0.2973, +0.1477, +0.1418, -0.1385, +0.1961, +0.2135, -0.0573, +0.0018, -0.1410, +0.1146, -0.3430, -0.2801, -0.0008, +0.3632, -0.0757, -0.1747, +0.1223, +0.0343, +0.1432, +0.2027, -0.0085, -0.1352, +0.2187, -0.2602, -0.4523, -0.1417, -0.0164, +0.0977, +0.1679, +0.0650, +0.3161, +0.5088, +0.2696, -0.0018, +0.2048, -0.5342, -0.1123, -0.0499, -0.1345, +0.0267, -0.7731, -0.0320, +0.1851, +0.1143, +0.0312, +0.0069, +0.2073, +0.0478, +0.0664, -0.3389, +0.2681, -0.1528, +0.3933, +0.0777, +0.1889, +0.2740, -0.2838, -0.0483, +0.2780, -0.0631, -0.0021, +0.2336, +0.3078, -0.1664, +0.0241, -0.5676, +0.0183, +0.0869, -0.3300, +0.0455, -0.0271, +0.1659, -0.2304, +0.1064, -0.3165, -0.1034, -0.0027, -0.2941, -0.1458, +0.0648, +0.1050, +0.0824, -0.2342, -0.6234, +0.1293, -0.0112, -0.4213, -0.1430, -0.0978, -0.3229, +0.0542, +0.3499, +0.2255, +0.1985, -0.1539, +0.1177, +0.0342, -0.5749, -0.4455, -0.0349, +0.0118, -0.1757, -0.3755, +0.2552, -0.0067, -0.2466, +0.0227, +0.1964, +0.1425, -0.8570, -0.3395, +0.2669, -0.3031, -0.1005, -0.0378, +0.1286, +0.0222, +0.1333, -0.2285, -0.0157, -0.2054, -0.1904, +0.0256, -0.0028, +0.1041, +0.0959, +0.1583, +0.1038, -0.3391, -0.1159, +0.0815, -0.4441, +0.2713, -0.4762, +0.0379, -0.0479, -0.2772, +0.0133, -0.2058, +0.3131, +0.0004, +0.0261, -0.1871, +0.3252, +0.1042, +0.0255, -0.3935, -0.0056, -0.1552, -0.1384, -0.1413, +0.2543, +0.2404, -0.0705, -0.0451, +0.0732, +0.2933, +0.2115, +0.1148, -0.2568, +0.2483, -0.2113, +0.0656, -0.1139, -0.1590, +0.0919, -0.0663, +0.2719, -0.2828, +0.0277, -0.0606, -0.0600, -0.4945, -0.0344, -0.1378, -0.3805, -0.0176],
-[ -0.0570, -0.3114, -0.1088, +0.6142, -0.1379, -0.0909, +0.3296, -0.0470, -0.0442, -0.7245, +0.4978, -0.3704, -0.0556, -0.9845, -0.5872, +0.2280, -0.7789, +0.0387, +0.2177, +0.1441, +0.1711, +0.4705, +0.8632, +0.3682, +0.1355, +1.3679, -0.2215, -0.0370, -0.1336, +0.5885, +0.6607, -0.1850, -0.2828, +0.1596, +0.1422, -0.5338, +0.1196, +0.1801, +0.1746, -0.6810, -0.1652, -0.0237, -0.1493, +0.2489, +0.0379, +0.6433, +0.1872, +0.4326, +0.2534, +0.1013, +0.4340, -0.0254, -0.2332, -0.5027, +0.1654, +0.6060, -0.2868, -0.0742, -0.3677, +0.0188, -0.1034, +0.0072, -0.6168, -0.0069, +0.1889, +0.2089, -1.2578, -0.3993, -0.3688, +0.1227, -0.0849, +0.3978, +0.5294, +0.4421, -0.3402, +0.1462, +0.1488, -0.1681, +0.0587, +0.2754, -0.5148, -0.2919, +0.0246, +0.0277, +0.1282, -0.5015, -0.2559, +0.1333, -0.9075, +0.0369, +0.2989, +0.2742, -0.3045, +0.0530, +0.5996, -0.1369, -1.0727, +0.0708, +0.5281, -0.6266, +0.2929, -0.0272, -0.6657, -0.0327, +0.7032, -0.3803, -0.4939, -0.4937, +0.5844, -0.4650, -0.6580, -0.4147, +0.0574, +0.1599, +0.4039, +0.1270, -0.2136, -0.3195, -0.1574, +0.3678, -0.2304, -0.1422, +0.0063, -0.2868, +0.1114, -0.2380, -0.1446, +0.6534, -0.7640, -0.4790, -0.2581, +0.0866, +0.6298, -0.1627, +0.2434, -0.1345, -0.1591, -0.6833, +0.8013, -0.0074, -0.3966, -0.3063, -0.2725, +0.1495, -0.0078, -0.2898, -0.2865, +0.6035, -0.7516, +0.4026, -0.1695, -0.5334, +0.0071, -0.2942, -0.4005, -0.1630, +0.4325, +0.7765, +0.2475, -0.4999, -0.7969, -0.7106, +0.4207, +0.1617, -0.4988, +0.0723, +0.7424, -0.1637, +0.1045, -0.5962, -0.1980, +0.2069, +0.1651, +0.3050, -0.4303, +0.1358, -0.2130, -0.3275, +0.1884, +0.3995, -0.4926, -0.2890, -0.2000, -0.2949, -0.2786, -0.1046, -0.4901, +0.3215, -0.6671, -0.0014, -0.6554, +0.1843, -0.0903, -0.0866, -0.8480, -0.0981, -0.0733, -0.1374, +0.3921, +0.1671, +0.0656, -1.0367, +0.5457, -0.0115, -0.2121, +0.3420, -0.2665, +0.0299, -0.3441, +0.4883, -0.1289, -0.5812, +0.8116, -0.1478, +0.0101, +0.3588, -0.6830, -0.1244, +0.2684, -0.3833, +0.0715, +0.5570, +0.4727, -0.0386, -0.4478, +0.4346, -0.2378, -0.2175, -0.5516, -0.0764, -1.6323, +0.2628, +0.4238, +0.1281, +0.1813, +0.3879, -0.1268, +0.0123, +0.3925, -0.1931, -0.6132, -0.5956, +0.6764, -0.0714, +0.0154, -0.1122, -0.4323, +0.5535, -0.3156, -0.3578, -0.8526, -0.4097, +0.2420, +0.1931, +0.6615, +0.4633],
-[ +0.3856, +0.0380, +0.1607, +0.7211, -0.4803, +0.3282, +0.6278, +0.2020, -0.8478, -0.0240, -0.2271, -1.1262, +0.1720, +1.0624, -0.4353, -0.3814, +0.4174, +0.3153, -0.0629, +0.5575, +0.3262, -0.2309, +0.7053, -0.7675, +0.0130, -0.4398, -0.4520, -0.4738, -0.2739, +0.2262, +0.3351, -0.7933, +0.3686, +0.1975, +0.5455, -0.3773, -0.1874, +0.0645, -0.6104, +0.9056, -0.0197, +0.7429, -0.0564, -0.1760, -0.4114, -0.2636, -0.3710, +0.5700, -0.4883, +0.4906, +1.3030, +0.1374, -0.5772, -0.2841, +0.6549, -0.2637, -0.6877, +0.1885, -0.2468, -0.2661, -0.1269, -0.0954, +0.4093, -1.0006, -1.0739, +0.5058, +0.1711, -0.5654, -0.9009, -0.3533, +0.7245, -0.0761, -0.7570, -0.5107, +0.5003, -0.3738, +0.8248, -0.0174, -0.0329, +0.1597, +0.3538, +0.1845, +0.5623, +0.1166, -0.0666, -0.2745, -0.3009, +0.3987, -0.2977, -0.6311, +0.0018, -0.2627, -0.6512, -0.0303, -0.9577, +0.2203, +0.2135, -0.0742, -0.6742, -0.2723, -0.1118, +0.4371, +0.3550, +0.4606, +0.4340, +1.0860, +0.1818, -0.5315, +0.4768, -0.1874, -0.2363, -0.6467, +0.9317, -0.1335, +0.5472, +0.6879, +0.1606, +0.1596, -0.1357, -0.0811, -0.3636, +0.7840, -0.1458, +0.4020, -0.0052, -0.1393, +0.3154, -0.0006, -0.7112, +0.2714, +0.5062, +0.1726, +0.7692, -0.1091, +0.3916, -0.2577, -0.5718, -0.4336, +0.1497, +0.4095, +0.3539, +0.6999, -0.5753, -0.0278, -0.6541, +0.5542, -0.7776, +0.0913, -0.6832, -0.6140, +0.0515, -0.2613, +0.1417, -0.9894, -0.1342, -0.2246, -0.1429, -0.4141, +0.1981, -0.1309, +0.3413, +0.3129, -0.1747, -0.5412, +0.6874, +0.3260, +0.0846, +0.3818, +0.4490, +0.7462, +0.0062, -0.2363, -0.1671, -0.5198, -0.6330, +0.9872, -0.2159, +0.4651, -0.2138, +0.3548, +0.7041, -0.2278, -0.1848, -0.8821, +0.2462, -0.1612, +0.8281, +0.8352, -0.7345, -0.1699, +0.3341, -0.4163, +1.0198, +0.2347, -0.2900, -0.3751, +0.8562, -0.7091, -0.6140, +0.1578, -0.3085, +0.5008, -0.3238, -0.1784, +0.1425, +0.2281, -0.6608, -0.4512, +0.6757, -0.2319, +1.3040, -0.3273, +0.2071, -0.1651, +0.0148, +0.3103, +0.3019, -0.1881, +0.2410, +0.0305, +0.0504, -0.3716, -0.1396, -0.2934, +0.1656, -0.3740, -0.1310, +0.0817, -0.0037, +0.2901, -0.5307, -0.4163, -0.7077, -1.1809, -0.6042, +0.0345, -0.5511, -0.2317, +0.7121, +0.5965, -0.1168, -0.7979, -0.0691, -0.0206, +0.0990, -0.5956, -0.2970, -0.8674, -0.1161, +0.4983, -0.9971, +0.5049, +0.3464, -0.1332, -0.6007, -0.0100],
-[ -0.3086, -0.2303, +0.3152, -0.1116, +0.0799, -0.3931, -0.1490, -0.0247, -0.7502, -0.1217, +0.7861, -0.1143, -0.3911, -0.4594, +0.1463, +0.0265, -0.0780, -0.6028, +0.4631, +0.7258, +0.4649, +0.0420, -0.0493, +0.1636, -0.3396, -0.0729, +0.4166, -0.3020, -0.0168, -0.4617, +0.0944, -0.2123, +0.7230, -0.2222, -0.3647, -0.0116, -0.3939, -0.2826, +1.0357, +0.4180, -0.2008, +0.7345, +0.0222, +0.0816, -0.3684, -0.1234, -0.4089, -0.0311, -0.1626, -0.2367, -0.0980, -0.2955, -0.1024, -0.4637, -0.2925, +0.5904, -0.5515, -0.2542, +0.0690, -0.1179, -0.2136, +0.2457, -0.1525, -0.0990, -0.0583, +0.1767, +0.4226, -0.1596, +0.0185, +0.0476, -0.0666, -0.0392, -0.3034, -0.2679, -0.5904, -0.0414, +0.5802, -0.3043, +0.7735, -0.1095, +0.1673, +0.2152, +0.0611, -0.3035, -0.2460, -0.2300, +0.4381, -0.1431, +0.4268, +0.1144, -0.1928, -0.1918, -0.6915, -0.5794, -0.3670, +0.7585, -0.8027, +0.3487, +0.5753, -0.2920, +0.3446, -0.1739, +0.6269, -0.1520, -0.2745, +1.0809, -0.3024, +0.0255, +0.1935, +1.0626, +0.6935, +0.0820, -0.6116, +1.3359, -0.4234, -0.6222, +0.0244, +0.0389, -0.6722, +0.4178, -0.2680, -0.0337, +0.0640, -0.0816, -0.0498, -0.4453, +0.0734, +0.1799, -0.0322, -0.6132, +0.3590, +0.1533, +0.4668, +1.0410, -0.6774, +0.2069, -0.3858, +0.0929, +0.2870, -0.5417, +0.2325, -0.5414, +0.1480, +1.1710, +0.2069, +0.4407, +0.1163, +0.0144, -0.5544, -0.2193, +0.2130, -0.2111, -0.0325, +0.3058, -0.2408, +0.3621, +0.1342, +0.2040, -0.0684, +0.4992, +0.0703, +0.1867, -0.6955, +0.4513, -0.7907, +0.3006, -1.0133, +0.1236, -1.0365, +0.0708, +0.4165, -0.3972, -0.9550, -0.0497, -0.7666, +1.1159, -0.5457, -0.5034, -0.2620, +0.3694, -0.8464, +0.0237, +0.0522, -0.0003, -0.0889, +0.1617, -0.0572, -0.7113, -0.3840, +0.0955, -0.5163, +0.2279, -0.0807, -0.3170, -0.3465, +0.3036, +1.0967, +0.4635, +0.3360, +0.1150, -0.0211, +0.2847, -0.2062, -0.0093, +0.5722, -0.3048, +0.2928, +0.3035, -0.3387, -0.3379, -0.1001, -0.2899, +0.4759, -0.7681, +0.0895, +0.2146, -0.4089, -0.0256, -0.0714, -0.8717, -0.1449, -0.4994, +0.4098, -0.4314, +0.0200, +0.0395, +0.5496, +0.3181, -0.0524, +0.3103, +0.4681, +0.0415, +0.0460, +0.3279, +0.2327, +0.1861, +0.3333, -0.0774, +0.1634, +0.0597, -0.0172, +0.7018, -0.2210, +0.4247, +0.1282, -0.0706, +0.5843, +0.0847, +0.1637, +0.1443, -0.4523, -0.1132, -0.1423, -0.4084, +0.2323, -0.3703],
-[ -0.1628, -0.0910, +0.3645, -0.0508, -0.0480, -0.3354, +0.1378, -0.0796, -0.0735, +0.5216, -0.4845, -0.1646, -0.0843, -0.4177, -0.0659, +0.1129, -0.2721, +0.0506, -0.1478, -0.2329, -0.4058, +0.3746, +0.1111, +0.0048, +0.3003, +0.1400, +0.0219, +0.0036, -0.3503, -0.4100, -0.5064, +0.0641, -0.0306, +0.0931, -0.1036, +0.1072, +0.2196, +0.2135, -0.0883, -0.0936, +0.4832, -0.2619, +0.0382, -0.1628, +0.2677, -0.0128, +0.2590, -0.0291, +0.0483, +0.0877, -0.5890, -0.2196, +0.6421, -0.2236, -0.1257, -0.1504, -0.1872, +0.3704, +0.3330, -0.1955, +0.0496, -0.2220, +0.0055, +0.3401, -0.0080, -0.2781, -0.1191, +0.1448, -0.2057, +0.1096, -0.3750, +0.0790, -0.2106, +0.2074, -0.5412, -0.0403, -0.2812, +0.0347, -0.3933, -0.0388, +0.0326, -0.1072, -0.3437, -0.3396, -0.1000, +0.0953, +0.0622, +0.3081, +0.0067, +0.1591, -0.0479, +0.0482, -0.0583, +0.0411, +0.2547, -0.1814, +0.0753, +0.3990, +0.0501, +0.0626, +0.0417, -0.1376, -0.4501, -0.1439, -0.0770, -0.2651, -0.1445, +0.0230, -0.0958, -0.2221, +0.1717, +0.1478, -0.3690, -0.0121, -0.6698, -0.0107, +0.1424, +0.0987, -0.0837, +0.3131, +0.0049, -0.3202, -0.0791, +0.0609, +0.3332, +0.1109, +0.0441, +0.1337, +0.3522, +0.2834, -0.3200, +0.5293, -0.4299, -0.3855, -0.1533, -0.0158, +0.1217, +0.0241, +0.0385, +0.1733, -0.1477, -0.6579, -0.2818, +0.3793, +0.1597, -0.0041, +0.7934, -0.0526, -0.0997, -0.1419, -0.1658, +0.0885, +0.1390, +0.1498, +0.1663, +0.0392, +0.0062, -0.4296, -0.4038, -0.1783, -0.6737, -0.2527, +0.0699, +0.2806, -0.3069, -0.3786, +0.0694, -0.4885, -0.0376, -0.0348, +0.1368, +0.4004, -0.4894, +0.1556, -0.1203, -0.3302, -0.0035, -0.3673, -0.1165, +0.0151, -0.1661, -0.0333, +0.0094, -0.0662, +0.1448, +0.1488, +0.0889, +0.0471, -0.0258, -0.0398, +0.0644, +0.2740, +0.1195, +0.1212, +0.5019, +0.3957, -0.0550, +0.0132, +0.1896, -0.2745, +0.1156, +0.0533, +0.0720, -0.1548, +0.0618, +0.0207, -0.4556, +0.0640, -0.1698, -0.3250, -0.0661, +0.1830, -0.0418, -0.2160, +0.1792, -0.0936, +0.4091, +0.1251, -0.3348, -0.4267, -0.1236, -0.3609, -0.1682, -0.2184, -0.0190, +0.1700, -0.1136, +0.0990, +0.1668, -0.4809, -0.0527, +0.2783, -0.1648, +0.0666, -0.4016, -0.0171, -0.0927, +0.0272, -0.0748, -0.2201, -0.1642, -0.1352, -0.2004, -0.1135, +0.0900, -0.4194, -0.0612, +0.0011, -0.1709, -0.4136, +0.1379, -0.6458, +0.0194, +0.0137, -0.2739, +0.1318],
-[ +0.2941, +0.0220, -0.1901, +0.4145, -0.0985, +0.1034, -0.1606, -0.3785, +0.0137, -0.3654, -0.0186, -0.0143, +0.5334, -0.6222, -0.4792, -0.1071, -0.2142, +0.1365, +0.0561, -0.1022, -0.1284, +0.0839, +0.5839, +0.1329, -0.4641, -0.3027, -0.4039, -0.0029, +0.2187, +0.1188, +0.5330, -0.0991, +0.3822, +0.0137, +0.0068, +0.6088, -0.4833, +0.2309, -0.0574, -0.3048, -0.2147, +0.4370, -0.3575, +0.0376, -0.3573, +0.0106, -0.1274, -0.0276, -0.2841, +0.3764, +0.0159, -0.3053, +0.0185, -1.1135, -0.2184, +0.2868, -0.1948, -0.3448, -0.2687, -0.2092, +0.3704, -0.5749, +0.4552, +0.1527, -0.1372, -0.0008, -0.4404, +0.0628, +0.2003, -0.0796, -0.1033, +0.2826, -0.1446, +0.4242, +0.2081, -0.1591, +0.1138, +0.5412, +0.1826, -0.1263, -0.3358, -0.3514, +0.2250, +0.0796, +0.0664, -0.2066, -0.1902, +0.0692, -0.8032, -0.1846, -0.2625, -0.2155, +0.1517, +0.3779, +0.0002, -0.2571, -0.5203, +0.0563, -0.0233, -0.4733, +0.0410, +0.1257, -0.3867, +0.6560, +0.3189, -0.3361, -0.2162, +0.1337, +0.4443, -0.7335, -0.0340, -0.4568, +0.0073, +0.2620, +0.0836, +0.5431, +0.2070, +0.1648, +0.4627, +0.1931, -0.1628, +0.0428, -0.3230, -0.0696, -0.1291, -0.4876, +0.2044, +0.0711, -0.3727, -0.9706, +0.2452, -0.2355, +0.3298, -0.4576, -0.0451, +0.0020, +0.2921, -0.2879, +0.0644, -0.0059, -0.2419, -0.6224, -0.2768, +0.0733, -0.0946, -0.2335, -0.2709, +0.2540, -0.0022, +0.2774, +0.4233, -0.1358, -0.3038, -0.0732, -0.2940, -0.0601, -0.0490, -0.0736, +0.2752, -0.2957, -0.4769, -0.3418, +0.1144, +0.3930, +0.0899, -0.3893, +0.5775, -0.0518, +0.1399, -0.7618, +0.4657, -0.3672, -0.0523, +0.3073, +0.5092, -0.4134, +0.1720, +0.1293, -0.2622, -0.0149, +0.2017, +0.0231, +0.0923, +0.0600, -0.0503, +0.0357, +0.0251, -0.0905, -0.2991, -0.2840, -0.3063, -0.0383, -0.3224, +0.0856, -0.3379, -0.3238, -0.3563, +0.0566, -0.2433, +0.5548, +0.2207, -0.3068, +0.1781, -0.0277, -0.1033, -0.2069, -0.0852, -0.2720, +0.2266, -0.4455, -0.4335, -0.1705, -0.5232, +0.3662, +0.1381, +0.0554, +0.1357, +0.0538, +0.2623, +0.1238, +0.3759, +0.3043, -0.1773, -0.0940, -0.2739, +0.1256, +0.1502, +0.1216, -0.0704, +0.2648, -0.8330, -0.4135, -0.1039, +0.2272, -0.2854, -0.0453, -0.0962, +0.2040, +0.0299, -0.1373, +0.0682, -0.1713, +0.0790, +0.3156, +0.2651, -0.0075, -0.5342, -0.1626, +0.1009, -0.6587, +0.0495, -0.1856, -0.0264, +0.2003, +0.0970, +0.5477],
-[ -0.0843, -0.1361, +0.1912, -0.0316, +0.2018, +0.2220, +0.0896, -0.1140, -0.3395, +0.1175, +0.0195, +0.1345, +0.7176, -0.0023, -0.0623, -0.4285, -0.2533, +0.1653, -0.1892, -0.2591, -0.0222, +0.4811, +0.3804, -0.6267, +0.0661, -0.2997, -0.1037, -0.2822, +0.2179, +0.5097, -0.4284, +0.0234, -0.6456, -0.6748, -0.3709, +0.2922, +0.0364, -0.0016, +0.2550, +0.1511, +0.8175, -0.3177, -0.1618, +0.4160, +0.3002, +0.3207, -0.0940, +0.5733, -0.3308, -0.3418, -0.1644, +0.8835, -0.2148, +0.5474, +0.7365, +0.1159, +0.1067, -0.1683, +0.1514, +0.2793, -0.4968, +0.0015, +0.1992, +0.3220, +0.2362, -0.0786, -0.0150, +0.5711, +0.3905, +0.0680, +0.0436, -0.3998, -0.0811, +0.1959, -0.0094, -0.1109, +0.1172, +0.1006, +0.3143, -0.6284, -0.4603, -0.3960, -0.2248, -0.2018, -0.5141, +0.2275, -0.0848, +0.2220, -0.0761, -0.1556, +0.3155, +0.1383, -0.3033, +0.0635, +0.3345, -0.1475, -0.4953, +0.1489, -0.1825, +0.1450, -0.0456, +0.5178, +0.0491, +0.1811, +0.3586, -0.0473, -0.4100, +0.2251, +0.1919, +0.4225, +0.2881, +0.6324, +0.4945, +0.1178, +0.0491, +0.2128, +0.2993, -0.3837, -0.1172, +0.0124, +0.0371, +0.2162, +0.2179, +0.1030, +0.0420, +0.0790, +0.2328, +0.0990, -0.2153, +0.2067, -0.4667, -0.0281, +0.6701, +0.0075, -0.0643, +0.3304, +0.3305, +0.0434, -0.0464, -0.5063, -0.0471, +0.0516, +0.5822, +0.1257, +0.0462, -0.3386, -0.2149, -0.2992, +0.0527, +0.0824, +0.2613, +0.0924, +0.4538, -0.0282, +0.2392, +0.2144, +0.7229, +0.0431, +0.1915, -0.0507, -0.0767, +0.1742, +0.1127, +0.0046, +0.1055, -0.1077, +0.1028, -0.1411, +0.0271, -0.2468, +0.0078, +0.8218, +0.2284, -0.0697, -0.4858, +0.1976, -0.0677, -0.1624, -0.5139, +0.2680, -0.1931, -0.1948, -0.0986, +0.2728, -0.0106, +0.3472, +0.1390, +0.0482, +0.2783, +0.1914, +0.3759, +0.7947, +0.1301, +0.2698, -0.2852, +0.1829, -0.1792, -0.1965, -0.2229, -0.0290, -0.2295, -0.0527, +0.3266, -0.6782, -0.0526, -0.6328, -0.3130, -0.1752, -0.6948, +0.1168, -0.0447, +0.3023, +0.3295, -0.1169, +0.3917, -0.0284, -0.2013, +0.1160, -0.4516, +0.2057, +0.1743, +0.2170, +0.0565, +0.0296, -0.5088, +0.3356, +0.4120, +0.0360, +0.3437, -0.0255, +0.2936, +0.4064, +0.2476, +0.2951, -0.2482, -0.0586, -0.1699, +0.2201, +0.3305, -0.4814, +0.1987, +0.4157, -0.4161, -0.0944, +0.2747, +0.3026, -0.0213, +0.1782, +0.0389, +0.1663, +0.0189, -0.2328, +0.0940, +0.1628, -0.1109, +0.0429],
-[ -0.0600, -0.1769, +0.3178, -0.1525, -0.0294, +0.1050, +0.1154, -0.2197, -0.2699, +0.2520, +0.1588, +0.0701, +0.0655, -0.1306, +0.0669, -0.1458, +0.0213, -0.1133, -0.1469, -0.1980, +0.0767, +0.4692, +0.2127, -0.0638, -0.0231, +0.1741, -0.2636, +0.1368, +0.0576, +0.0814, -0.1222, -0.0941, -0.2273, -0.3099, -0.5212, -0.1896, +0.0668, +0.2728, +0.1492, -0.0924, +0.3509, -0.1409, +0.0554, +0.2494, +0.2829, +0.1790, +0.0423, -0.1140, -0.4169, +0.0750, -0.2323, +0.2672, -0.2353, -0.0255, +0.4265, -0.4377, -0.2580, +0.2028, +0.3246, +0.3485, -0.2017, -0.5991, -0.3987, -0.2159, +0.0497, +0.3947, -0.1314, +0.0913, -0.1660, -0.2475, +0.2048, -0.0474, -0.1865, +0.3779, +0.0325, -0.1807, +0.1053, +0.0971, +0.0080, -0.2218, +0.0966, -0.3792, -0.2775, +0.3460, -0.1778, +0.2605, +0.1486, -0.1431, -0.0835, +0.2096, +0.1590, -0.2703, +0.2127, +0.1101, +0.1465, -0.0891, -0.3222, +0.0569, +0.1747, +0.2375, -0.2103, -0.0107, -0.1136, +0.0976, -0.1933, +0.0705, -0.1542, +0.3702, +0.2005, -0.3519, -0.5233, +0.1416, -0.1070, +0.1114, +0.2615, +0.2433, +0.5091, +0.0241, -0.2689, +0.0094, -0.2657, +0.2700, +0.2896, -0.2416, -0.1381, +0.0172, -0.0888, +0.2495, -0.1275, +0.1384, +0.2493, -0.1006, +0.1217, +0.1860, +0.1730, +0.0144, +0.2743, +0.0139, +0.1954, +0.0334, -0.5526, +0.1759, +0.2292, -0.1091, +0.0799, -0.1606, -0.0049, -0.5978, +0.2569, -0.0102, -0.2593, -0.3201, +0.4080, -0.2339, +0.1308, -0.4308, -0.2824, +0.0948, +0.7695, -0.4378, +0.1011, +0.3593, -0.1474, -0.0904, +0.2863, -0.1272, +0.2722, -0.1589, +0.3337, -0.3030, -0.2071, +0.1580, +0.0440, -0.0403, -0.0289, +0.1730, -0.4066, -0.3634, -0.2886, -0.1604, -0.4222, +0.2973, -0.3061, -0.4018, -0.1095, +0.1043, +0.4336, -0.2122, +0.3761, +0.3251, +0.3403, +0.2832, -0.3653, +0.1285, +0.0947, -0.1028, +0.0759, +0.0091, -0.1404, -0.3382, -0.0116, -0.0665, -0.0503, -0.1227, -0.5904, -0.3311, +0.0857, -0.0388, +0.2615, +0.0180, -0.0250, +0.0630, +0.1653, -0.0476, -0.0966, +0.2017, +0.0159, -0.1519, +0.1055, +0.2485, -0.3718, +0.0591, +0.1435, -0.2155, -0.2704, +0.1420, +0.0775, +0.2138, -0.1687, -0.0246, -0.2106, -0.1691, -0.5890, -0.3299, -0.1939, +0.1105, +0.2724, -0.1152, -0.1633, -0.1843, +0.0688, +0.1945, -0.0483, +0.2670, +0.2457, +0.3271, +0.2259, -0.0493, -0.2296, -0.2250, -0.1003, +0.0057, +0.0178, +0.0639, +0.2316, +0.2037],
-[ +0.0248, -0.2448, +0.2173, +0.0365, +0.4262, -0.4215, -0.6964, +0.3486, -0.1507, -0.2265, -0.0195, -0.3793, -0.1171, -0.6551, -0.5025, +0.2703, +0.0195, +0.7401, -0.2249, +0.1624, -0.3559, +0.1671, -0.3274, -0.0635, -0.0416, -0.3006, +0.1383, -0.7318, +0.1632, -0.4247, +0.4741, +0.0844, -0.0632, -0.4722, -0.5054, +0.4905, +0.5495, +0.6109, +0.0572, +0.3081, -0.0805, +0.6664, -0.2181, +0.4078, +0.0260, -0.2802, +0.3432, +0.0367, -0.1726, +0.1598, -0.1072, -0.3405, +0.3679, -0.1774, -0.1992, +0.3341, +0.2926, +0.3086, -0.1737, +0.0513, -0.0194, +0.2091, +0.1393, -0.0138, -0.2954, +0.5209, +0.0900, -0.0735, -0.3146, -0.1453, -0.1853, +0.0767, +0.0836, -0.1402, -0.2091, +0.0431, -0.7069, +0.4933, -0.0008, -0.3814, +0.2925, +0.1641, -0.4744, -0.1731, +0.2785, +0.1059, -0.0128, -0.3355, -0.5360, +0.0049, -0.2881, -0.3139, +0.3992, +0.6875, +0.0258, -0.1211, -0.1585, -0.0085, -0.4538, -0.3041, +0.3345, -0.3850, +0.3599, -0.1343, +0.2121, +0.0439, +0.1215, -0.1166, +0.4186, +0.1313, +0.4669, -0.1825, +0.0541, +0.0689, -0.6265, -0.1030, +0.1540, +0.1679, +0.3563, -0.0089, +0.2719, +0.0045, -0.3466, -0.3818, +0.1228, -0.3765, -0.2083, -0.5209, -0.3701, -0.5017, -0.1476, -0.0075, +0.4262, -0.0348, +0.4371, -0.2563, -0.0859, -0.0206, -0.2822, -0.2257, +0.2358, +0.1265, -0.1517, +0.4696, -0.1107, -0.5551, +0.2680, +0.1019, +0.2076, -0.0010, +0.2203, -0.6511, +0.3485, +0.0486, +0.3844, -0.3445, +0.4878, +0.2653, -0.0398, -0.0927, -0.3188, -0.2537, -0.3103, -0.3086, +0.0133, -0.1711, +0.2899, +0.3109, +0.1202, -0.2733, -0.5331, -0.1647, -0.0174, +0.6839, +0.0462, +0.3668, -0.4232, -0.2460, +0.1788, -0.2271, +0.1934, -0.4205, -0.2482, +0.1871, +0.1725, +0.0195, +0.1671, -0.0748, +0.1594, -0.4028, -0.5530, -0.1366, +0.0947, -0.5861, +0.1717, +0.4299, +0.1769, -0.1222, -0.1205, +0.9211, -0.1561, +0.3052, +0.1364, -0.0049, +0.3333, +0.0219, -0.2358, +0.0258, -0.4461, +0.0581, -0.0489, +0.0986, +0.1190, +0.1363, -0.3278, -0.2261, +0.4565, -0.1150, -0.1474, +0.2775, -0.3371, -0.3235, -0.0857, +0.0439, -0.3381, -0.0338, -0.0612, +0.3220, -0.1914, -0.1077, +0.2115, -0.3086, -0.0831, -0.0529, -0.4690, +0.3315, -0.3761, -0.1943, -0.2522, -0.4119, -0.6374, +0.1982, -0.5021, -0.1276, -0.2247, -0.4073, +0.1517, -0.2968, -0.1528, -0.0687, -0.0439, -0.3185, +0.4746, +0.1704, +0.7913, +0.8537],
-[ -0.0125, +0.0339, +0.0942, +0.1065, -0.2941, +0.1880, +0.4836, +0.3091, +0.0001, -0.3102, -0.0984, -0.0082, +0.1226, +0.1562, +0.0370, +0.2486, -0.1902, +0.0980, +0.0569, +0.2838, -0.5228, -0.0240, +0.2401, -0.1335, +0.4315, +0.1599, -0.2099, -0.2030, -0.2261, -0.2225, +0.2794, +0.2605, +0.2303, -0.2839, -0.0076, +0.2088, +0.0420, +0.3520, +0.1360, -0.3324, +0.0211, +0.2809, -0.0747, +0.0811, -0.1446, -0.1106, +0.2177, +0.4078, +0.2303, +0.3201, +0.0872, -0.4772, +0.0007, +0.3134, -0.0706, -0.1251, +0.2119, -0.4185, -0.4953, +0.1104, -0.2654, +0.1992, +0.2499, +0.0032, -0.0832, +0.1699, +0.0300, +0.1022, -0.4310, -0.1854, +0.2048, +0.0844, +0.1295, -0.0258, -0.1136, -0.1858, +0.0968, +0.0200, -0.2542, -0.3440, +0.5220, +0.4656, +0.2522, +0.1347, -0.1479, +0.2996, -0.2121, +0.1431, -0.1702, +0.2667, -0.1621, -0.0515, +0.4094, +0.1556, -0.3823, +0.0293, +0.1679, +0.3139, -0.0769, -0.0349, +0.1449, +0.0096, -0.0654, +0.0196, +0.3611, +0.5908, -0.2116, -0.0168, -0.2191, -0.0160, -0.0665, -0.2013, -0.2676, -0.0631, -0.3607, -0.0609, -0.2878, +0.5278, -0.1225, +0.3201, +0.3847, +0.0811, -0.0579, +0.0506, +0.1614, +0.1437, +0.0211, +0.2910, -0.2963, +0.1751, +0.4307, +0.0372, -0.2564, +0.3257, +0.0670, +0.2396, -0.0817, +0.1785, +0.1020, -0.1030, +0.3187, +0.0634, -0.3035, +0.1635, +0.2071, -0.0078, -0.0155, -0.1278, +0.1929, +0.2105, -0.2946, -0.3796, +0.2026, -0.3876, -0.0989, +0.3802, -0.3621, +0.1792, -0.2667, +0.3769, +0.1683, -0.0891, +0.2939, -0.3115, -0.1034, +0.2173, +0.0341, +0.0104, -0.3272, +0.2046, -0.3682, +0.1443, -0.4883, +0.1637, +0.0262, +0.5948, +0.3948, -0.2208, -0.1766, -0.1092, +0.0519, -0.1109, -0.4795, -0.1470, -0.0981, +0.0981, +0.2791, -0.0836, -0.4717, -0.3330, -0.3765, +0.1027, +0.1449, -0.4796, -0.1172, +0.3163, +0.2038, -0.0142, -0.4739, +0.0642, -0.0241, -0.4661, -0.2000, -0.4040, -0.1623, -0.1735, +0.2648, +0.2086, -0.0743, +0.1319, -0.0413, +0.3020, -0.0398, +0.1025, -0.1678, -0.0976, -0.2039, -0.0569, -0.0547, +0.1647, +0.0540, -0.1578, -0.6153, -0.2088, +0.0829, -0.1087, +0.0918, -0.0570, -0.0744, +0.2033, +0.1149, +0.1478, +0.0851, -0.0758, +0.1421, -0.2630, -0.2184, +0.0669, -0.0678, -0.4329, -0.3416, +0.1028, -0.2887, -0.5655, +0.1929, -0.3164, +0.3300, +0.1481, +0.4201, -0.4805, +0.0117, -0.1674, +0.3126, +0.1827, +0.1008, +0.0737],
-[ -0.1361, -0.0976, +0.2548, -0.0476, -0.4532, -0.6810, +0.2308, +0.6115, -0.2814, +0.2722, +0.2492, -0.0879, -0.3156, +0.1095, +0.4353, +0.5543, -0.4512, +0.3759, -0.1941, +0.2486, +0.2180, +0.1404, +0.0420, +0.0321, -0.0613, +0.3774, +0.0299, +0.0147, -0.5387, -0.1061, -0.0624, -0.0693, -0.4877, +0.0218, -0.0675, -0.1379, +0.5339, +0.2936, +0.3321, -0.0093, +0.4609, +0.0401, +0.1017, +0.0602, -0.2272, +0.2902, -0.1290, +0.0461, +0.1839, -0.4958, -0.4016, +0.0207, +0.0800, -0.0977, -0.1117, -0.3743, +0.2381, +0.0804, +0.0160, +0.2193, +0.0624, -0.2670, -0.2765, -0.1272, -0.2503, -0.0461, -0.0810, +0.1734, -0.5187, +0.0158, +0.0383, -0.0880, +0.2478, +0.3498, +0.3950, +0.0148, +0.1859, +0.2575, -0.0965, +0.0871, +0.5933, -0.5955, +0.0979, -0.6478, -0.2096, +0.0386, +0.4747, -0.4868, +0.0970, +0.0629, +0.1542, +0.0641, +0.0440, -0.1722, -0.0876, -0.0216, -0.4929, -0.0594, -0.1472, +0.1473, -0.2534, -0.1252, -0.2922, +0.3834, -0.0433, +0.1348, +0.2073, +0.6652, +0.1094, -0.2942, -0.3063, +0.0313, +0.0364, +0.1433, +0.3182, +0.1789, -0.0668, +0.4142, -0.1710, +0.3241, +0.1707, -0.5370, +0.0198, -0.4291, -0.2010, -0.0989, +0.0338, -0.0907, +0.4200, +0.1040, -0.1108, +0.3516, -0.2389, +0.1904, +0.1677, -0.4324, +0.0204, -0.2520, -0.3342, +0.3865, -0.5099, -0.3145, +0.2533, +0.2054, -0.0024, +0.3825, +0.0516, -0.2741, -0.0854, -0.1404, +0.3892, +0.0950, -0.5328, +0.0325, +0.4394, -0.2918, -0.2817, +0.0056, +0.3267, +0.0249, -0.4757, -0.1443, +0.2780, +0.0383, +0.1080, -0.1130, +0.0432, +0.2240, -0.3109, +0.2280, -0.1656, +0.3653, +0.1266, -0.0294, +0.2328, +0.0724, -0.1120, +0.0199, +0.6213, -0.0422, -0.0816, -0.1795, -0.1076, +0.1642, -0.1244, +0.3217, -0.3620, -0.1502, -0.5481, -0.6521, +0.1581, -0.5252, -0.0355, -0.1297, -0.0878, -0.0257, +0.0288, -0.0401, -0.3398, -0.3273, -0.0481, -0.4680, +0.0941, -0.1850, +0.5048, +0.2087, +0.1509, +0.0988, -0.2888, -0.5772, +0.3615, +0.3422, +0.1228, +0.1141, -0.1387, -0.2812, +0.0682, +0.4771, +0.3319, -0.0814, +0.0206, +0.5814, -0.0499, +0.0058, -0.4338, -0.1293, -0.2039, -0.1165, -0.1489, -0.4010, +0.3295, -0.4514, -0.1156, -0.3898, +0.1227, -0.0742, +0.1991, +0.3631, +0.0632, -0.5420, -0.0657, -0.2362, -0.0365, +0.0654, -0.0587, -0.7026, -0.0105, -0.0963, +0.0904, -0.2143, +0.0118, +0.4974, -0.6794, +0.2728, +0.1461, -0.4021],
-[ +0.2911, +0.0252, +0.0441, -0.1234, +0.1550, -0.2065, +0.1747, +0.1595, +0.1185, +0.1842, +0.1109, +0.2428, +0.0372, +0.0421, -0.0559, +0.4316, +0.1375, +0.1832, +0.2081, +0.0060, +0.3478, +0.0078, +0.4174, -0.2214, +0.2263, -0.1045, -0.1597, +0.0060, +0.1511, +0.0521, +0.0738, +0.0968, -0.1308, -0.0186, -0.3695, -0.2996, +0.3190, -0.2862, +0.1596, -0.4530, +0.2555, -0.0150, -0.3202, -0.0093, -0.0696, +0.4508, +0.2378, -0.2935, -0.0845, -0.2027, -0.3102, +0.0103, -0.1468, +0.6637, +0.1318, -0.3989, -0.1223, +0.2322, +0.2325, +0.1941, +0.2911, +0.1567, -0.0603, -0.2620, -0.2573, +0.0699, -0.0802, +0.1799, +0.0001, +0.0352, +0.0766, -0.1832, +0.1431, +0.2031, +0.2651, +0.0714, -0.2598, +0.0053, +0.1373, +0.1325, +0.1409, -0.2189, +0.0365, -0.1192, +0.2667, -0.0102, +0.1253, -0.0278, -0.0346, +0.1614, +0.0764, -0.1752, +0.3285, -0.1769, +0.0560, +0.3775, -0.2392, -0.0972, -0.2325, -0.2187, -0.0783, +0.2324, +0.1628, +0.0399, -0.0534, -0.1589, +0.0373, +0.2408, +0.0807, +0.1918, +0.1144, +0.2444, +0.3656, +0.1358, +0.2533, +0.3330, +0.2993, +0.0931, -0.0197, +0.2733, +0.2069, +0.2868, -0.1247, -0.2558, -0.2353, +0.2030, +0.2879, +0.1017, -0.2530, +0.0451, -0.4580, +0.2718, -0.4685, -0.0309, -0.1339, -0.1899, +0.1198, -0.3026, -0.0639, +0.1232, +0.0415, -0.2986, -0.2040, -0.0716, +0.1659, -0.1350, -0.1966, -0.2942, -0.2841, -0.3668, +0.9108, +0.1547, -0.2661, +0.0232, +0.1595, +0.2270, -0.3725, +0.0234, -0.1675, -0.2936, -0.1094, -0.0938, -0.0266, -0.1504, +0.0602, +0.4208, -0.1584, +0.4186, +0.0688, +0.1242, -0.1871, +0.6453, +0.0872, -0.2200, -0.1441, -0.1716, +0.1579, -0.4258, -0.1333, +0.1831, +0.2060, -0.2931, -0.3437, +0.1329, -0.3451, +0.2567, -0.0931, +0.3409, -0.0909, +0.1106, -0.1024, -0.1636, +0.1012, +0.2364, -0.0400, +0.3681, -0.2308, -0.0585, -0.1258, +0.1280, +0.0825, -0.2495, -0.2131, -0.0132, +0.2915, -0.0689, -0.1753, +0.0512, -0.1871, -0.0144, +0.0385, +0.1749, +0.1746, -0.1735, +0.1271, -0.1452, -0.1364, +0.3078, -0.1171, +0.1335, -0.0730, +0.1279, -0.1821, -0.1351, -0.0292, -0.1827, +0.0275, -0.1182, -0.1565, +0.0669, -0.1174, -0.4445, +0.3324, +0.0200, +0.4529, +0.2224, +0.0731, +0.1084, +0.0158, -0.3577, +0.0603, +0.0354, +0.0818, +0.3384, +0.1224, +0.0543, -0.0367, -0.0182, -0.0817, +0.0739, +0.3456, +0.2242, +0.1394, +0.1080, +0.4645, -0.0836],
-[ -0.0479, +0.1331, -0.0916, -0.0002, -0.1733, -0.1774, +0.4257, +0.1671, -0.2073, +0.2273, +0.3339, +0.0408, +0.1382, +0.0528, +0.0805, +0.3353, +0.0578, +0.0059, +0.0316, +0.1117, -0.1136, +0.3098, -0.0467, +0.3397, -0.2236, -0.0664, -0.2431, +0.4334, -0.3122, +0.5193, +0.0094, +0.0254, -0.1745, +0.2182, +0.0422, -0.0916, +0.0505, +0.3262, +0.1174, -0.3048, -0.1399, -0.0850, +0.1519, +0.3870, +0.0971, -0.0171, -0.0356, +0.1490, -0.4502, -0.1160, +0.0318, +0.0634, -0.0023, -0.0194, -0.2932, -0.0333, +0.3558, +0.3744, -0.2504, -0.0194, +0.0595, -0.0212, +0.2327, -0.1196, +0.1403, +0.4866, -0.2335, -0.1282, +0.1314, -0.3898, +0.0061, -0.1864, -0.2772, +0.0064, -0.1581, -0.0937, +0.0922, +0.0080, +0.2430, -0.1993, -0.3810, +0.0056, -0.2256, +0.1696, +0.0573, +0.1619, +0.1918, -0.1466, -0.0888, -0.1172, +0.1264, -0.1207, -0.0221, +0.1458, -0.1771, +0.1786, +0.0579, +0.2019, -0.2409, +0.1583, +0.1189, +0.4001, -0.5152, +0.4519, -0.0767, +0.1069, +0.0321, +0.2578, -0.0971, -0.1077, -0.0422, -0.1098, +0.1311, -0.0872, -0.1170, +0.1748, -0.3340, -0.5122, +0.0460, +0.0176, +0.1353, -0.0354, +0.1726, +0.1428, +0.2590, +0.5661, +0.3093, -0.0381, +0.3977, +0.1259, +0.5698, +0.4974, -0.0609, -0.0936, -0.4606, +0.0318, -0.5266, -0.0934, -0.3129, +0.0124, -0.3269, -0.1724, -0.4367, -0.2131, +0.1322, +0.1437, -0.0196, +0.0439, +0.0736, -0.3361, +0.2174, +0.4335, -0.2091, +0.1897, +0.3060, -0.0883, +0.2073, -0.1840, -0.1963, -0.1535, -0.2841, +0.1253, +0.1264, -0.1940, -0.2254, +0.1820, -0.1039, -0.0036, +0.3465, +0.0028, +0.1394, +0.1971, +0.2045, -0.0696, -0.1166, +0.1119, +0.1891, -0.1620, +0.0795, -0.1819, -0.3050, +0.2498, -0.0021, +0.2290, -0.5197, +0.2111, -0.0612, +0.0092, -0.2305, -0.3659, +0.0075, +0.3581, +0.0471, +0.1735, +0.1062, -0.0882, -0.1167, -0.0042, +0.4123, -0.0168, +0.0636, +0.2696, +0.5927, -0.2619, -0.1943, -0.0427, +0.0867, +0.0194, +0.0851, +0.0975, -0.0781, -0.1522, -0.3116, +0.1528, -0.1430, +0.1754, -0.1765, +0.4800, -0.0084, -0.0873, -0.1647, +0.1148, +0.2186, +0.0590, -0.0251, -0.1672, -0.0842, +0.0781, +0.0659, +0.2357, +0.1831, +0.0591, +0.1442, +0.1315, +0.0251, -0.2479, -0.0610, -0.0266, +0.1820, -0.3100, -0.2956, +0.2264, -0.3252, -0.0502, +0.0081, +0.0171, -0.0082, -0.1259, -0.1426, -0.0384, -0.1705, +0.2844, -0.0812, +0.4512, +0.1431, -0.2101],
-[ +0.3975, +0.0603, +0.2624, +0.4018, +0.1623, -0.0238, +0.1034, +0.2576, +0.0364, -0.3271, -0.4375, +0.2982, -0.6016, +0.1980, +0.0986, +0.6358, +0.6067, -0.3525, +0.1575, +0.0705, -0.0740, +0.1200, +0.1813, +0.0418, -0.1777, -0.5141, -0.3394, +0.1700, -0.3651, -0.3544, -0.0387, +0.1712, -0.1980, +0.1041, +0.0161, +0.6207, +0.1048, +0.1848, +0.0753, +0.2312, -0.3344, +0.1452, +0.2946, +0.3253, +0.0775, +0.1658, -0.4919, -0.2192, -0.0671, -0.1306, -0.1427, -0.2229, +0.1491, +0.1053, -0.0729, -0.2558, -0.3453, +0.2334, +0.1523, +0.4557, +0.1303, -0.1611, +0.1525, -0.3323, +0.0807, -0.0636, -0.0087, +0.0266, +0.1338, +0.1611, -0.3803, -0.0139, +0.2500, +0.1019, +0.6161, -0.1879, -0.2951, -0.2619, +0.0861, -0.0798, -0.6109, -0.6078, +0.2102, -0.0896, +0.5327, +0.0187, +0.5059, -0.0105, +0.1004, +0.2203, +0.0590, -0.0620, +0.3079, +0.0536, -0.1042, +0.7077, -0.1788, -0.0468, -0.3501, +0.2258, -0.0149, +0.4304, +0.0227, -0.2189, -0.3309, -0.2264, +0.1553, +0.0774, +0.0090, +0.2321, -0.3405, +0.1789, +0.0719, +0.0029, -0.0421, +0.1266, -0.1958, +0.3099, -0.1819, +0.1510, +0.0047, +0.3718, -0.1612, +0.0734, +0.4715, +0.6387, +0.4123, -0.1210, +0.0085, -0.2726, +0.2627, +0.2969, +0.2179, +0.2094, +0.1807, +0.3879, -0.5351, -0.5429, -0.5244, -0.1714, +0.3948, -0.0217, +0.5449, -0.3176, +0.4858, +0.1822, -0.1967, -0.1345, -0.0321, -0.2816, -0.0004, -0.0433, -0.3497, -0.3879, +0.1900, -0.1076, -0.1775, -0.6605, -0.4304, -0.1296, -0.3042, +0.3626, -0.1161, -0.1033, +0.1811, +0.0216, -0.0146, -0.0116, -0.0426, -0.1701, +0.0427, +0.3073, -0.1439, +0.2131, -0.2708, -0.0942, -0.0583, -0.3204, -0.0184, -0.1194, +0.1047, +0.0952, -0.0431, +0.1094, -0.0274, -0.3901, -0.2028, +0.1787, -0.1761, -0.1447, +0.3204, +0.0693, -0.6784, -0.1707, -0.1779, -0.2513, -0.1666, -0.1050, +0.0455, +0.0593, -0.0933, -0.3976, -0.1421, -0.2670, +0.6564, -0.2088, -0.2548, +0.4063, -0.4954, +0.1265, +0.0968, -0.0323, -0.0741, -0.0125, -0.0264, +0.1841, -0.0046, -0.2472, +0.0703, -0.1902, -0.3295, -0.0920, +0.2232, -0.3756, -0.0381, -0.6690, -0.2531, -0.0335, -0.2410, +0.0129, -0.2026, -0.0618, -0.1672, -0.0934, -0.2651, -0.1886, +0.3258, +0.2041, +0.1016, -0.1330, -0.2496, -0.3590, +0.1134, +0.2793, -0.1895, +0.0942, -0.0140, +0.1660, -0.0332, -0.1366, +0.0506, +0.2313, -0.3251, +0.2350, +0.1984, -0.3045],
-[ -0.1244, +0.0467, -0.2788, +0.4575, -0.0748, -0.4002, +0.8065, -0.4954, +0.4621, -0.0297, +0.1578, +0.5572, -0.4810, -0.3364, +0.1981, -0.4577, -0.5189, -0.2748, -0.3190, -0.1295, -0.2100, -0.3129, +0.0677, -0.3496, +0.2366, -0.4851, +0.1440, -0.3993, -0.3010, +0.1903, -0.0104, +0.2706, +0.0560, +0.1651, -0.3059, +0.1723, -0.0381, +0.0744, +0.3331, +0.0662, +0.2514, -0.1483, -0.1333, -0.2432, -0.1971, -0.2435, -0.4451, +0.0307, +0.2830, +0.1034, +0.4785, -0.0338, +0.4945, -0.2218, -0.4259, +0.1723, -0.3336, -0.1547, -0.5019, +0.7082, -0.5717, +0.4096, -0.6571, +0.0823, -0.0680, -0.1518, +0.1608, +0.4834, -0.2698, -0.4448, -0.1332, -0.1917, +0.0868, -0.1208, +0.5762, -0.2558, +0.1775, +0.0565, -0.0321, -0.5963, -0.2200, +0.6051, -0.6825, +0.0358, +0.1749, +0.6319, -0.8650, -0.2608, -0.0685, +0.2391, -0.0369, -0.0770, -0.4179, -0.0079, +0.2566, +0.3069, -0.1205, -0.0178, -0.6410, +0.1569, -0.3519, -0.2583, -0.3258, -0.7489, -0.2438, -0.3257, -0.3815, -0.9372, +0.0860, +0.2511, -0.3017, +0.0428, -0.2221, +0.3140, +0.2347, -0.1383, +0.0511, -0.6644, -0.5659, -0.4956, +0.1200, +0.0444, +0.1911, +0.0424, -0.0573, +0.2888, -0.0837, -0.4370, -0.1554, +0.2436, -0.3111, -0.1141, +0.0500, +0.4466, -0.1981, -0.4976, -0.2438, +0.3547, -0.3850, -0.4817, +0.3871, +0.2476, -0.0043, -0.3596, -0.5270, +0.3349, -0.0573, -0.2888, +0.3322, -0.5017, +0.1827, -0.0712, +0.2914, +0.5111, -0.2119, +0.2552, -0.1014, -0.0706, -0.3091, -0.4019, +0.3362, -0.4000, -0.4460, -0.0660, -0.0115, -0.0576, -0.1440, +0.1168, -0.2178, -0.2009, -0.2137, +0.2927, +0.2332, -0.6983, -0.2708, +0.2801, -0.3586, -0.0667, +0.0526, -0.2045, -0.1303, -0.5292, +0.4341, +0.1684, +0.4273, +0.0900, -0.4618, -0.0819, -0.0289, -0.4542, +0.0024, +0.2126, -0.2633, +0.0579, +0.0425, -0.0113, +0.0473, -0.6465, +0.0824, -0.0409, +0.1870, -0.3765, -0.2056, -0.2201, -0.3408, +0.1940, -0.0177, +0.0060, +0.3177, -0.2964, +0.1934, +0.6009, -0.3270, -0.0354, -0.2978, +0.0542, +0.0680, +0.0100, +0.1105, -0.0325, -0.2642, +0.0597, -0.4088, +0.0358, +0.3133, +0.3854, -0.0946, -0.0004, -0.0382, -0.3050, -0.2804, -0.4568, -0.0950, -0.4881, +0.0035, +0.0202, -0.1340, -0.1794, +0.6133, +0.2774, +0.0348, +0.0286, -0.4590, +0.1485, -0.7287, +0.4565, -0.1745, -0.3535, -0.4678, +0.3834, -0.6188, -0.7744, +0.3191, -0.0715, +0.1052, -0.0231],
-[ +0.0580, -0.3371, +0.3239, +0.3150, -0.3001, +0.1801, -0.0312, -0.5783, -0.0172, -0.2807, +0.0673, +0.4073, +0.2058, -0.0427, +0.3201, -0.2968, +0.0349, -0.0799, -0.0138, -0.1815, -0.0677, +0.0024, +0.2618, -0.0787, +0.3508, -0.4335, -0.5828, -0.2823, -0.1908, -0.1853, +0.1219, +0.0701, -0.2294, +0.2899, -0.1157, +0.1798, +0.3162, +0.0430, +0.5583, +0.1997, +0.1252, +0.0226, +0.0324, -0.4922, -0.0369, -0.0692, -0.4051, -0.1870, +0.0089, +0.3477, -0.0689, +0.1811, +0.2633, -0.2877, -0.1416, +0.1487, +0.2070, +0.5753, +0.2179, +0.3493, -0.0858, -0.1485, +0.1173, -0.2726, +0.0917, +0.2187, +0.2546, -0.0227, -0.0932, -0.4266, -0.0505, -0.1081, -0.0286, -0.1489, +0.1425, -0.2813, +0.5944, +0.0710, -0.2507, -0.3329, +0.3650, +0.1446, -0.2549, +0.4105, +0.0349, +0.3155, -0.0624, +0.5752, -0.1162, +0.0195, -0.1993, +0.0881, +0.0697, +0.4865, +0.2223, +0.0368, +0.1157, +0.1420, +0.4291, +0.1668, +0.0772, +0.1248, -0.1832, +0.3463, +0.2325, -0.1066, -0.0909, -0.1951, +0.1902, +0.3861, -0.0333, -0.0321, -0.3942, +0.0205, +0.0115, +0.3744, -0.3810, -0.2990, -0.1335, -0.2115, -0.1880, +0.6321, +0.1321, -0.2987, -0.0758, +0.1898, -0.4732, +0.5376, -0.0909, +0.0027, +0.3838, +0.3588, -0.0469, +0.1783, +0.1699, +0.1422, -0.0621, -0.3444, -0.4191, -0.3353, +0.1657, +0.2193, +0.1733, -0.1795, -0.1521, +0.2495, +0.0659, -0.2625, -0.0148, -0.1001, -0.0658, +0.1761, +0.3362, -0.1943, -0.6844, +0.0543, -0.1504, -0.0522, +0.4026, -0.0019, +0.2111, +0.0205, +0.0599, +0.0294, -0.2959, +0.3209, +0.0298, +0.2731, +0.1676, +0.1578, -0.1474, +0.0302, +0.1557, -0.1848, -0.3529, +0.3117, -0.4560, -0.1120, +0.1324, -0.1800, +0.1793, -0.2910, -0.1240, -0.1297, +0.2881, +0.0235, -0.1947, -0.4855, -0.0345, -0.3622, -0.2499, +0.0088, -0.1905, +0.0603, +0.1892, -0.0315, +0.0295, -0.2410, +0.0864, +0.0888, -0.0964, +0.1514, +0.0060, -0.0862, -0.4172, +0.0968, +0.3526, -0.2188, +0.0880, -0.1246, +0.2900, -0.1955, +0.2456, -0.2717, -0.3450, +0.2010, -0.0474, -0.4630, +0.1374, +0.1800, -0.1061, +0.2078, -0.2144, +0.0447, -0.0025, -0.0561, +0.4208, +0.2254, -0.0628, +0.2521, -0.2476, +0.0794, +0.2266, -0.2359, +0.2156, +0.2297, +0.3097, +0.2366, -0.0859, -0.2971, -0.2814, +0.2527, -0.1882, +0.1252, -0.1642, +0.1704, +0.4092, -0.0192, +0.2157, -0.2505, -0.3426, -0.3608, +0.2457, +0.1501, -0.1108, -0.2853],
-[ +0.7381, -0.2475, -0.0494, -0.8059, -0.3116, +0.1576, +0.1347, -0.0784, +0.0452, -0.2930, -0.1851, -0.6253, +0.0669, -0.6952, -0.1905, +0.1123, +0.0303, +0.0440, +0.0817, +0.2308, -0.0063, +1.0707, -0.2214, +0.0562, -0.0705, +0.1031, +0.1280, +0.0245, +0.1798, +0.0761, +0.0530, +0.6943, -0.0402, -0.2658, +0.7095, -0.0842, +0.1608, -0.4585, +0.4220, -0.1964, +0.5404, +0.1161, +0.0050, +0.4415, +0.5303, +0.0945, +0.0919, +0.6751, -0.1676, +0.5655, -0.0321, -0.3334, -0.0581, +0.1706, -0.2093, -0.1301, +0.2631, -0.4652, +0.0640, +0.3510, -0.2780, +0.3195, +0.4595, -0.2393, -0.6972, -0.0133, -0.1362, -0.1866, +0.1914, -0.2980, +0.6745, +0.1496, +0.0493, +0.0787, +0.3799, -0.4630, -0.8067, -0.0254, -0.0671, +0.4575, -0.2982, -0.3343, -0.0386, -0.5071, -0.1302, -0.0116, +0.1203, +0.1037, +0.0925, +0.3226, -0.4569, +0.5480, +0.3634, +0.4034, -0.0447, -0.2874, -0.3197, +0.1841, +0.0943, +0.2061, -0.0682, -0.1927, -0.3331, +0.5746, +0.5211, +0.1638, -0.7889, -0.1275, +0.4053, +0.3205, +0.3071, -0.3261, +0.4975, +0.3669, +0.2436, +0.0290, +0.0485, +0.0254, -0.9289, -0.0045, -0.1394, +0.3343, -0.5084, -0.3056, +0.0270, -0.0177, -0.4645, -0.4447, +0.2515, -0.1789, -0.0150, +0.1901, -0.3010, +0.2151, +0.0271, +0.3128, -0.4510, +0.1436, +0.1326, -0.5074, -0.1928, -0.2072, -0.0506, +0.0585, +0.2597, +0.0557, +0.1554, +0.0637, +0.1753, +0.1603, -0.0491, +0.0947, -0.0947, -0.0386, +0.0485, +0.1325, +0.3477, +0.0992, -0.3166, +0.2578, -0.3771, -0.6604, +0.3837, +0.4531, -0.1933, +0.0080, +0.2843, -0.1099, -0.2604, +0.1090, -0.2726, -0.0214, +0.1486, +0.6095, +0.0327, +0.2487, -0.2636, -0.0398, -0.0023, -0.2461, +0.4543, +0.3383, +0.0459, +0.3432, +0.3111, -0.0287, -0.3101, -0.1319, +0.0269, +0.0879, +0.1646, -0.3670, -0.0204, -0.1816, +0.3627, +0.3105, -0.1901, -0.8469, -0.1429, -0.0095, +0.7778, -0.0932, -0.0653, -0.2607, -0.2949, +0.2495, -0.1045, -0.6736, -0.0541, -0.6866, +0.1623, +0.4817, -0.3854, -0.1670, -0.4186, -0.2369, +0.1780, -0.5476, +0.2418, +0.0207, +0.1405, -0.3712, -0.2743, +0.0896, +0.3807, +0.7793, +0.1667, +0.0631, -0.2508, +0.6040, -0.1580, -0.2618, +0.2751, +0.2168, +0.3795, -0.2427, -0.4092, +0.2154, -0.8448, +0.3266, +0.5106, -0.6358, -0.2464, -0.4913, -0.4326, -0.4836, -0.7830, +0.5032, +0.1403, +0.1921, -0.4615, +0.3502, +0.5148, +0.0262, -0.0378, +0.0218],
-[ -0.0206, +0.0659, -0.2565, -0.1178, -0.0108, -0.5836, +0.2226, -0.0939, -0.0271, +0.2265, +0.0943, -0.1793, +0.1053, -0.1203, -0.0704, +0.2342, +0.1546, +0.4810, -0.1052, +0.1559, -0.0555, +0.2432, +0.2105, -0.3110, +0.0955, +0.1117, +0.3404, +0.0115, -0.2706, +0.1904, +0.3692, +0.2379, +0.1437, +0.0253, +0.3716, +0.1286, +0.2525, -0.2104, +0.2484, -0.3496, +0.1212, -0.2015, -0.1019, +0.2766, +0.2695, +0.1454, -0.5423, +0.2566, -0.0013, +0.1011, -0.1921, -0.0071, -0.0599, +0.2944, -0.2065, +0.1577, -0.0255, +0.2411, +0.0634, -0.0065, -0.1555, -0.1093, +0.3201, +0.1953, +0.0549, +0.0787, -0.0385, -0.3140, +0.2594, -0.0827, +0.3342, +0.0012, -0.0240, +0.1015, +0.0216, +0.0185, -0.1822, +0.2033, -0.0328, -0.1944, -0.2264, +0.0489, +0.2461, +0.1915, +0.1118, -0.2512, +0.3018, -0.0487, -0.2431, -0.0076, -0.0899, -0.1716, +0.2301, +0.1369, -0.3787, -0.1428, -0.0987, -0.2805, -0.1682, +0.4088, -0.0173, +0.2908, -0.2743, +0.0587, +0.4514, -0.0456, -0.4386, +0.3342, +0.0661, +0.0353, +0.4922, -0.7322, +0.3238, -0.2757, -0.0458, -0.0987, +0.0529, -0.1216, -0.2411, +0.1616, -0.0720, +0.5098, -0.1742, -0.2574, +0.0332, -0.0881, -0.2096, +0.0546, +0.1921, -0.3496, +0.2334, -0.4729, +0.1516, -0.0504, +0.1546, +0.1410, -0.1773, +0.5221, -0.3395, -0.3449, +0.3083, +0.0403, -0.1190, -0.0325, +0.2385, +0.0123, +0.2955, -0.1028, -0.0572, -0.0628, -0.3075, -0.0982, -0.1004, +0.3240, -0.0951, +0.5076, -0.1176, +0.3036, -0.0862, +0.1839, -0.3230, -0.5516, +0.1847, -0.0974, -0.3160, +0.5997, -0.2010, -0.1829, +0.0963, +0.3688, -0.1199, +0.2221, +0.2468, +0.1372, +0.1562, +0.4491, +0.0962, -0.1357, -0.1821, -0.1760, +0.2399, -0.4287, +0.1030, -0.1147, +0.3199, -0.0476, -0.3862, -0.3519, +0.4984, -0.1864, +0.0967, +0.0678, -0.0255, +0.0495, -0.0430, +0.3054, +0.2907, -0.4478, +0.1105, -0.1157, +0.2442, -0.3512, +0.0636, -0.2319, +0.0601, +0.3072, -0.2897, -0.4553, +0.0210, +0.0958, -0.4464, +0.4383, +0.2507, +0.1024, -0.0568, -0.3112, -0.2059, -0.4570, +0.2250, -0.2215, +0.1468, +0.1813, -0.2931, +0.1007, -0.0960, +0.2029, +0.4445, -0.0166, -0.1324, -0.0913, +0.1978, -0.2619, +0.0271, +0.2970, -0.0730, +0.0342, -0.1097, +0.0822, -0.1587, +0.0859, +0.2537, -0.0574, -0.0527, -0.5641, -0.1083, -0.0059, -0.1982, +0.1345, +0.0167, +0.0796, +0.2063, -0.1226, +0.2049, +0.0640, +0.1948, +0.2156],
-[ +0.5519, +0.0513, -0.2814, -0.1081, +0.4918, +0.3216, +0.0762, +0.0575, -0.2296, +0.1430, -0.0473, -0.2251, +0.3829, -0.5347, +0.4668, -0.6335, +0.2985, -0.0935, +0.4089, -0.2893, -0.3299, -0.3789, -0.3584, +0.0124, -0.0628, -0.1894, -0.5388, +0.0133, +0.0361, -0.2352, -0.0468, -0.6312, +0.4365, -0.1059, +0.0632, -0.4930, -0.2637, +0.3447, -0.1379, +0.5067, +0.0147, +0.2901, -0.1365, -0.0063, -0.2201, -0.4227, -0.0173, -0.2490, +0.3692, +0.0920, +0.4893, +0.5749, -0.1984, +0.3157, +0.0180, -0.0667, +0.0169, -0.0173, -0.1439, -0.1318, +0.3033, -0.0239, -0.1698, +0.0777, -0.3522, -0.1974, -0.0287, -0.0749, +0.2130, -0.2972, +0.3312, -0.0111, +0.3668, -0.2288, +0.1613, -0.1882, +0.1315, -0.1463, +0.5001, -0.0885, +0.3079, -0.4730, +0.0129, -0.4098, -0.2915, -0.1633, +0.4581, +0.3639, +0.0429, +0.0489, -0.5022, -0.2359, -0.7827, -0.4324, -0.0656, +0.2880, +0.2235, +0.3295, -0.4484, -0.0991, +0.3212, +0.2464, -0.2285, -0.0386, -0.0746, +0.2591, -0.0314, -0.1551, +0.0027, +0.0949, -0.1944, +0.3021, +0.0144, +0.2922, +0.4638, -0.6117, +0.2648, +0.4724, +0.4701, -0.4681, +0.2530, +0.1654, +0.1597, -0.5759, +0.3194, +0.3979, -0.2799, -0.1007, -0.1350, +0.2451, -0.3349, +0.4901, -0.4146, -0.0482, -0.2564, -0.3343, +0.1317, -0.2191, +0.1227, +0.1225, +0.2376, +0.0775, +0.4042, +0.2867, -0.0208, +0.0251, +0.0629, +0.2248, +0.3367, -0.4687, +0.6583, -0.2974, -0.3763, -0.3273, -0.2385, +0.3309, +0.0276, +0.2650, +0.1817, -0.1479, +0.0767, +0.0040, +0.0864, +0.0370, -0.3777, +0.0365, -0.2231, +0.1891, -0.7009, -0.0407, +0.2263, -0.2734, -0.2038, -0.3759, +0.1326, -0.0957, -0.0955, -0.3577, +0.2432, -0.3343, -0.0818, +0.4028, +0.2523, -0.2782, -0.2638, +0.5693, -0.0417, -0.1251, +0.3552, -0.2030, +0.3901, +0.6543, -0.0449, +0.1659, -0.5343, +0.1039, -0.2405, -0.1986, +0.3727, +0.0126, -0.0750, -0.1492, -0.1449, +0.5876, +0.1234, -0.5702, +0.1546, +0.2700, +0.3258, +0.4746, -0.0436, +0.2323, -0.2355, -0.4237, +0.1582, +0.2140, +0.5732, +0.3075, -0.3210, +0.3381, +0.3614, -0.0347, +0.4458, -0.0468, -0.0211, -0.6787, -0.2945, -0.5741, -0.0622, +0.5319, +0.3267, +0.0316, +0.1697, -0.0413, +0.1485, -0.0395, -0.2128, +0.2895, -0.3552, -0.1553, -0.3712, +0.1985, +0.5970, +0.4085, +0.0845, +0.0485, +0.5842, +0.0358, -0.3295, +0.0578, -0.0269, -0.3693, -0.3669, +0.1904, +0.2907, +0.1336],
-[ -0.0663, -0.3474, +0.2937, -0.3453, +0.5875, +0.0839, +0.2786, -0.4704, -0.0538, +0.4598, -0.2641, +0.2168, +0.2352, -0.0699, -0.1660, +0.0367, +0.3793, +0.1119, +0.2799, -0.0936, -0.2325, +0.1220, +0.3516, +0.3244, -0.0093, +0.3741, -0.0405, +0.1817, +0.1862, -0.1718, +0.3106, -0.0407, +0.0567, +0.2398, -0.3312, +0.0257, -0.3013, +0.0906, -0.0941, +0.1860, -0.0730, +0.2885, -0.2410, -0.2040, -0.3055, -0.1838, +0.7850, -0.1954, -0.1275, +0.0687, +0.3292, +0.3618, -0.0271, +0.2285, +0.0405, +0.0039, +0.3536, -0.0453, +0.0397, +0.2821, +0.5155, -0.3573, -0.3295, +0.1070, -0.1557, -0.0199, +0.2729, -0.1590, -0.1519, +0.2035, -0.0600, -0.1351, -0.2425, -0.2450, +0.2618, +0.1039, -0.0239, +0.0207, -0.0275, +0.1956, +0.1542, -0.1087, -0.1858, -0.1258, -0.2261, +0.1710, -0.0095, +0.2291, +0.1807, -0.0717, -0.2777, -0.4251, -0.2181, -0.2523, +0.0932, -0.3342, +0.2693, -0.0931, -0.3272, +0.3386, -0.1731, +0.0882, -0.0388, +0.3526, +0.1001, -0.0724, +0.0580, +0.1069, -0.0739, -0.0173, -0.1927, -0.0398, -0.1471, +0.2138, +0.2972, -0.0540, -0.0702, +0.3311, +0.3107, -0.4498, -0.0410, -0.1421, +0.2008, -0.3581, -0.0654, +0.3527, -0.3508, +0.5676, +0.3380, +0.2792, +0.3364, -0.1180, -0.0956, -0.0945, +0.3532, -0.2808, +0.1156, -0.3018, -0.1284, +0.1322, -0.2177, -0.3536, -0.1163, +0.1442, +0.0544, -0.0520, -0.0935, -0.0389, +0.2355, -0.1508, +0.0334, +0.1625, -0.0570, +0.0922, -0.2637, +0.0786, -0.1576, -0.3297, +0.4285, -0.2155, +0.2264, -0.2432, -0.1515, -0.2511, -0.4285, +0.0903, +0.3151, +0.1654, -0.0998, -0.1048, +0.1084, -0.2451, -0.3192, -0.2839, +0.1695, +0.0071, +0.1145, -0.4226, +0.2563, +0.1695, +0.1237, +0.2135, +0.1209, +0.2015, -0.0175, +0.0028, +0.2071, +0.1469, -0.1188, -0.2060, -0.2925, -0.0588, +0.0473, +0.2574, -0.1653, +0.0977, -0.4298, -0.2020, -0.2299, +0.1185, +0.3264, -0.0511, -0.0698, +0.1839, +0.1456, -0.1438, -0.1972, -0.0161, +0.2833, -0.2013, -0.0045, -0.0018, -0.0231, -0.1224, +0.0642, +0.3147, +0.1657, +0.2248, -0.0007, +0.0951, -0.1961, +0.1023, +0.1240, +0.1744, +0.0264, -0.1413, +0.0181, -0.2669, -0.4848, +0.0801, +0.3102, +0.1198, +0.2436, +0.1273, +0.4990, -0.0604, +0.0977, +0.0166, +0.1470, -0.1536, -0.2691, -0.1054, +0.1312, +0.4211, +0.0988, +0.2298, +0.2502, -0.2912, -0.1419, +0.2418, +0.2973, -0.2015, -0.1817, -0.0262, -0.1974, -0.0795],
-[ -0.2097, +0.1729, +0.1217, +0.1132, -0.0596, -0.2502, +0.2017, +0.1972, -0.0804, +0.2506, +0.4203, +0.0047, +0.2293, +0.3884, +0.0636, +0.1996, +0.0480, +0.0913, -0.0187, -0.4314, -0.0188, -0.0248, -0.0407, -0.1030, -0.0792, -0.0918, +0.3159, +0.0902, -0.1493, +0.2896, -0.0594, -0.1055, -0.0553, +0.4742, -0.0574, +0.0155, -0.0710, -0.1234, +0.3404, +0.0636, -0.2277, -0.0430, +0.1607, +0.1531, +0.0073, -0.0407, +0.2017, +0.3172, -0.5818, +0.3355, +0.0280, -0.0795, -0.2449, -0.1919, +0.3268, +0.1312, -0.1493, -0.0656, -0.1482, -0.1045, -0.2848, +0.3498, +0.3616, -0.4391, +0.0634, +0.2900, -0.4208, -0.2300, -0.1560, -0.2766, -0.1878, -0.0083, -0.0358, -0.2226, +0.3990, +0.0566, +0.4359, -0.0416, -0.1255, -0.0053, -0.1905, -0.1912, -0.1385, +0.0038, +0.1298, -0.1782, -0.3861, +0.0321, +0.1969, +0.2704, -0.1199, +0.1919, -0.1319, -0.0604, -0.0543, -0.0601, -0.1589, +0.2349, -0.1380, -0.2177, +0.0393, +0.1172, +0.2216, +0.3722, -0.1225, +0.1798, +0.0511, +0.1885, +0.3714, -0.2291, -0.0178, +0.2587, +0.1974, -0.2691, -0.2672, -0.0804, -0.2566, +0.1140, +0.0702, -0.1479, -0.0766, +0.1301, -0.1145, +0.2643, +0.2521, +0.5178, +0.0466, -0.1019, +0.0245, -0.0204, -0.1585, -0.2132, +0.2078, -0.0992, +0.1706, -0.0786, -0.1297, -0.1287, +0.4405, +0.1151, +0.0983, -0.0388, +0.2761, -0.0276, -0.0164, -0.0871, +0.1687, +0.0014, +0.0995, -0.0913, +0.3643, -0.4339, +0.0070, -0.1230, +0.3374, +0.2993, +0.0263, -0.0087, +0.3070, -0.0454, -0.1270, +0.4292, -0.1709, +0.2164, -0.1621, -0.5785, -0.1937, -0.3957, +0.3361, -0.1170, +0.1993, +0.1888, -0.1823, -0.2302, -0.0885, +0.2479, -0.0229, -0.3401, -0.3067, +0.1078, -0.2817, -0.2539, -0.1013, +0.5285, -0.3843, +0.0568, -0.3106, +0.0533, +0.3640, -0.0927, -0.5513, -0.0362, +0.0053, +0.1241, +0.1022, -0.1230, +0.1791, -0.0647, +0.1766, -0.0644, -0.2788, +0.2589, -0.0948, -0.1154, +0.0718, -0.3298, +0.1239, +0.3155, +0.2845, -0.1631, +0.1506, +0.0343, +0.3193, +0.3269, -0.4261, +0.0917, -0.1276, +0.6166, +0.1516, -0.0073, +0.1164, -0.1068, +0.1024, -0.0546, +0.0823, +0.1792, -0.4155, +0.1751, +0.2966, -0.3977, -0.1986, -0.3103, +0.0695, +0.0647, -0.1709, +0.1093, +0.2011, -0.5787, +0.0172, -0.0608, +0.3439, -0.0277, +0.2463, -0.1530, -0.2043, +0.2256, +0.1863, +0.2290, +0.0408, +0.0741, -0.2031, +0.3496, -0.0224, +0.3403, -0.0695, +0.1074],
-[ -0.0003, -0.3044, +0.4460, +0.1808, +0.0575, +0.3863, +0.3343, -0.0873, +0.0772, +0.0417, -0.2723, +0.2732, +0.2943, -0.0961, +0.2566, +0.0375, +0.0300, +0.5390, +0.2300, +0.2941, -0.3558, +0.1914, +0.0620, -0.0483, -0.2449, -0.1154, -0.1646, +0.6449, -0.1792, +0.1099, +0.1142, -0.0761, +0.1167, +0.0152, +0.3108, +0.5886, +0.2649, +0.1822, -0.3308, +0.0202, -0.3642, -0.2656, +0.6961, +0.1750, +0.0493, -0.2683, -0.2037, -0.3239, -0.3731, +0.1197, +0.2602, -0.5951, +0.0618, -0.2428, +0.0832, +0.3814, -0.3129, +0.1019, -0.0127, -0.0651, -0.1155, -0.0557, +0.1840, +0.0163, +0.0133, -0.6342, -0.3788, -0.2772, +0.0301, -0.1676, -0.3078, -0.0301, +0.1685, -0.1506, +0.0278, -0.1542, +0.1565, -0.6516, -0.1237, +0.0929, -0.2329, -0.1984, -0.4724, +0.2307, +0.3782, +0.4176, +0.4383, -0.3455, +0.3168, +0.1180, +0.2909, -0.1012, +0.1286, -0.0347, -0.2117, +0.0111, -0.0285, +0.1317, +0.1310, +0.2168, -0.1906, +0.3162, +0.0639, -0.0704, -0.2262, +0.1623, -0.4405, +0.3805, +0.0383, -0.0340, -0.7635, +0.0810, +0.0497, -0.2813, -0.3334, -0.1317, -0.1793, +0.2184, +0.1701, -0.6818, -0.0908, -0.0421, -0.0849, -0.0449, +0.1266, -0.3249, +0.0535, -0.0865, -0.3225, -0.2194, -0.2844, -0.1194, -0.0899, +0.0359, +0.1564, -0.0033, -0.4960, -0.0576, +0.1548, -0.2170, +0.4585, +0.3145, +0.0617, -0.0532, +0.1724, -0.0141, +0.1699, -0.4904, +0.4061, -0.2469, -0.1990, +0.2468, +0.0400, -0.0165, -0.3423, +0.3232, -0.4064, -0.0525, -0.4683, +0.2054, -0.1599, -0.0302, -0.1733, +0.0794, +0.1102, -0.2173, +0.0244, -0.3933, -0.1153, -0.0233, +0.5126, +0.0037, -0.2264, -0.2053, -0.0165, +0.1438, -0.5592, -0.0604, -0.3643, -0.0868, -0.0800, -0.2152, -0.2482, -0.1522, -0.0747, -0.6181, +0.1722, -0.1270, -0.2769, -0.2791, +0.2759, -0.2312, -0.4696, -0.1414, -0.0734, -0.3751, +0.2078, -0.2445, +0.2426, +0.0533, -0.1425, +0.3050, -0.0827, -0.5703, +0.1974, -0.1613, -0.3847, +0.2888, -0.0833, -0.0521, +0.1316, -0.2689, -0.0090, +0.3293, +0.1631, +0.1408, -0.2444, -0.0232, +0.2931, +0.0770, +0.0145, -0.1422, +0.2749, +0.1730, +0.1402, +0.0209, -0.3114, +0.2974, +0.3669, +0.2171, -0.0237, -0.1884, +0.0323, +0.1172, +0.2836, -0.0257, +0.4679, +0.1863, +0.1192, +0.4333, +0.1319, -0.0990, +0.2281, +0.0288, -0.3451, -0.3312, -0.1227, +0.5827, -0.3799, +0.4705, +0.3426, +0.1792, -0.4163, +0.4064, +0.0575, -0.0937],
-[ +0.0611, +0.3078, -0.1742, +0.2253, -0.4689, -0.1905, -0.3324, -0.1328, +0.4608, -0.3198, -0.2465, -0.0288, +0.1197, -0.5908, +0.3047, -0.0921, -0.1324, -0.2190, +0.4715, -0.1399, -0.1553, -0.0099, -0.9663, -0.1458, -0.2057, -0.3101, -0.0829, -0.2965, -0.8199, -0.4384, +0.4178, +0.0461, -0.3854, -0.3726, +0.3608, -0.0623, -0.2017, -0.2245, -0.6420, -0.0401, -0.2116, +0.1069, +0.2786, -0.0822, -0.4163, -0.4312, +0.1290, -0.3507, +0.0898, +0.0773, +0.3763, -0.4004, -0.0178, -0.6708, +0.2680, +0.4420, +0.1213, +0.0530, +0.3676, +0.1269, +0.1466, -0.2989, +0.4742, -0.3132, +0.0904, +0.0000, +0.4407, -0.3638, +0.0135, +0.4315, -0.2404, -0.1172, -0.2249, +0.2325, +0.0726, -0.1253, -0.1858, +0.5537, -0.0504, -0.9185, -0.0784, -0.0081, +0.0234, +0.1326, -0.1351, +0.2210, -0.0699, +0.0861, +0.3462, +0.8427, +0.1939, +0.3911, -0.3045, -0.0151, -0.2161, +0.1299, -0.0528, +0.0737, -0.1087, -0.4404, +0.1146, -0.7538, -0.0746, -0.1742, -0.2862, +0.1254, +0.0625, -0.9375, +0.3686, +0.2854, +0.1226, -0.1359, +0.2138, +0.1159, -0.2702, +0.2378, -0.1893, +0.0742, -0.0629, -0.4931, +0.1946, +0.0666, +0.0595, -0.2730, -0.2086, -0.2011, +0.0994, -0.6447, -0.3034, +0.4399, -0.0323, -0.8062, +0.2143, -0.2933, -0.8614, +0.2216, -0.6174, +0.3424, -0.3845, -0.1546, -0.2461, -0.3759, -0.0275, +0.1786, +0.1448, -0.1917, +0.0765, +0.1404, -0.3502, +0.2456, -0.1461, -0.2474, +0.1245, +0.0020, -0.1272, -0.4356, -0.3834, -0.1794, -0.0142, -0.2149, +0.3772, +0.2140, -0.0896, -0.0987, +0.1417, +0.4623, +0.0911, +0.2603, +0.3035, -0.0827, -0.0475, -0.0204, +0.0262, -0.1349, -0.3267, +0.1301, -0.0057, +0.0480, -0.6501, +0.1047, +0.2006, +0.3080, -0.1755, -0.1978, -0.5803, -1.1720, +0.1803, -0.0135, -0.0410, -0.1853, -0.4568, -0.4508, +0.2594, -0.0582, -0.0565, -0.5740, +0.1930, +0.5278, +0.0094, -0.6138, -0.4217, +0.2114, -0.0352, +0.3174, +0.0062, -0.1661, -0.2995, -0.6589, -0.2840, +0.2203, +0.1942, -0.0672, +0.0641, -0.5811, +0.0498, -0.4309, -0.4020, +0.4601, -0.1588, +0.0766, -0.1776, +0.3328, -0.5007, +0.0958, +0.0832, +0.1465, -0.2590, -0.7014, -0.3533, +0.3146, -0.1766, -0.8621, +0.2161, -0.1767, -0.2962, -0.1483, +0.2304, -0.9708, -0.2495, +0.1152, +0.0527, -0.1122, -0.2209, +0.0535, -0.1199, +0.2872, -0.4190, -0.1181, +0.2871, -0.1416, +0.1468, +0.1890, -0.3637, +0.2674, -0.2951, -0.5520],
-[ +0.3224, -0.3127, +0.1477, +0.4042, -0.2816, +0.1801, -0.3632, -0.4932, +0.3709, -0.0116, +0.1003, -0.0342, -0.1900, -0.2473, +0.4070, +0.3534, +0.0446, -0.5582, +0.4056, +0.2565, -0.0216, -0.1793, -0.0214, +0.0586, +0.5041, -0.0780, +0.3289, -0.4695, -0.0019, -0.1165, +0.1928, +0.0276, -0.0934, -0.0401, +0.2345, -0.2896, +0.1065, -0.0970, +0.2237, +0.3538, +0.0806, +0.1541, +0.4284, -0.2360, -0.0456, +0.0949, -0.0767, -0.2645, +0.2787, +0.0931, +0.1863, -0.0527, +0.3325, -0.1285, -0.1237, +0.4867, +0.1638, +0.5354, +0.3012, -0.1084, +0.1007, +0.1260, +0.0695, -0.2001, +0.2486, -0.3006, +0.1528, -0.4508, -0.0287, +0.2927, -0.3191, -0.1170, +0.0527, -0.1668, -0.2379, -0.0629, -0.0162, +0.3974, -0.5739, -0.3054, +0.0959, +0.1848, +0.3932, -0.0600, -0.0137, -0.6117, -0.2887, +0.1422, +0.3672, +0.1573, -0.0439, +0.2197, -0.1045, +0.1218, +0.2470, -0.3030, +0.0290, -0.2101, -0.2285, -0.1076, +0.3314, -0.0303, -0.2679, -0.0188, -0.0019, +0.0514, -0.1176, -0.4099, -0.0185, +0.3927, +0.0246, +0.3295, +0.1434, +0.1825, -0.1085, +0.1551, -0.3395, +0.0757, +0.1600, -0.3613, +0.3572, +0.0125, +0.0061, +0.1241, -0.0557, +0.0449, +0.1740, -0.0347, -0.3372, -0.1299, +0.0773, +0.3050, +0.2442, -0.0268, +0.4932, -0.0212, -0.7499, -0.1609, +0.2292, -0.0242, -0.4588, -0.0083, -0.2593, -0.1930, -0.0839, +0.0332, +0.0602, +0.2326, -0.0420, -0.1836, +0.0801, +0.3550, -0.0732, +0.2023, +0.0618, +0.2686, +0.3199, -0.0585, +0.0699, +0.4110, +0.0118, -0.0995, -0.2929, -0.2489, +0.0978, +0.0877, -0.0767, +0.0659, -0.2370, +0.0765, -0.1233, +0.2962, +0.1523, +0.0544, -0.2004, -0.3175, +0.0601, +0.5150, +0.0255, +0.0057, +0.2318, -0.0558, -0.4948, -0.4292, -0.1899, -0.4096, +0.1288, +0.1194, +0.0070, -0.0548, +0.1307, -0.1176, +0.1721, -0.2888, +0.2454, -0.2094, -0.0900, -0.2116, +0.4802, +0.4547, -0.1396, -0.1156, -0.4985, -0.1793, -0.2882, +0.0199, -0.4122, -0.0101, -0.0266, +0.1625, +0.2353, -0.3339, +0.2636, -0.2425, -0.2090, -0.1268, -0.0383, +0.0191, -0.0739, -0.1670, +0.0690, -0.0317, -0.1051, -0.1572, +0.0167, -0.0760, +0.0480, -0.4994, +0.0660, +0.2312, -0.4430, +0.5670, +0.4197, +0.0942, +0.0800, +0.0784, +0.0543, -0.0619, +0.1259, -0.0537, +0.0592, +0.1902, -0.0528, +0.1624, -0.0941, -0.0937, +0.2642, +0.1356, +0.2628, -0.0354, +0.2153, +0.1671, -0.0721, +0.4179, -0.3169, -0.0289],
-[ -0.5803, -0.0273, -0.0867, -0.2584, +0.0324, +0.5024, +0.2084, -0.1799, +0.1409, -0.6306, +0.0890, +0.1275, +0.0616, +0.0344, +0.0807, -0.0372, +0.0265, -0.1669, -0.2355, +0.0271, -0.7700, +0.1172, -0.0231, -0.2389, +0.0853, -0.5193, +0.4735, -0.0984, +0.8684, +0.7334, +0.3930, -0.0315, +0.2018, -0.0346, -0.8833, +0.0193, +0.5264, -0.1244, +0.1678, +0.2494, +0.0423, +0.2485, -0.1706, +0.2937, -0.6983, -0.7671, +0.1922, -0.5751, -0.0333, +0.1523, +0.5973, -0.0412, -0.1279, -0.3813, -0.0872, +0.1495, +0.1821, +0.6008, -0.4524, +0.4405, +0.6326, -0.2808, -0.2926, +0.4507, +0.0868, +0.1535, -0.2036, -0.1044, -0.2049, +0.4605, -0.3767, +0.3232, +0.0216, +0.2235, -0.1168, -0.3464, +0.2172, +0.1721, +0.2620, -0.5405, +0.2447, +0.0913, -0.1686, +0.2218, +0.2892, +0.4072, -0.3119, -0.8141, -0.5237, -0.2244, -0.0809, -0.0767, +0.2571, -0.2712, +0.2743, +0.2806, -0.5054, +0.3266, -0.2475, +0.1132, +0.1580, -0.5744, +0.6102, +0.3380, -0.3990, +0.1183, -0.0317, +0.2527, +0.2397, +0.1724, +0.3687, +0.1003, +0.4660, +0.6658, +0.1793, +0.2163, +0.4701, +0.3775, +0.2500, +0.4531, +0.1673, -0.4755, -0.1397, +0.5405, -0.5446, +0.1288, +0.0967, +0.2088, +0.3100, +0.2587, -0.0596, +0.2117, +0.0903, -0.4571, -0.3911, +0.1151, -0.1371, -0.0751, -0.5101, +0.9461, -0.2897, +0.4531, +0.1608, -0.4687, -0.1213, -0.5739, -0.0733, +0.3992, -0.2095, +0.3293, -0.0643, -0.5819, -0.3289, +0.1431, +0.1823, +0.2308, +0.0626, +0.2265, -0.2274, -0.1451, +0.1298, +0.2444, +0.3809, +0.1196, +0.2863, -0.0854, -0.0057, +0.0601, +0.0965, -0.7362, -0.1561, +0.3504, +0.1185, +0.3864, -0.3101, -0.4990, +0.3772, +0.4807, +0.0461, +0.9313, +0.0836, -0.2765, +0.2350, +0.0832, +0.2205, -0.5168, -0.1647, +0.1240, +0.5142, +0.0643, -0.1902, +0.0209, +0.1553, -0.1786, +0.0356, +0.2483, +0.3052, +0.1525, -0.4210, +0.3188, -0.2613, +0.5367, +0.4172, +0.0167, +0.1076, -0.7111, +0.2268, +0.4572, -0.0538, +0.4088, -0.4665, -0.2512, -0.0689, +0.2433, -0.3109, +0.0256, -0.2157, +0.3432, +0.3144, -0.3142, +0.6272, +0.2602, -0.2451, -0.0987, -0.2741, -0.0236, +0.2398, -0.0648, -0.0188, -0.3843, +0.3367, +0.1920, +0.4231, -0.3188, +0.0820, +0.3757, +0.4807, -0.1248, +0.3980, -0.0158, -0.5703, +0.1927, -0.6508, -0.1380, -0.0500, +0.3608, +0.1018, +0.3031, +0.7349, -0.2402, +0.2606, +0.4573, -0.1254, -0.6462, +0.3231, +0.3154],
-[ +0.0149, -0.0283, +0.0292, +0.0228, -0.2204, +0.0025, -0.1869, +0.1630, -0.1096, -0.0707, +0.2569, -0.0258, -0.0743, +0.2652, +0.1330, -0.3632, -0.4221, -0.4973, +0.0707, +0.0312, -0.1621, -0.0081, -0.0504, -0.0034, -0.3477, +0.2506, +0.3567, -0.1004, -0.0023, +0.0513, -0.0193, +0.1204, +0.2787, -0.0471, -0.0686, -0.1681, +0.1938, +0.2302, +0.0325, +0.0863, -0.2133, +0.2352, -0.0514, +0.0857, -0.0373, -0.3076, +0.0739, -0.0005, -0.1691, +0.1977, +0.2865, -0.0232, -0.1837, -0.1503, -0.2634, -0.3663, +0.3594, +0.2725, +0.0468, +0.1010, -0.0176, -0.0638, +0.1523, -0.1746, -0.1516, +0.3473, -0.4868, +0.2359, -0.2848, -0.0089, +0.2509, -0.1903, +0.0904, -0.0008, -0.0443, -0.3106, +0.1641, -0.1648, -0.0804, +0.1817, +0.1874, +0.2325, +0.0388, -0.2293, +0.0438, -0.0323, +0.3212, -0.3971, +0.1317, -0.1043, +0.1733, -0.3115, -0.1521, -0.0278, +0.1597, +0.1488, +0.2086, +0.3062, +0.1483, -0.0037, +0.0211, +0.4898, +0.1590, -0.4147, +0.1122, +0.4511, +0.4929, +0.2055, -0.1063, -0.2175, -0.1760, +0.2200, +0.3597, +0.0898, -0.0207, +0.0137, +0.4418, +0.2735, +0.1716, +0.2474, +0.1682, +0.0975, +0.0733, +0.4200, -0.3772, +0.0910, +0.2955, +0.0999, -0.3352, +0.3816, +0.0081, -0.1290, +0.0712, +0.2741, -0.2172, +0.1118, -0.3487, -0.4790, -0.3282, +0.2295, +0.2731, +0.1193, +0.5220, -0.1749, +0.3679, -0.4365, +0.1776, +0.4369, +0.0663, +0.2523, +0.0318, -0.2594, -0.0968, -0.1865, +0.1813, +0.0345, +0.0566, +0.1780, +0.2866, -0.0196, +0.2674, +0.1790, -0.1964, -0.1468, +0.3044, -0.0378, +0.2500, +0.2037, -0.1253, -0.5152, -0.3690, -0.0885, -0.3400, +0.2524, +0.0910, -0.3584, -0.2269, -0.0640, -0.0404, +0.4809, -0.2771, -0.0946, +0.0924, -0.0384, -0.1648, -0.3782, +0.4143, +0.1945, -0.0368, +0.2829, -0.0968, -0.2018, +0.1974, -0.0393, -0.0609, +0.0347, -0.0810, +0.1275, -0.2494, +0.0792, -0.2517, -0.0751, -0.0438, +0.2531, -0.2712, -0.3991, -0.2440, +0.4161, +0.0998, +0.1292, -0.0100, -0.1110, -0.0403, -0.1242, -0.2749, +0.4414, -0.3737, +0.0662, +0.3098, -0.2940, -0.1035, +0.0787, -0.2168, +0.1684, -0.0599, +0.1484, -0.1814, -0.0735, +0.1977, -0.1252, -0.3795, -0.0251, +0.4081, -0.3642, -0.1602, +0.1218, -0.0431, +0.0123, -0.0645, +0.0157, -0.2527, +0.2099, +0.0956, -0.3961, -0.0332, +0.1681, +0.5391, -0.0096, +0.5405, -0.3352, +0.1402, -0.0295, -0.0723, +0.2783, +0.0030, +0.2798],
-[ -0.0354, +0.0453, +0.3500, -0.3471, -0.2109, -0.1173, -0.3520, -0.0333, -0.0067, +0.3466, +0.0650, -0.2510, -0.4762, -0.0643, -0.2253, +0.1201, -0.2505, -0.0481, +0.0518, -0.3525, -0.1378, +0.0982, -0.5547, +0.2424, -0.1063, -0.2991, +0.4079, -0.1162, -0.0661, +0.2924, -0.3963, +0.2862, +0.1332, -0.0872, -0.1993, +0.1340, -0.3032, -0.1052, -0.1286, -0.3403, +0.1369, +0.1253, -0.1515, -0.2172, +0.2381, -0.4324, -0.0409, -0.3135, -0.0799, -0.4632, -0.5431, -0.1894, +0.2509, +0.5030, -0.2823, +0.3794, -0.0391, -0.1346, +0.2211, -0.0250, -0.3781, +0.3886, +0.5035, +0.0534, +0.1245, +0.1264, -0.0116, +0.0133, -0.1717, +0.3956, +0.0467, +0.1601, +0.3756, +0.0925, +0.0328, +0.2124, +0.6018, +0.1404, +0.0594, +0.1382, -0.5218, +0.2223, +0.0790, -0.0674, -0.0832, -0.3092, +0.3593, -0.3136, +0.1884, -0.2425, -0.5318, -0.1218, +0.2421, -0.3231, -0.7911, -0.4926, +0.3991, -0.2189, -0.1681, -0.5131, +0.0509, +0.0338, -0.1953, +0.1520, -0.2028, -0.0616, +0.4112, +0.1993, +0.1682, +0.1303, -0.1001, -0.1197, -0.2874, +0.3450, +0.1934, +0.3140, -0.6519, +0.0112, +0.0481, -0.0431, -0.7008, -0.1956, -0.0524, +0.1107, +0.0457, +0.2703, -0.2400, +0.0137, -0.5900, +0.0930, +0.0433, +0.0270, -0.3728, +0.3152, +0.5378, +0.1319, -0.0989, +0.1903, +0.2497, +0.0627, -0.0222, -0.6911, -0.2004, +0.9832, -0.2162, +0.7030, +0.2834, -0.3340, -0.2094, +0.3005, -0.1364, +0.6207, +0.1348, -0.0796, +0.3638, -0.0591, -0.3195, -0.0862, -0.0592, +0.4195, +0.3004, +0.3248, -0.2234, -0.1877, +0.7093, -0.1116, -0.7692, -0.3403, +0.5564, +0.3110, +0.1635, +0.0245, +0.1445, -0.3785, -0.1565, +0.1251, +0.1432, -0.2219, -0.1753, +0.1186, -0.5071, -0.4024, -0.3913, -0.2113, +0.1187, -0.3587, -0.2125, -0.1784, -0.1304, +0.0333, +0.6733, +0.2380, -0.0781, +0.3920, +0.5218, -0.5096, -0.0453, -0.1092, -0.2755, -0.2618, +0.2256, -0.2251, -0.2685, -0.6291, +0.4639, -0.0920, +0.4521, +0.0293, +0.0722, +0.3435, -0.2480, -0.1396, -0.0924, +0.1203, -0.1185, -0.0110, +0.5724, -0.1400, -0.1099, +0.6710, +0.1855, -0.9102, +0.1814, +0.0835, +0.4068, -0.1440, -0.2479, +0.5081, -0.2556, +0.2026, -0.4832, -0.3482, +0.1707, -0.3255, +0.1505, -0.3818, -0.0001, -0.0519, -0.1092, +0.0822, +0.5690, -0.5227, +0.1843, +0.5351, +0.4847, +0.0426, +0.2993, -0.1047, +0.5704, -0.1589, -0.4606, +0.2568, +0.1225, +0.0552, +0.1132, -0.2106],
-[ -0.0355, +0.3622, -0.1122, -0.0303, -0.4921, +0.1137, -0.1361, +0.0401, +0.0725, -0.1617, +0.1317, -0.1431, +0.1153, +0.3067, -0.4288, +0.1733, -0.3218, -0.0858, -0.1087, -0.2338, -0.0811, +0.0730, -0.2743, +0.1327, +0.3564, -0.5947, +0.0407, +0.4382, +0.1483, -0.0121, +0.1343, -0.1675, -0.3163, -0.1488, +0.1189, +0.0350, -0.0097, -0.1976, +0.2417, +0.0877, +0.2365, +0.0743, -0.1832, -0.1173, -0.1580, -0.5560, -0.0276, +0.3173, -0.0094, +0.0388, -0.1414, -0.2771, +0.2711, +0.2469, -0.1703, +0.1818, +0.0264, -0.2214, +0.5135, -0.2963, +0.0303, -0.2954, -0.4191, +0.2253, -0.1221, +0.0004, +0.7831, -0.1942, +0.2980, +0.0941, -0.1158, +0.0762, -0.4350, +0.2548, +0.1551, +0.0626, -0.1493, +0.2065, -0.1857, +0.3529, +0.0159, -0.0789, +0.0286, +0.3495, -0.4227, -0.2727, -0.4004, -0.0161, +0.0784, +0.0005, -0.5149, +0.2267, +0.1262, +0.2041, -0.2295, -0.0231, -0.0952, -0.3389, -0.0382, -0.7448, +0.3889, -0.2127, +0.0199, +0.4035, -0.0883, -0.5268, -0.0065, -0.1990, +0.0788, -0.0710, +0.0046, +0.0501, +0.2624, +0.1142, +0.0861, +0.0973, -0.0997, -0.1003, +0.1973, +0.0342, -0.4391, -0.1778, +0.1548, -0.1463, +0.4342, +0.0971, +0.1819, +0.3409, +0.5878, +0.2337, +0.2358, +0.3475, +0.1530, -0.0638, +0.3338, +0.0206, -0.5476, +0.0459, +0.2077, +0.0189, -0.2543, -0.1159, -0.0761, +0.1582, +0.2011, +0.3916, +0.3256, +0.1015, -0.0287, +0.1276, +0.1682, +0.0129, +0.1087, -0.1810, -0.0576, +0.1725, +0.1025, +0.1324, +0.0085, +0.2264, +0.0824, +0.2827, -0.6279, +0.1958, +0.0485, -0.0216, -0.1729, -0.1706, +0.1623, +0.1096, +0.0931, -0.2832, +0.1802, -0.0646, -0.1355, +0.0594, +0.3365, -0.5376, -0.3364, -0.0848, -0.2613, +0.2620, -0.1301, -0.1667, +0.0069, -0.0479, -0.1272, +0.1957, +0.0804, -0.3009, +0.4240, +0.1106, -0.1548, +0.1902, +0.2378, +0.0324, +0.0166, -0.0790, -0.2156, -0.0279, +0.3249, -0.2199, -0.2090, -0.3370, +0.1200, +0.0100, +0.3260, -0.1957, -0.1774, +0.0949, +0.1212, -0.1598, -0.5556, +0.0015, -0.2261, +0.1006, +0.2085, -0.0848, -0.3551, +0.2949, +0.0054, -0.3264, +0.0888, +0.0342, +0.2470, -0.1530, +0.1504, +0.0761, +0.4616, +0.3578, -0.1200, -0.1338, -0.0620, +0.0946, +0.2839, +0.0636, -0.0184, +0.2804, -0.0567, -0.1815, +0.2045, -0.3143, -0.0527, +0.1029, +0.0471, -0.0471, +0.0808, -0.1168, -0.4076, +0.0829, -0.3031, +0.4676, +0.0224, -0.2077, +0.1978, -0.1999],
-[ -0.1010, -0.2404, -0.2849, +0.1455, +0.1378, +0.1926, +0.2361, -0.2937, +0.2064, +0.0421, +0.1812, +0.3691, -0.3486, -0.1022, -0.0744, +0.1229, -0.4386, +0.0125, -0.3881, -0.2996, -0.2048, -0.0510, -0.0781, -0.3222, -0.1134, +0.4023, -0.0872, -0.2938, -0.2908, +0.1103, +0.0489, +0.0848, -0.0176, -0.1458, +0.2423, -0.2866, +0.0703, +0.1127, -0.0908, -0.1242, -0.0303, +0.0013, +0.3948, -0.0005, -0.3593, -0.0699, +0.0717, -0.1636, +0.0218, -0.1483, -0.0507, -0.3385, +0.2285, +0.1355, -0.2551, +0.1935, -0.0375, -0.3576, -0.1881, -0.1769, +0.0818, -0.5925, -0.3859, -0.0831, -0.2700, +0.4297, +0.0970, +0.1278, -0.1513, +0.0816, -0.1888, +0.1098, +0.3399, -0.0018, +0.2739, +0.0184, +0.0993, -0.0991, +0.1596, +0.5928, -0.0822, -0.2233, +0.3677, +0.3220, +0.1140, -0.1767, +0.5258, +0.4774, -0.0458, -0.0948, -0.4548, -0.2476, -0.0233, -0.0541, +0.0045, +0.2602, +0.4560, -0.0344, +0.1204, +0.1533, -0.1514, +0.3085, +0.2845, +0.3404, -0.4993, -0.0295, +0.0624, -0.1884, +0.2009, -0.1249, -0.0573, -0.1487, -0.2205, +0.0016, -0.0881, +0.1541, +0.0690, +0.0145, +0.0524, +0.3216, -0.1606, +0.1517, +0.0081, +0.4805, +0.0226, -0.0203, +0.0023, -0.0584, +0.1681, -0.0201, -0.0608, +0.1595, +0.3428, -0.2155, +0.2397, +0.0575, +0.7541, +0.0353, +0.3523, -0.1614, +0.2833, -0.1922, -0.0940, -0.0291, -0.5722, -0.1692, +0.2149, +0.0178, -0.4139, +0.1471, +0.2255, +0.1661, +0.2754, -0.1459, -0.4383, -0.3946, +0.6009, -0.0886, +0.0474, +0.0736, +0.2629, -0.0619, +0.4421, +0.1605, -0.2438, +0.3361, -0.2058, +0.0710, -0.1289, +0.0594, -0.2340, -0.2595, -0.0250, +0.2283, -0.0586, +0.0627, -0.2667, +0.0925, +0.1576, +0.1741, +0.8442, +0.5583, -0.0159, -0.2321, -0.0409, +0.0735, -0.0223, +0.1001, -0.0379, -0.0188, +0.3270, -0.0840, -0.1032, -0.2846, +0.1852, -0.2949, -0.2839, +0.2000, +0.0629, -0.1761, +0.1738, +0.0466, +0.3147, +0.0903, +0.3592, -0.0907, +0.1427, +0.0810, +0.4527, -0.0541, +0.1086, +0.1319, -0.0877, +0.1123, +0.4379, +0.1703, +0.1027, +0.2658, +0.1417, -0.2404, -0.2094, +0.2889, +0.0311, +0.2736, +0.2997, +0.0053, +0.0980, -0.1896, +0.1880, -0.1268, +0.2664, -0.2131, +0.0449, +0.5181, +0.3755, +0.1311, +0.1349, -0.3928, -0.0983, -0.0195, -0.2122, -0.2219, +0.0039, -0.0009, -0.1480, -0.0794, -0.1908, +0.1162, -0.1523, -0.1697, +0.3557, +0.0493, +0.2932, +0.0499, -0.4129, +0.0758],
-[ -0.0468, -0.1803, +0.1076, +0.3251, +0.6184, -0.3114, -0.1230, +0.3713, -0.4464, +0.0684, +0.3383, +0.3221, -0.2729, +0.2946, +0.1943, +0.1954, -0.6578, -0.0570, -0.0339, -0.2920, +0.0423, -0.5298, +0.4007, -0.5820, -0.0377, +0.0406, -0.2370, -0.4655, -0.0046, +0.5069, -0.0471, +0.0535, +0.1463, +0.3264, +0.4456, +0.0105, +0.3068, -0.0262, +0.0298, +0.0183, +0.3544, +0.5920, -0.1028, +0.0257, -0.1456, +0.4452, -0.4759, +0.1087, +0.3227, +0.1700, +0.2066, -0.6348, +0.0231, +0.5112, +0.6282, +0.3323, +0.4566, -0.0154, -0.2268, +0.0425, +0.2978, -0.1051, +0.2577, +0.5342, -0.7325, +0.1593, +0.4029, +0.0706, -0.3219, +0.3941, -0.1809, +0.2960, +0.7586, +0.8630, -0.5558, +0.0672, -0.2114, -0.8054, +0.6901, +0.4814, +0.2078, +0.3896, +0.2214, -0.4920, +0.9965, -0.7324, -0.6585, +0.5329, +0.7044, -0.6737, +0.0255, -0.1597, +0.2869, -0.5315, -0.0708, -0.0608, -0.1456, -0.1391, +0.2564, +0.4272, +0.8474, +0.1289, -0.4975, -0.2000, +0.2369, -0.0471, +0.6356, +0.0456, +0.4963, -0.6084, +0.0811, -0.1642, -0.2298, -0.2015, +0.2522, +0.4432, -0.4480, -0.8622, +0.0647, +0.1456, -0.0836, -0.0173, +0.3379, -0.5648, -0.0681, -0.5624, +0.1191, +0.0971, +0.1196, +0.1649, -0.3151, -0.1059, -0.4016, +0.1005, +0.4878, -0.0364, -0.0470, +0.3035, +0.1903, -0.3378, +0.1568, -0.0147, +0.1942, -0.5899, -0.2620, -0.2944, +0.5645, +0.0389, -0.3849, -0.4410, +0.2850, -0.1466, +0.5244, -0.2212, -0.1834, +0.1653, +0.0254, +0.0407, +0.0358, +0.4145, +0.5616, -0.1249, +0.1544, +0.3584, -0.7873, +0.6443, -0.5025, +0.2097, -0.1029, -0.1549, -0.2047, -0.0593, +0.2371, +0.6084, +0.6281, +0.6733, -0.0301, +0.0384, +0.3657, -0.1154, -0.5736, +0.5779, -0.4174, -0.1531, -0.0563, -0.1114, -0.1184, -0.1867, +0.3557, -0.4798, -0.0917, +0.0213, -0.2287, -0.2391, +0.0658, -1.0389, -0.3860, -0.4087, -0.1438, +0.1826, +0.1439, +0.0826, +0.6390, +0.2824, +0.2706, -0.5583, +0.3452, -0.2026, +0.0264, +0.2765, -0.0574, +0.1179, +0.2400, +0.3694, +0.1398, -0.0551, +0.4724, -0.0146, +0.0828, -0.1048, -0.7036, +0.2830, +0.1624, +0.0022, +0.0491, +0.3424, +0.0850, -0.0712, -0.4055, -0.1021, -0.0042, -0.3948, -0.9802, -0.0024, +0.1138, -0.6403, -0.0022, -0.8502, +0.0091, +0.5823, -0.3955, -0.1233, -0.2180, -0.3058, -0.9293, +0.0442, -0.0494, -0.5554, -0.1709, +0.1602, -0.1647, -0.6202, -0.3488, +0.0541, -0.5352, +0.1713],
-[ +0.0434, -0.3968, -0.1349, -0.2066, +0.3152, -0.0083, +0.2409, -0.3602, -0.0166, -0.3587, -0.7228, +0.2045, -0.1413, -0.3595, -0.0951, +0.3833, -0.2863, +0.1655, +0.0306, -0.0000, +0.1136, +0.1681, -0.1042, +0.3163, +0.1026, +0.1338, +0.5371, +0.3121, -0.2184, -0.1777, +0.1852, -0.5399, -0.1528, -0.2153, -0.2149, +0.0972, +0.2558, -0.1794, +0.1174, -0.0328, -0.2456, -0.1888, +0.2037, +0.0165, +0.1809, +0.2236, -0.2411, -0.2453, +0.2664, -0.0525, +0.0902, +0.1405, -0.0758, +0.1247, +0.1022, +0.3313, +0.4122, -0.0819, -0.0913, -0.0533, -0.1639, +0.1616, -0.0751, +0.2544, +0.0883, -0.2207, -0.1827, +0.0533, -0.1477, -0.2653, -0.2350, +0.6668, +0.2252, -0.3081, -0.3665, +0.0026, +0.0920, -0.1562, -0.0314, +0.0379, -0.2651, +0.1148, -0.5456, +0.0571, +0.1669, +0.1868, +0.2954, +0.3341, +0.0854, -0.0493, -0.0501, -0.1120, -0.1885, +0.0989, -0.0145, +0.1403, -0.3893, +0.1667, +0.6599, -0.2808, +0.3894, +0.2285, -0.2094, -0.1589, +0.4491, -0.0021, -0.2059, -0.0030, +0.2450, -0.2107, -0.0648, +0.0584, -0.1049, +0.0746, +0.2399, +0.2282, +0.0306, +0.5307, -0.0164, +0.1248, +0.2186, -0.0220, -0.1162, +0.5217, +0.1629, -0.0953, -0.2606, +0.2256, +0.0594, +0.4022, -0.0169, +0.4560, -0.0626, +0.1872, -0.0363, +0.3869, +0.1683, +0.3439, -0.1965, -0.1233, -0.2428, -0.3865, -0.3022, -0.1513, -0.2319, +0.0000, +0.2206, -0.0137, -0.1011, +0.2059, -0.1762, -0.4659, +0.2081, -0.3539, -0.0841, -0.1500, +0.4548, +0.3499, -0.2080, +0.3888, +0.2226, -0.2984, -0.4921, -0.3772, -0.0471, -0.0440, -0.0105, +0.1756, -0.3131, -0.0878, +0.7077, +0.3702, +0.1133, -0.2221, +0.1952, +0.0806, -0.2353, +0.2592, +0.2637, -0.6006, +0.2933, -0.4829, +0.4448, -0.0385, -0.3345, -0.1955, -0.0801, +0.0901, -0.1696, -0.3215, +0.3141, +0.5010, +0.0102, -0.0129, -0.2312, +0.0084, -0.0576, +0.4211, -0.2397, -0.0064, +0.3961, -0.0321, -0.1348, -0.0105, +0.0683, +0.0717, -0.3076, +0.0072, -0.2908, +0.1944, -0.4525, +0.4002, -0.4078, +0.4851, -0.4503, -0.4731, -0.0486, +0.0489, +0.0492, -0.0522, -0.3638, -0.1330, -0.5329, -0.1299, +0.0669, -0.2405, +0.4118, -0.0958, -0.1522, -0.2151, -0.0750, -0.0031, -0.1397, +0.1805, -0.0993, -0.2138, +0.5460, +0.4139, +0.2523, +0.2470, +0.1786, -0.3776, -0.2915, +0.0429, -0.0625, -0.0230, -0.2243, +0.0370, +0.4230, +0.0268, +0.1411, +0.5420, +0.1266, -0.0715, +0.0100, -0.1583],
-[ -0.0856, +0.1478, +0.2785, -0.0657, +0.1545, +0.1689, -0.1283, +0.4019, +0.1912, -0.1993, -0.2968, -0.0713, -0.1384, -0.0585, +0.1859, -0.1121, +0.2789, -0.6703, +0.0369, -0.2677, +0.2354, +0.0859, +0.1691, +0.1177, +0.4367, -0.1944, +0.1313, +0.0345, +0.3538, +0.2729, -0.0549, -0.8789, -0.3384, +0.0929, +0.0006, +0.1985, +0.1025, -0.0835, -0.3176, -0.0434, -0.1049, +0.0199, +0.2184, -0.4230, +0.0097, +0.1678, +0.5019, +0.1112, -0.2290, -0.4790, -0.1312, +0.0389, -0.0391, -0.2474, -0.2959, +0.2159, +0.0441, +0.0862, -0.2301, -0.0838, +0.3966, +0.2530, -0.2189, +0.1688, +0.1591, +0.1861, -0.3146, +0.3129, +0.1761, -0.1694, +0.1243, +0.5333, +0.3268, -0.6051, -0.1596, -0.1461, -0.1474, -0.0511, +0.0185, -0.0473, -0.3436, +0.0696, -0.0586, +0.5214, +0.3185, -0.2699, +0.3036, +0.0976, -0.0414, +0.1253, -0.3417, -0.3601, -0.3066, -0.1276, +0.1276, +0.2614, -0.2289, -0.0838, -0.5791, +0.1228, +0.2188, -0.1403, -0.5108, -0.0042, -0.2635, -0.1724, -0.0935, +0.1031, +0.0405, +0.0990, +0.0993, -0.2823, -0.0210, +0.0794, +0.4503, +0.5037, +0.0093, +0.0860, -0.3676, -0.0706, +0.2548, -0.0475, +0.3295, -0.1392, +0.1828, +0.0132, +0.1810, +0.2123, -0.4686, +0.0295, +0.4871, +0.0510, +0.3081, -0.4667, -0.3504, -0.1607, +0.2874, -0.1792, -0.4659, -0.0761, -0.0962, +0.0650, -0.1850, +0.2290, -0.2686, +0.0044, +0.2452, +0.0938, -0.1060, -0.0672, -0.2507, -0.2213, -0.4228, +0.2368, -0.0212, +0.0515, +0.0144, +0.2502, -0.2411, -0.1577, +0.1654, -0.2035, +0.1488, +0.1289, +0.4932, +0.2637, +0.1076, +0.5758, -0.1948, -0.0004, -0.1230, +0.1666, -0.0507, -0.0315, +0.0948, -0.1583, +0.8365, -0.5093, +0.2411, +0.2074, +0.0961, -0.1875, +0.2806, -0.0420, +0.1372, -0.0757, -0.1236, -0.3455, +0.1362, -0.2789, +0.2951, +0.4255, +0.0779, -0.2744, -0.3579, -0.1468, -0.2699, +0.3013, -0.6950, -0.4577, -0.1276, -0.0866, -0.0794, +0.0145, -0.0166, +0.0164, +0.0345, +0.0089, +0.0295, -0.1214, -0.2517, +0.5609, -0.3563, +0.4615, -0.1071, +0.1822, -0.3121, +0.2674, -0.3350, -0.2546, -0.3108, -0.0827, +0.1112, -0.4741, +0.4961, -0.3827, +0.3214, -0.0214, +0.2837, +0.2449, -0.0901, +0.0207, +0.1853, +0.3550, -0.0331, +0.6148, -0.0934, +0.1115, +0.0347, +0.1423, +0.2681, +0.1036, -0.2877, -0.3500, -0.3821, +0.0184, -0.3467, +0.1867, +0.6907, +0.0475, -0.5266, +0.1676, +0.1046, +0.2239, -0.0536, +0.1539],
-[ -0.0844, -0.3474, -0.0897, +0.1492, -0.4280, -0.1678, -0.3024, +0.4074, -0.3629, -0.2004, +0.1868, +0.1184, -0.0086, -0.0451, +0.3128, -0.1078, +0.0704, -0.0958, +0.2218, -0.1937, -0.3028, +0.2372, -0.4567, +0.2715, +0.0018, +0.0344, +0.3235, -0.2282, +0.0839, +0.2394, -0.2440, -0.2340, +0.0998, -0.0844, -0.1730, -0.1000, +0.2880, -0.3090, +0.1695, +0.3572, +0.0307, -0.0739, -0.1133, -0.1782, -0.2876, -0.0359, -0.3327, +0.1698, -0.3572, +0.1098, +0.1340, +0.0604, -0.0513, +0.1150, +0.2439, +0.0899, -0.5564, +0.0675, -0.3053, +0.0340, +0.2903, -0.0247, -0.4335, +0.0542, -0.2079, -0.1710, +0.1518, -0.2401, -0.2369, -0.1225, -0.5155, +0.0449, +0.2075, -0.4325, -0.6876, +0.1819, -0.3930, -0.2237, -0.2683, +0.4713, -0.0287, +0.0986, -0.7589, -0.0699, -0.1480, +0.0169, -0.1973, -0.4215, -0.1522, +0.0113, -0.1273, -0.1016, -0.0639, +0.3509, -0.2240, -0.1146, -0.6177, +0.3497, +0.0372, +0.0542, +0.1487, -0.0626, -0.0458, +0.1751, +0.1285, -0.4678, +0.0586, +0.1874, -0.0348, -0.0960, +0.0458, +0.0459, +0.0862, -0.0687, -0.2644, +0.1326, -0.1289, -0.4631, -0.2240, -0.2605, +0.1904, +0.0466, -0.6984, -0.1629, -0.3469, +0.0080, +0.1777, +0.2707, +0.1424, +0.0567, -0.3038, -0.2561, -0.4254, -0.5804, +0.0237, -0.3453, -0.4146, +0.0453, -0.1700, -0.2211, -0.1830, +0.1386, +0.0974, -0.2867, -0.1311, +0.2497, -0.1554, -0.1106, -0.0011, +0.0374, -0.1288, +0.0673, -0.1604, -0.3713, -0.2043, -0.2112, +0.5406, -0.0867, +0.3670, -0.4745, -0.2994, -0.1433, -0.0713, +0.0591, -0.0761, +0.3913, -0.2590, +0.0657, +0.0527, +0.0918, -0.0480, -0.1542, +0.2264, +0.0627, -0.2540, +0.1928, -0.4839, -0.4015, -0.2736, -0.3463, +0.1071, -0.1021, +0.1950, -0.9547, +0.0687, +0.0291, +0.2292, +0.1111, +0.0181, -0.4079, -0.1859, -0.0060, -0.1915, -0.1541, -0.1969, +0.0345, -0.1558, -0.6596, -0.0265, -0.2989, +0.1218, +0.6290, -0.3345, +0.1225, -0.2464, -0.3944, -0.3526, +0.2880, -0.2926, +0.1864, -0.1420, +0.3058, +0.4685, +0.1149, -0.2107, +0.0171, -0.0748, +0.0790, -0.3467, +0.2248, +0.0542, -0.0743, +0.2650, -0.5654, -0.2655, +0.4095, -0.2855, -0.3975, -0.2072, -0.0676, +0.2310, -0.0036, +0.2007, +0.1200, +0.0486, +0.0304, +0.4052, -0.1677, -0.1908, -0.0181, +0.3009, +0.5420, -0.5680, -0.2664, +0.3837, +0.1885, +0.0908, -0.3664, +0.0211, -0.1291, -0.1372, +0.4594, +0.2679, -0.3230, -0.0231, -0.1443],
-[ +0.1188, -0.0062, -0.1855, +0.0061, +0.0306, -0.0784, -0.0046, +0.0331, -0.0294, -0.0984, -0.0919, -0.0323, +0.2738, -0.0880, +0.0371, -0.1605, +0.0143, -0.0569, +0.2232, +0.0354, -0.0566, +0.1567, -0.0185, +0.0081, -0.1761, -0.0795, +0.1846, +0.1453, -0.0407, -0.2160, -0.0459, -0.0277, +0.0894, -0.1279, -0.0910, +0.1040, +0.0504, -0.2097, -0.0634, +0.0084, -0.1961, +0.1012, +0.1308, +0.2605, -0.0705, -0.0478, -0.2174, +0.2493, -0.2422, -0.1305, +0.0405, +0.0641, -0.1725, -0.0818, -0.2816, +0.0841, +0.3524, +0.0472, -0.0587, +0.0883, -0.0404, +0.1379, -0.2522, -0.0918, +0.1629, +0.2672, +0.0629, +0.0421, -0.1408, +0.1162, +0.4380, +0.0535, +0.0310, -0.0877, -0.1680, +0.0768, -0.0017, -0.0234, -0.1326, -0.0905, +0.0225, +0.1534, -0.3547, -0.0126, +0.2719, +0.2255, +0.2082, +0.0991, -0.1591, -0.0375, +0.1838, -0.1323, -0.1685, +0.0670, -0.0271, +0.1774, -0.1511, -0.1249, -0.0076, +0.2603, -0.0498, +0.4234, +0.1259, +0.0072, -0.1172, -0.1527, +0.1257, -0.1016, -0.0718, -0.1387, -0.0541, -0.1035, +0.3143, +0.0014, +0.0494, +0.1847, -0.0088, -0.1042, -0.2360, +0.0559, -0.1222, -0.0523, -0.2117, -0.0481, +0.1020, -0.1081, +0.1276, -0.0923, +0.2182, +0.2122, -0.4165, +0.3006, -0.0619, -0.1256, -0.0520, -0.2651, +0.1489, -0.0744, -0.1675, -0.0369, -0.1036, -0.1059, -0.0107, -0.0155, -0.0360, +0.1124, +0.1453, -0.1140, -0.0969, +0.0473, +0.0795, -0.0893, -0.1323, -0.2102, +0.3700, +0.0070, +0.2332, -0.3127, +0.2441, +0.0592, +0.1080, -0.0951, +0.1115, +0.1210, -0.0443, +0.3194, -0.0297, -0.1664, +0.1317, -0.0076, -0.1066, +0.0799, +0.1736, -0.1156, +0.0316, -0.0194, +0.1922, +0.1214, +0.0565, -0.1967, +0.0512, -0.3551, +0.5148, -0.3325, -0.1339, -0.0176, -0.0343, -0.0769, +0.0491, +0.1307, -0.2277, -0.0290, +0.0137, -0.0868, +0.2483, -0.0012, -0.1753, +0.0822, -0.1489, -0.1712, +0.2157, +0.2645, -0.0124, -0.0948, -0.0568, -0.1064, -0.4283, +0.1993, +0.0347, -0.0106, -0.0786, +0.1873, +0.0116, +0.2466, -0.2081, +0.0319, -0.0489, +0.1163, -0.1659, +0.1652, +0.0900, -0.0880, +0.1234, +0.0172, -0.0558, +0.0468, +0.1217, +0.1276, -0.4597, -0.2922, -0.1088, +0.2172, -0.0321, +0.0119, +0.2671, +0.3911, +0.0646, +0.0570, -0.0646, +0.1160, +0.0275, -0.0507, +0.0738, -0.1869, +0.0136, -0.0425, +0.1594, +0.0189, -0.1377, +0.0037, +0.3298, -0.4311, +0.0769, -0.0184, -0.1103, +0.0244],
-[ +0.1054, -0.2168, +0.3055, -0.1927, +0.4667, +0.0062, -0.0394, -0.0066, +0.0748, +0.2722, +0.1231, -0.4803, -0.3702, -0.4034, +0.2811, -0.1451, -0.2890, +0.0938, +0.3394, +0.2368, +0.3143, -0.3831, -0.0124, +0.0447, +0.3256, -0.0822, +0.1423, -0.1473, +0.1624, -0.0504, -0.3621, -0.1886, -0.3732, +0.0208, -0.1155, -0.2275, -0.1666, -0.2031, +0.1617, -0.3938, -0.1407, +0.0080, -0.0580, +0.0384, +0.0658, -0.1640, -0.2468, -0.1383, +0.0596, +0.1068, +0.0534, -0.0051, -0.3557, -0.0406, -0.0507, +0.1816, +0.6789, -0.1818, +0.1339, +0.1081, +0.0070, -0.0684, -0.2302, +0.0372, +0.6024, +0.3344, -0.1124, +0.3763, +0.1331, -0.3067, +0.1826, -0.1368, -0.0467, +0.0766, -0.3554, -0.1818, -0.0986, +0.0499, +0.2472, -0.1546, +0.1109, -0.0436, -0.1748, +0.1036, +0.1237, -0.2409, +0.0438, -0.5612, -0.0766, +0.0434, +0.0672, -0.2422, +0.0780, -0.1071, -0.0339, +0.3233, -0.2388, -0.0255, -0.1036, +0.3328, -0.0563, +0.8040, -0.5256, -0.0498, -0.4856, -0.0392, -0.0712, -0.2621, -0.2574, +0.2102, -0.2959, +0.0252, +0.0019, -0.1644, -0.1745, -0.1622, +0.1824, -0.2087, +0.1812, -0.1774, -0.3812, -0.1082, -0.0959, +0.2566, +0.2259, -0.1851, +0.3297, -0.0968, +0.3032, +0.1812, +0.0655, -0.1436, -0.3918, -0.2189, +0.2596, -0.1304, +0.1238, -0.1444, -0.2449, -0.0436, -0.1132, +0.3240, +0.0263, -0.0106, +0.0406, +0.4209, -0.0316, -0.0954, +0.5860, +0.4458, +0.1500, -0.3507, -0.1574, +0.0575, -0.3635, +0.0061, +0.2587, -0.0712, -0.0532, -0.1439, -0.4468, -0.0377, +0.3117, -0.4202, -0.0904, -0.0639, -0.1331, +0.0928, +0.1268, -0.0187, -0.1143, +0.1903, +0.0173, +0.3476, +0.0337, -0.0970, -0.1437, -0.0459, -0.1899, -0.0688, -0.2715, +0.1964, -0.2309, +0.0410, +0.0591, -0.0484, +0.1132, -0.0666, -0.4161, -0.3532, +0.2478, -0.4591, +0.3771, -0.2481, +0.3671, +0.5620, +0.1931, -0.1757, -0.0949, +0.0013, +0.0432, -0.3041, +0.0795, +0.2424, +0.3880, -0.2640, -0.0703, -0.0955, +0.3911, -0.0092, -0.0215, +0.1020, -0.0816, +0.5155, +0.1905, +0.0905, -0.0211, +0.0291, +0.1083, -0.2923, -0.0677, +0.1323, +0.0813, +0.1232, +0.3196, +0.0985, +0.2345, +0.2325, +0.1330, -0.4605, -0.0187, -0.0423, -0.1833, +0.5139, -0.1893, -0.1392, -0.0291, -0.4728, +0.1218, -0.1672, -0.0034, -0.2759, +0.0834, +0.0443, -0.1188, +0.2753, +0.1841, +0.0355, +0.1480, -0.0975, +0.2347, -0.3679, -0.1949, +0.2217, -0.2040, +0.1008],
-[ +0.3394, -0.7614, +0.2214, -0.0855, +0.1614, +0.1544, -0.2578, -0.0026, +0.0793, -0.3764, +0.6935, -0.1747, +0.3017, -0.5659, +0.4088, -0.3397, +0.0083, -0.0262, +0.1206, +0.1305, +0.4384, -0.0426, -0.1596, -0.2370, +0.5147, +0.2141, -0.0156, -0.1807, -0.4023, +0.1593, -0.6592, -0.0338, -0.3846, -0.7189, -0.3224, +0.1704, +0.0438, -0.0268, -0.1999, +0.2407, -0.6428, +0.5990, -0.1621, -0.1820, +0.2747, -0.5300, -0.1427, -0.7566, +0.4896, -0.4544, +0.4176, +0.3437, -0.4714, +0.1215, -0.5182, -0.1339, -0.4483, +0.2899, +0.5122, +0.1295, +0.1649, +0.1705, +0.2041, -0.1614, +0.1871, +0.2149, -0.1200, +0.2660, -0.0501, -0.1457, -0.5291, -0.5227, -0.0281, +0.4277, +0.3698, -0.2083, -0.4078, -0.2390, +0.2048, +0.4018, +0.2991, +0.4258, -0.2820, +0.1101, +0.4753, -0.2546, +0.3167, +0.1833, -0.2245, -0.0669, -0.2413, +0.0229, -0.1720, -0.1400, -0.3102, +0.1771, +0.1776, +0.4946, -0.3560, -0.2972, -0.1236, +0.2733, -0.6177, -0.2299, +0.1100, -0.3703, +0.0889, -0.2761, -0.4925, -0.0626, -0.3893, -0.0899, -0.0676, -0.0853, -0.2297, +0.0095, -0.1208, -0.5865, +0.6617, -0.4572, -0.2909, -0.2341, +0.0815, -0.1485, -0.2683, -0.1679, -0.0129, +0.0477, +0.1809, -0.2123, -0.3615, -0.6727, +0.0831, +0.3760, +0.0771, -1.4335, -0.1328, -0.4613, -0.1139, +0.2321, +0.1380, -0.1703, +0.5679, +0.1268, -0.3508, +0.6495, -0.1023, +0.6463, +0.1550, +1.1874, -0.6792, +0.0565, -0.3362, +0.1157, +0.4535, +0.4557, -0.2579, -0.3490, -0.1606, -0.0600, -0.3668, -0.2549, -0.2206, -0.2502, +0.2149, +0.1647, -0.0841, -0.0877, +0.3362, +0.1809, +0.0896, -0.3949, -0.1881, +0.5513, +0.1961, +0.3686, -0.3547, -0.4208, +0.4066, -0.2038, +0.3193, -0.5107, -0.0533, -0.5291, +0.0475, +0.0730, +0.0105, -0.3940, -0.1920, -0.2656, +0.3453, +0.2038, +0.3677, -0.5476, +0.3070, +0.1598, +0.5035, -0.2558, -0.0726, +0.0814, -0.1602, +0.1250, -0.6546, +0.0126, -0.0443, +0.0209, -0.4783, -0.6256, -0.4328, +0.0440, -0.4465, -0.3143, +0.2611, +0.1469, -0.4565, -1.1730, +0.2640, +0.2994, +0.7914, -0.3757, +0.5256, +0.0436, -0.0332, +0.1276, +0.0059, +0.1051, +0.2218, +0.3520, -0.0248, -0.3851, +0.1581, -0.3110, -0.6304, +0.0452, +0.2547, -0.0698, +0.8202, -0.4308, +1.2043, -0.4712, +0.1173, -0.3822, -0.3770, -0.0086, +0.1568, +0.4548, -0.4026, +0.1963, +0.4417, -0.6008, +0.5816, -0.1452, +0.0417, +0.1982, -0.3800, -0.2664],
-[ -0.2992, -0.0651, +0.2159, +0.0240, +0.0736, -0.4168, -0.5236, +0.1070, +0.0535, +0.3093, +0.2249, +0.2270, -0.3072, -0.0049, -0.1310, -0.2224, +0.1580, +0.4033, +0.5195, -0.1055, +0.2601, -0.1190, -0.3645, +0.0051, +0.2045, +0.3766, -0.0244, -0.5023, -0.0240, -0.1550, +0.2681, +0.3682, -0.1841, -0.0522, +0.2098, +0.2268, -0.1093, +0.2332, +0.5778, +0.6197, +0.2322, +0.0085, +0.1506, +0.3598, -0.0317, +0.5181, -0.0356, -0.0515, -0.2531, +0.3544, -0.1317, -0.4739, -0.1546, -0.3621, -0.1195, -0.1657, +0.3775, +0.2377, +0.2617, -0.5888, +0.2719, -0.0414, +0.2364, +0.1782, +0.1752, -0.2697, +0.2526, -0.4014, +0.1016, -0.2323, +0.1804, +0.2456, -0.5135, +0.4187, +0.1828, +0.0881, +0.3396, -0.3524, +0.2835, +0.1598, +0.3014, +0.3287, -0.1001, -0.5764, +0.5307, +0.3432, +0.1786, +0.1841, +0.3194, +0.0322, +0.0635, -0.1484, -0.1721, +0.2902, +0.0985, -0.2712, +0.0447, -0.2040, +0.3322, -0.3784, +0.4789, +0.1240, +0.0907, -0.4958, +0.0231, +0.3108, +0.1237, +0.3056, -0.0658, +0.3824, -0.2770, -0.1186, +0.2047, +0.1621, +0.2605, +0.0635, +0.0690, -0.1246, +0.3525, +0.3477, -0.1305, +0.3089, -0.1852, -0.0984, +0.3058, +0.2318, +0.0024, -0.0468, +0.3999, +0.3441, -0.2823, +0.0867, +0.3494, +0.0294, -0.2707, +0.1037, +0.0623, +0.2920, -0.0737, -0.2443, +0.1817, +0.5216, -0.1961, +0.2754, -0.3191, -0.1483, +0.1877, +0.2167, -0.0089, -0.2084, +0.1375, +0.5702, -0.2180, +0.0258, +0.5848, +0.0790, +0.0788, -0.4052, +0.2006, +0.5514, +0.2136, -0.0307, -0.0158, +0.2657, -0.2026, +0.1168, +0.2559, -0.2174, +0.0156, -0.0384, +0.1042, +0.1578, -0.5233, -0.1059, -0.0075, +0.4496, -0.1021, +0.4807, -0.2985, +0.4535, +0.4438, +0.0698, +0.0586, -0.0216, -0.0365, -0.1558, +0.2064, +0.2944, -0.0148, -0.3029, +0.3201, +0.0180, -0.1867, +0.5149, -0.3466, +0.3419, -0.1637, -0.1427, -0.1105, +0.0022, +0.3945, +0.1162, +0.0346, +0.3303, -0.1833, +0.1308, -0.3093, +0.0348, -0.0904, -0.2031, +0.0814, -0.3449, -0.1796, -0.3040, -0.3401, +0.1225, -0.1545, +0.5068, +0.3989, -0.0013, +0.5641, -0.3532, -0.1942, -0.1687, -0.1114, -0.1999, -0.0661, +0.2681, +0.2743, +0.4534, -0.2305, +0.4529, +0.0423, +0.0636, +0.3217, -0.2737, -0.0687, +0.4375, +0.0141, -0.0618, +0.2720, -0.2361, +0.2434, -0.1013, -0.2688, -0.1412, +0.2729, +0.0794, -0.1377, +0.5015, +0.2502, -0.2067, -0.1218, -0.6458, -0.0523, -0.0650],
-[ +0.3441, +0.2829, -0.1503, -0.0332, +0.1858, +0.1395, +0.0879, -0.1205, -0.1095, +0.1852, +0.1222, +0.0559, -0.4706, +0.0324, -0.1134, -0.0665, -0.3218, +0.1018, +0.2539, +0.0300, +0.2705, -0.1099, +0.1179, -0.1600, +0.1179, -0.2765, +0.1150, -0.2641, -0.2885, +0.1065, +0.1017, +0.2576, -0.1618, -0.3436, +0.1729, +0.0816, -0.4718, -0.1865, +0.0193, +0.1006, +0.3371, +0.1657, +0.3770, +0.1948, -0.3284, +0.4507, -0.6109, -0.0043, -0.1162, +0.5108, -0.0104, -0.0478, -0.1986, +0.7830, -0.2516, -0.0317, +0.1780, +0.0521, -0.4717, +0.2174, +0.1625, -0.5251, +0.3654, +0.0506, +0.0803, -0.0040, +0.2544, +0.0186, +0.2581, +0.6387, +0.0425, +0.5194, -0.1895, +0.2762, -0.0024, +0.2617, +0.1806, +0.0780, +0.2480, -0.0483, -0.1712, -0.0462, -0.6504, -0.1070, -0.0228, +0.2949, -0.2238, -0.0048, +0.1718, +0.1315, -0.1787, -0.1962, +0.1789, -0.0566, -0.3448, -0.1039, +0.5405, +0.1158, -0.1730, -0.2223, -0.7140, +0.0533, +0.5751, -0.0426, -0.3939, +0.2308, -0.2111, +0.3114, -0.3711, -0.0791, +0.1444, +0.0691, -0.4759, +0.0175, -0.3883, -0.5391, -0.5098, -0.2830, +0.0391, +0.0104, -0.1874, +0.0947, -0.5966, -0.3012, +0.5591, -0.0172, +0.7039, -0.2962, +0.0215, +0.2526, -0.1035, -0.3527, -0.1393, +0.2405, +0.0787, -0.1479, +0.0842, +0.0582, +0.2952, -0.4363, -0.1011, +0.2056, +0.3146, +0.0389, -0.0858, -0.1660, +0.3535, +0.4799, -0.4005, +0.0061, +0.0206, +0.2809, -0.4679, +0.0673, +0.1444, +0.4264, +0.1073, -0.0798, +0.2253, +0.2579, -0.2576, -0.6007, +0.2503, +0.1877, +0.1759, -0.0705, -0.0339, +0.0163, -0.2833, +0.0496, -0.0724, +0.2122, -0.3213, -0.3731, -0.1660, +0.7755, +0.5124, -0.3694, +0.0588, +0.6647, -0.1604, +0.0630, +0.4835, -0.0083, +0.0906, -0.0258, +0.1266, +0.2651, +0.2562, -0.1427, -0.0474, -0.4239, -0.7708, +0.0567, -0.0012, +0.2501, +0.3560, +0.2524, -0.0227, +0.3620, -0.1382, +0.0917, -0.5030, -0.3181, +0.2090, -0.1478, +0.1735, +0.1747, +0.2128, -0.3544, -0.0411, -0.2734, +0.1527, +0.1054, -0.0259, -0.0187, +0.3115, +0.4073, +0.0994, +0.0935, +0.6014, -0.0894, +0.0277, -0.1051, -0.1312, -0.1745, +0.3722, -0.0633, +0.0195, -0.1503, -0.2477, +0.4542, +0.2569, -0.0691, -0.4412, -0.3885, +0.0734, -0.0987, -0.2265, -0.3065, -0.3015, -0.1369, -0.0411, -0.0006, -0.3387, -0.1562, +0.2495, +0.1843, -0.2748, +0.2291, +0.1961, -0.4904, -0.0636, -0.4188, -0.1648, +0.0309],
-[ -0.1101, +0.2888, -0.0570, -0.2413, -0.0390, +0.2698, +0.1938, +0.0145, +0.0237, -0.2956, -0.4008, -0.0022, +0.0345, -0.1847, +0.2073, +0.0978, -0.0419, -0.3933, -0.2629, +0.0098, -0.3885, +0.1342, -0.0587, -0.1620, -0.3930, +0.1811, +0.1102, -0.1745, -0.2421, +0.2253, -0.1974, +0.1268, +0.0282, -0.2039, +0.0702, -0.2754, -0.0110, -0.0924, +0.2770, +0.0063, -0.0631, +0.0970, -0.7981, +0.6435, +0.0694, -0.1290, -0.4013, -0.2976, -0.1189, -0.0855, -0.0435, +0.2674, +0.0120, -0.1390, +0.1714, -0.0429, +0.1475, -0.0044, +0.1297, +0.3749, -0.0918, -0.5348, +0.0863, -0.3325, -0.4748, -0.1736, -0.3445, -0.1265, -0.1200, -0.0806, -0.1163, +0.0163, +0.2598, -0.1576, -0.2488, -0.2472, +0.2509, -0.4404, -0.1876, +0.3221, -0.3592, -0.1262, +0.3532, +0.0683, +0.2758, -0.1483, -0.2939, -0.1960, -0.4137, +0.0178, -0.7016, +0.3077, -0.2093, -0.0895, -0.2004, -0.3399, +0.0842, -0.0058, -0.2212, +0.2213, +0.4328, +0.1054, +0.0692, +0.1697, -0.3399, -0.6201, -0.2515, -0.1451, -0.3156, +0.0578, +0.0930, -0.3049, +0.3093, -0.0713, +0.1023, +0.1076, +0.1541, +0.0090, -0.0674, -0.2613, +0.5020, -0.0728, +0.0510, +0.3646, -0.2715, -0.2480, -0.1565, -0.0924, +0.1268, +0.3606, -0.0366, +0.2756, -0.3328, -0.1564, -0.1865, +0.2388, -0.0115, +0.1762, +0.0824, +0.1327, -0.1527, -0.2355, -0.4851, -0.1165, +0.4048, -0.1261, -0.0750, +0.0529, +0.0781, -0.1981, -0.1395, -0.1394, +0.1320, -0.3198, -0.0006, +0.1270, -0.4287, -0.6049, +0.2057, +0.3400, -0.3563, -0.4932, -0.5145, -0.1045, +0.1827, -0.3174, +0.0244, +0.0332, +0.2180, +0.4740, -0.0398, -0.1993, -0.3635, +0.2097, -0.6872, +0.2724, -0.1679, +0.0348, +0.3445, +0.1957, -0.3088, -0.1068, -0.2200, -0.3352, -0.1096, +0.0410, +0.0512, +0.3525, +0.0330, -0.5465, -0.2135, -0.1984, -0.2308, +0.5293, +0.1617, +0.2654, -0.1835, +0.1527, -0.2546, -0.1011, -0.4182, +0.3049, +0.1546, +0.0340, -0.3729, -0.0622, +0.1132, -0.0512, -0.2418, +0.5127, +0.3217, -0.2271, -0.3689, -0.3579, -0.2182, -0.2907, -0.1061, -0.0115, -0.1363, +0.0616, -0.3810, +0.2862, +0.1817, +0.1519, -0.0023, +0.2365, -0.2017, +0.4321, +0.5002, -0.2249, +0.2603, +0.1545, +0.2074, -0.0076, +0.3339, +0.2493, -0.0047, -0.1137, +0.0961, -0.0032, -0.4285, -0.1184, +0.0864, -0.0413, -0.0146, +0.1829, +0.1736, +0.5632, +0.1765, +0.0709, -0.2767, -0.3822, +0.0837, -0.0828, -0.1817, -0.4356],
-[ +0.0509, +0.2549, -0.0917, +0.0055, -0.1253, -0.2132, +0.1324, +0.1052, +0.1497, -0.1908, -0.0401, -0.0706, +0.0651, +0.1787, -0.1051, +0.0126, +0.0923, +0.1210, -0.1329, +0.0673, -0.0865, -0.0131, -0.2468, -0.0502, -0.4783, -0.0405, +0.0969, -0.0889, -0.3024, +0.0693, -0.0800, -0.0309, +0.2216, +0.0338, +0.0138, -0.1827, +0.3096, -0.0509, +0.1161, -0.0364, -0.0345, +0.1886, +0.0345, +0.0415, +0.0310, -0.0568, +0.0756, -0.2673, +0.4001, +0.0710, -0.2191, -0.0395, +0.0336, +0.0451, -0.1021, -0.0249, -0.0280, -0.1428, +0.0277, +0.0195, +0.0316, +0.1818, +0.2445, -0.1122, -0.1844, -0.0665, +0.1236, +0.2563, -0.5410, -0.0603, +0.3191, -0.0136, -0.1709, -0.1540, +0.1974, -0.1454, -0.1034, -0.0974, -0.0698, +0.0841, -0.0363, -0.1820, +0.2072, -0.1064, -0.0869, -0.1811, -0.1966, +0.1278, +0.0298, -0.2119, -0.1671, -0.2875, -0.0361, -0.0482, +0.0314, +0.0290, +0.0851, +0.0537, +0.0957, +0.2396, +0.1253, +0.0739, +0.1998, -0.0330, -0.1236, -0.0330, -0.1687, +0.0705, +0.0731, -0.0384, -0.0285, -0.1246, +0.0957, -0.0006, +0.0445, -0.0565, +0.0416, +0.1593, +0.1834, +0.0946, -0.0487, +0.0335, +0.0907, +0.2604, -0.2899, -0.2021, -0.3221, +0.0609, -0.0346, +0.0620, +0.0226, +0.0928, -0.2789, -0.0239, -0.0884, -0.0846, -0.1203, +0.1690, +0.0817, -0.0668, -0.1689, -0.0252, +0.1500, +0.0080, +0.0213, -0.0426, +0.0002, +0.0008, +0.3091, -0.0535, +0.0746, +0.0195, +0.2861, -0.4008, -0.2297, -0.0856, +0.1802, -0.1335, -0.1767, -0.4181, +0.0338, -0.0447, -0.4958, +0.2912, +0.0691, +0.1188, -0.0518, -0.2267, -0.1507, +0.0251, -0.0474, -0.0816, -0.1468, +0.0212, -0.1467, -0.1739, +0.0645, -0.1244, +0.0266, -0.1640, -0.2757, -0.3275, -0.0195, +0.0605, +0.1956, -0.0616, -0.1276, +0.1034, -0.1577, -0.4807, -0.0699, +0.1038, -0.3131, +0.3759, +0.0188, -0.1638, +0.1375, -0.0620, +0.0319, +0.0859, +0.0839, -0.1305, +0.4374, +0.2390, -0.0321, -0.0078, +0.3058, +0.0666, -0.2315, +0.0097, -0.0036, -0.1209, -0.3647, -0.1463, +0.1597, -0.5550, -0.1898, +0.0746, -0.0216, +0.1312, -0.1723, -0.1189, +0.0156, +0.2415, -0.0221, +0.0615, +0.1584, -0.0553, +0.2352, +0.1394, +0.1370, -0.2963, +0.0449, -0.1839, +0.3226, -0.0966, +0.4623, -0.0386, -0.0344, -0.1119, -0.0139, +0.0523, -0.0863, +0.1050, +0.0226, +0.0937, -0.0856, +0.3126, +0.0949, +0.2978, -0.2201, -0.0661, +0.2530, +0.0930, -0.0358, -0.0728],
-[ +0.0133, -0.2384, -0.0061, -0.0901, -0.1275, -0.1155, -0.2142, -0.1617, +0.3009, -0.0036, -0.0136, -0.0096, -0.3440, -0.0666, +0.1599, -0.0057, -0.2449, +0.2083, -0.0132, -0.0672, +0.0751, -0.0280, -0.1097, -0.2804, -0.0946, +0.0997, -0.1202, -0.0579, -0.1848, +0.0839, -0.0730, +0.0810, +0.1752, +0.1299, +0.0543, +0.2047, +0.2369, +0.0868, -0.4617, -0.3397, +0.1840, -0.1539, +0.1362, -0.2022, -0.0365, +0.1864, -0.4431, +0.1442, -0.1381, -0.2529, +0.0283, -0.3730, -0.1827, -0.4236, -0.1750, -0.0424, -0.1016, +0.1586, -0.1437, -0.0213, +0.3303, -0.1499, -0.0556, +0.0507, -0.0538, -0.0622, +0.2669, +0.0454, -0.0731, +0.1335, +0.2288, -0.0877, -0.0884, +0.0883, -0.1660, +0.0539, -0.0647, -0.1985, +0.0427, +0.1618, +0.0732, -0.1073, -0.0604, -0.2294, -0.0829, +0.0373, -0.2572, -0.1134, -0.1325, -0.0592, -0.2515, -0.7041, +0.1332, -0.2625, -0.3124, +0.0847, -0.2374, +0.0154, +0.2717, +0.0413, -0.2797, -0.3216, +0.0994, -0.2653, -0.1076, -0.2748, -0.1153, +0.0928, -0.0615, -0.1129, -0.0233, +0.0454, -0.5039, +0.2351, +0.0766, -0.0882, -0.1210, -0.5043, -0.0870, +0.2185, +0.2934, +0.1159, +0.3287, +0.0840, -0.2659, -0.4456, +0.1535, +0.4992, +0.4418, -0.0713, -0.0580, -0.3314, -0.1225, -0.1038, +0.1139, +0.2054, +0.1049, -0.0219, -0.1247, +0.0612, +0.0055, +0.0180, +0.0207, -0.0282, +0.1353, +0.0653, +0.1345, +0.1435, +0.0643, +0.0131, -0.1639, +0.1931, +0.3108, -0.1027, +0.3498, -0.0372, +0.0780, +0.0271, +0.0456, +0.0713, -0.1977, +0.1929, -0.3310, -0.4828, -0.3361, +0.1634, +0.2493, -0.1914, -0.1188, -0.0863, +0.1576, -0.0852, +0.3123, +0.0625, +0.1785, -0.2350, -0.2904, -0.2623, +0.3570, -0.0630, +0.0245, -0.4582, -0.2041, +0.0670, +0.0551, +0.1855, +0.1265, -0.0155, -0.2492, +0.2700, +0.1065, +0.0067, +0.1265, +0.0670, -0.0494, -0.2904, +0.3440, -0.1183, +0.0556, -0.1526, -0.0097, +0.1318, -0.1130, +0.2119, -0.0430, -0.1200, -0.0621, -0.2154, +0.2679, -0.0248, -0.1998, -0.2859, -0.2692, -0.3040, -0.3696, -0.0085, -0.3063, -0.5537, -0.1833, -0.1371, -0.2980, +0.0445, -0.0327, +0.3345, -0.0481, -0.1551, +0.0561, -0.0279, +0.1251, +0.0571, +0.2553, -0.2445, -0.1182, +0.1923, +0.0178, -0.1569, -0.0934, +0.0127, +0.2180, +0.2012, +0.0539, +0.1074, +0.0909, +0.0018, -0.0202, -0.2950, -0.1744, +0.0324, +0.0047, +0.0917, -0.2003, -0.1513, -0.2091, -0.0636, +0.0784, +0.0418],
-[ -0.2106, -0.5721, -0.0255, -0.1498, +0.1872, +0.3760, -0.1564, +0.0184, +0.0084, -0.0493, -0.0988, -0.0707, -0.1691, +0.1350, -0.3833, +0.2407, -0.1562, -0.0640, -0.0549, +0.0372, -0.0310, -0.0492, +0.0252, +0.1114, +0.1642, +0.0543, +0.0866, +0.2849, +0.4380, -0.0755, +0.0529, -0.0072, -0.0424, -0.5035, +0.0025, -0.2118, -0.1066, -0.0997, -0.3320, +0.4686, +0.2913, -0.2035, -0.1154, -0.2489, +0.1538, -0.0449, -0.4716, -0.0805, -0.0606, +0.1385, -0.0411, -0.4550, +0.1078, -0.3315, -0.5334, +0.0061, -0.8814, +0.0727, +0.1807, +0.1161, -0.1132, -0.4640, -0.2277, -0.2282, -0.2055, -0.5139, +0.0047, -0.0208, +0.1003, -0.2417, +0.0952, +0.2703, -0.1661, +0.1264, -0.4941, +0.0922, +0.1002, -0.1667, -0.1846, +0.0267, +0.0046, -0.3622, -0.0821, -0.1047, -0.2113, -0.1532, +0.2937, -0.0069, +0.1870, +0.0629, +0.0534, -0.3144, -0.2376, +0.4708, -0.0426, +0.1698, +0.1616, -0.1427, -0.0134, -0.1560, -0.0194, +0.1307, -0.0201, +0.0507, +0.1696, +0.3215, -0.3706, +0.3820, +0.3235, -0.2105, -0.0798, -0.0110, +0.0270, -0.1236, +0.1016, +0.3631, -0.1671, +0.0517, -0.0126, -0.4177, +0.0929, -0.0079, -0.4019, +0.1569, +0.1172, +0.0554, +0.2186, -0.0931, -0.1609, -0.0355, -0.4825, -0.9546, +0.1382, +0.2313, -0.7419, -0.0895, -0.1796, -0.0352, -0.0448, +0.1210, -0.1250, +0.1624, -0.1704, -0.0683, -0.1812, -0.0288, -0.0914, +0.3675, -0.3053, +0.1319, -0.4109, -0.0725, +0.0943, -0.3600, -0.1820, -0.7750, -0.4543, -0.1667, +0.0541, +0.1525, +0.3136, +0.2429, +0.0330, +0.0671, -0.0504, +0.2418, -0.0134, -0.0162, +0.0131, -0.0574, -0.0483, -0.1079, -0.0850, +0.0559, +0.0030, -0.2679, -0.1837, -0.4726, +0.0286, +0.0347, +0.0651, -0.0097, -0.0460, -0.2189, -0.1798, -0.0577, -0.0150, +0.4606, -0.5806, -0.0051, -0.2598, -0.2094, -0.6703, +0.2159, +0.0723, +0.0526, -0.2678, +0.0617, -0.1728, +0.1177, +0.2750, +0.0184, -0.4359, -0.0940, +0.0947, -0.2164, -0.4097, +0.2435, -0.1214, +0.2233, +0.1313, -0.6796, +0.1504, +0.0502, -0.1445, -0.3432, +0.0023, -0.3242, -0.0105, -0.0249, +0.3985, -0.1757, -0.0498, -0.0050, +0.2735, -0.1137, +0.1709, +0.2007, -0.5754, -0.1786, -0.0405, +0.0717, -0.6758, -0.1847, -0.4255, -0.3366, +0.0736, -0.3934, -0.0511, -0.2154, -0.0673, -0.1232, -0.0641, +0.0687, -0.0759, +0.0476, +0.1716, +0.2402, +0.0314, -0.0472, -0.9131, -0.6135, -0.1311, +0.0928, +0.0507, -0.1242]
+weights_dense1_b = np.array([
+ -0.4552, -0.1503, -0.3889, -0.4356, -0.3327, -0.3599, -0.1077, -0.0547,
+ -0.2992, -0.3454, -0.3705, -0.1112, -0.3337, -0.1734, -0.1778, -0.1140,
+ -0.2167, -0.2335, -0.2373, -0.2079, -0.1363, -0.2558, -0.5103, -0.4488,
+ -0.3511, -0.4497, -0.1993, -0.3206, -0.2805, -0.2771, -0.4950, -0.1219,
+ +0.0040, -0.2419, -0.2004, -0.4094, +0.0324, -0.1852, -0.1683, -0.2174,
+ -0.2260, -0.4295, -0.0234, +0.0697, -0.0889, -0.2716, -0.0776, -0.2180,
+ -0.2874, -0.2960, -0.2822, -0.2619, -0.2378, -0.2151, -0.2067, -0.3821,
+ -0.0814, -0.2688, -0.4554, -0.2181, -0.3726, -0.2187, -0.2084, -0.0858,
+ -0.0825, -0.0525, -0.0755, -0.3285, -0.0519, -0.0250, -0.2732, -0.3364,
+ -0.4320, -0.2458, -0.1822, +0.1847, -0.2062, -0.3188, +0.0713, -0.0491,
+ -0.0854, -0.2231, -0.4355, -0.3462, -0.2672, -0.2903, -0.1080, -0.2521,
+ +0.0054, -0.2362, -0.0619, -0.4408, +0.0751, -0.2314, -0.2603, -0.1113,
+ -0.3952, -0.2884, -0.3625, -0.2351, -0.2622, -0.4668, -0.0353, -0.1395,
+ -0.1773, +0.1823, +0.0127, -0.0130, -0.4013, -0.3007, -0.0907, -0.1370,
+ -0.5183, -0.3694, -0.4402, -0.1385, -0.0357, -0.2825, -0.2086, -0.2025,
+ -0.2341, -0.1279, -0.0560, -0.2587, -0.1521, -0.3957, -0.2828, -0.2725,
+ -0.2685, -0.1803, -0.3683, -0.2698, -0.3685, -0.2295, -0.2916, -0.0725,
+ -0.4537, -0.0974, -0.2592, -0.3471, -0.3788, -0.1340, -0.1553, -0.3611,
+ -0.3332, -0.2287, -0.3208, -0.3125, -0.3103, -0.2460, -0.4101, -0.1370,
+ -0.2561, -0.3928, -0.3879, -0.2522, -0.1590, -0.2807, -0.4501, -0.2707,
+ -0.1521, +0.0380, -0.3081, -0.3519, -0.4400, -0.3066, -0.2812, -0.1797,
+ -0.4441, -0.0870, -0.1536, -0.1278, -0.2556, -0.2012, -0.3185, -0.3652,
+ -0.1689, -0.2889, -0.2408, -0.2699, -0.2554, -0.2719, -0.2210, -0.2482,
+ -0.2705, -0.3078, -0.0254, -0.1835, -0.3230, +0.0395, -0.2266, -0.2825,
+ -0.2693, -0.3372, -0.4361, -0.2536, -0.1638, -0.1545, -0.2476, -0.2914,
+ -0.2217, -0.0175, -0.2298, -0.4264, -0.0302, -0.1662, -0.4174, -0.2917,
+ -0.2843, -0.3738, -0.2208, -0.1737, -0.1845, -0.2461, -0.3582, -0.3421,
+ -0.3054, -0.3308, -0.2655, -0.3869, -0.2984, -0.2619, -0.2193, -0.2247,
+ -0.0871, -0.2090, -0.2010, -0.0026, -0.3469, -0.3607, -0.2386, -0.3746,
+ -0.3181, -0.2639, -0.4784, -0.1579, -0.4695, -0.0145, -0.0449, -0.1226,
+ +0.0301, -0.2598, -0.5048, -0.2104, -0.2998, -0.3548, -0.1479, +0.0088,
+ -0.1583, +0.1815, +0.0321, -0.2097, -0.2642, -0.3827, -0.2363, -0.2139
])
-weights_dense1_b = np.array([ -0.4552, -0.1503, -0.3889, -0.4356, -0.3327, -0.3599, -0.1077, -0.0547, -0.2992, -0.3454, -0.3705, -0.1112, -0.3337, -0.1734, -0.1778, -0.1140, -0.2167, -0.2335, -0.2373, -0.2079, -0.1363, -0.2558, -0.5103, -0.4488, -0.3511, -0.4497, -0.1993, -0.3206, -0.2805, -0.2771, -0.4950, -0.1219, +0.0040, -0.2419, -0.2004, -0.4094, +0.0324, -0.1852, -0.1683, -0.2174, -0.2260, -0.4295, -0.0234, +0.0697, -0.0889, -0.2716, -0.0776, -0.2180, -0.2874, -0.2960, -0.2822, -0.2619, -0.2378, -0.2151, -0.2067, -0.3821, -0.0814, -0.2688, -0.4554, -0.2181, -0.3726, -0.2187, -0.2084, -0.0858, -0.0825, -0.0525, -0.0755, -0.3285, -0.0519, -0.0250, -0.2732, -0.3364, -0.4320, -0.2458, -0.1822, +0.1847, -0.2062, -0.3188, +0.0713, -0.0491, -0.0854, -0.2231, -0.4355, -0.3462, -0.2672, -0.2903, -0.1080, -0.2521, +0.0054, -0.2362, -0.0619, -0.4408, +0.0751, -0.2314, -0.2603, -0.1113, -0.3952, -0.2884, -0.3625, -0.2351, -0.2622, -0.4668, -0.0353, -0.1395, -0.1773, +0.1823, +0.0127, -0.0130, -0.4013, -0.3007, -0.0907, -0.1370, -0.5183, -0.3694, -0.4402, -0.1385, -0.0357, -0.2825, -0.2086, -0.2025, -0.2341, -0.1279, -0.0560, -0.2587, -0.1521, -0.3957, -0.2828, -0.2725, -0.2685, -0.1803, -0.3683, -0.2698, -0.3685, -0.2295, -0.2916, -0.0725, -0.4537, -0.0974, -0.2592, -0.3471, -0.3788, -0.1340, -0.1553, -0.3611, -0.3332, -0.2287, -0.3208, -0.3125, -0.3103, -0.2460, -0.4101, -0.1370, -0.2561, -0.3928, -0.3879, -0.2522, -0.1590, -0.2807, -0.4501, -0.2707, -0.1521, +0.0380, -0.3081, -0.3519, -0.4400, -0.3066, -0.2812, -0.1797, -0.4441, -0.0870, -0.1536, -0.1278, -0.2556, -0.2012, -0.3185, -0.3652, -0.1689, -0.2889, -0.2408, -0.2699, -0.2554, -0.2719, -0.2210, -0.2482, -0.2705, -0.3078, -0.0254, -0.1835, -0.3230, +0.0395, -0.2266, -0.2825, -0.2693, -0.3372, -0.4361, -0.2536, -0.1638, -0.1545, -0.2476, -0.2914, -0.2217, -0.0175, -0.2298, -0.4264, -0.0302, -0.1662, -0.4174, -0.2917, -0.2843, -0.3738, -0.2208, -0.1737, -0.1845, -0.2461, -0.3582, -0.3421, -0.3054, -0.3308, -0.2655, -0.3869, -0.2984, -0.2619, -0.2193, -0.2247, -0.0871, -0.2090, -0.2010, -0.0026, -0.3469, -0.3607, -0.2386, -0.3746, -0.3181, -0.2639, -0.4784, -0.1579, -0.4695, -0.0145, -0.0449, -0.1226, +0.0301, -0.2598, -0.5048, -0.2104, -0.2998, -0.3548, -0.1479, +0.0088, -0.1583, +0.1815, +0.0321, -0.2097, -0.2642, -0.3827, -0.2363, -0.2139])
+weights_dense2_w = np.array(
+ [[
+ +0.3879, +0.2396, +0.0232, +0.0493, -0.0340, +0.1665, +0.2217, +0.1171,
+ +0.0085, +0.3267, +0.2266, -0.0363, -0.2285, +0.1748, -0.1585, +0.0734,
+ -0.3677, +0.0954, +0.2970, -0.1971, +0.0358, +0.2842, +0.1077, +0.1848,
+ -0.3721, +0.3555, +0.0312, +0.3012, +0.1629, -0.0240, +0.1497, -0.0660,
+ -0.1494, -0.0224, +0.1263, -0.9698, -0.1457, +0.1154, -0.2845, +0.0623,
+ +0.1252, -0.4020, +0.0405, -0.2055, -0.7892, +0.3388, +0.2717, +0.2135,
+ -0.0900, +0.2047, +0.3570, +0.1618, -0.0130, -0.1451, +0.0269, -0.3374,
+ -0.0319, +0.0781, +0.1225, -0.2690, -0.3954, -0.1528, -0.1380, -0.3103,
+ +0.0119, -0.2609, +0.1626, -0.1506, -0.1703, +0.1453, -0.1559, +0.0226,
+ +0.2468, +0.1129, -0.3168, +0.3180, -0.4714, -0.2041, +0.0954, +0.0695,
+ -0.2502, -0.5624, -0.0675, +0.1097, +0.1381, +0.0817, -0.2450, +0.1088,
+ +0.2002, -0.1809, -0.1564, -0.0451, -0.1434, -0.0938, -0.3670, +0.4046,
+ +0.2029, +0.1312, +0.1496, -0.4210, -0.1977, +0.1471, +0.4224, -0.3782,
+ -0.2004, +0.1622, +0.0707, -0.0112, -0.4681, +0.1948, +0.0322, -0.0500,
+ +0.2589, -0.0610, +0.0823, -0.2286, +0.1807, -0.5483, -0.5366, -0.1090,
+ +0.2459, -0.0599, -0.0595, +0.5233, +0.0837, +0.6305, -0.3973, +0.3492
+ ],
+ [
+ -0.1334, -0.0525, +0.1074, -0.3238, -0.0303, +0.0381, +0.0375,
+ -0.2776, -0.2203, +0.0472, -0.0031, +0.0020, +0.0296, +0.0328,
+ -0.3609, -0.1506, -0.3898, -0.3399, +0.1574, -0.0749, +0.1668,
+ -0.2909, +0.4024, +0.1138, -0.0228, -0.0884, -0.1580, -0.2851,
+ +0.1364, +0.0736, +0.1732, +0.0582, -0.3385, -0.0205, +0.1458,
+ -0.2729, +0.0598, +0.1277, +0.1406, +0.2345, +0.3031, -0.7386,
+ +0.1244, -0.0150, +0.0451, -0.0418, +0.3890, +0.2390, -0.0930,
+ +0.0282, +0.2572, -0.3782, -0.1127, -0.2627, +0.1525, +0.2133,
+ -0.2603, +0.3870, -0.3704, +0.0680, +0.1075, +0.0063, -0.1415,
+ -0.5181, +0.0323, +0.0563, +0.0615, +0.8169, +0.0176, +0.0858,
+ -0.0934, +0.2120, +0.1557, -0.2070, +0.2223, +0.1712, +0.2042,
+ -0.4291, -0.1514, -0.2126, +0.0720, -0.3121, -0.0420, -0.1002,
+ +0.0914, -0.1049, +0.3737, +0.3156, -0.0343, +0.3863, -0.1249,
+ +0.0459, +0.1408, +0.0087, -0.1110, -0.0767, +0.2177, -0.2325,
+ -0.0777, +0.0536, -0.0612, -0.1087, -0.5225, +0.2759, -0.2000,
+ +0.3127, -0.0211, -0.0045, -0.3404, +0.0398, -0.0767, +0.1566,
+ -0.2795, -0.1252, +0.1945, -0.2738, -0.0554, -0.1285, +0.0640,
+ +0.2618, +0.0349, +0.1813, +0.3157, +0.2025, -0.0145, -0.0113,
+ +0.2274, +0.2284
+ ],
+ [
+ +0.0546, +0.1862, +0.1502, -0.2191, +0.1300, -0.4032, +0.0688,
+ -0.1727, +0.2701, -0.0894, -0.0106, +0.0361, -0.0038, +0.0384,
+ -0.3165, -0.0239, +0.2474, -0.1388, +0.0296, +0.0637, +0.1847,
+ -0.2262, -0.0378, +0.3002, +0.0082, -0.3944, -0.0419, +0.1132,
+ -0.0422, +0.1070, -0.0537, +0.1755, +0.1924, -0.0057, -0.4325,
+ +0.4300, +0.4567, -0.2306, -0.3064, -0.7085, -0.4412, +0.0413,
+ -0.0133, -0.1687, -0.2661, -0.3792, -0.3363, +0.0660, -0.6811,
+ +0.2143, +0.2445, +0.0295, -0.3500, -0.3781, +0.1208, -0.2184,
+ -0.2113, +0.1053, -0.1678, -0.2032, -0.1639, -0.1226, +0.4539,
+ +0.0142, -0.3058, +0.1940, +0.2655, -0.3414, +0.1642, -0.1385,
+ +0.0784, -0.4992, +0.0288, -0.1054, -0.1665, +0.1739, -0.0872,
+ -0.0894, -0.2990, +0.2007, -0.1665, -0.0540, -0.0317, -0.2191,
+ -0.3372, -0.4565, -0.3386, +0.1020, +0.0560, -0.2470, +0.6016,
+ -0.1027, +0.3426, +0.1477, +0.0364, +0.4503, +0.4186, +0.3667,
+ -0.0920, +0.3414, +0.0065, -0.3542, +0.0795, +0.2348, -0.1317,
+ -0.0349, -0.0729, +0.2412, +0.0103, -0.1912, +0.0650, -0.2161,
+ -0.0071, +0.1522, +0.0506, +0.0947, -0.1561, +0.3604, -0.1740,
+ -0.0589, -0.3219, -0.0495, +0.0784, +0.1333, +0.0137, +0.1009,
+ +0.0227, -0.0451
+ ],
+ [
+ -0.3659, +0.3609, +0.0757, +0.0230, -0.2625, +0.1963, +0.2730,
+ -0.0915, +0.5428, -0.3923, -0.4557, +0.4054, +0.1263, +0.1352,
+ -0.2606, +0.1874, +0.2919, +0.2726, +0.0937, -0.4385, +0.2201,
+ -0.0312, +0.4016, +0.0312, +0.0897, +0.2672, -0.2690, -0.0755,
+ -0.0904, +0.1233, +0.0601, -0.2100, +0.3736, -0.2714, +0.0402,
+ -0.2663, -0.2331, +0.1311, -0.0994, +0.0008, +0.0423, +0.3885,
+ -0.3188, +0.2140, +0.0799, +0.2551, +0.0308, +0.1343, +0.2759,
+ -0.0590, -0.2743, +0.0347, -0.0869, -0.3184, -0.1484, -0.1302,
+ +0.0563, -0.0078, +0.1153, +0.2749, -0.1931, -0.1806, -0.0848,
+ -0.0633, +0.4508, -0.3048, -0.5275, -0.0930, -0.1693, +0.1414,
+ +0.2661, +0.2183, +0.1022, -0.0988, +0.1789, +0.3381, +0.3250,
+ +0.2161, -0.0701, -0.0880, -0.0250, -0.4079, +0.1521, -0.1058,
+ -0.1326, -0.4439, -0.0534, +0.0147, -0.2594, -0.1968, -0.4695,
+ +0.4551, +0.0918, -0.1311, -0.0133, -0.1826, -0.1722, -0.0214,
+ -0.1624, +0.1087, -0.0513, +0.1001, +0.2597, +0.1829, -0.3807,
+ +0.0630, -0.6444, +0.2731, -0.2359, -0.2519, -0.4507, +0.1038,
+ +0.3720, +0.0332, +0.3184, +0.0875, +0.4122, -0.5976, +0.3661,
+ +0.4470, -0.0326, -0.2758, +0.1908, +0.0329, +0.1615, -0.0914,
+ -0.0453, +0.4482
+ ],
+ [
+ -0.2430, -0.3549, -0.0276, +0.1378, +0.2154, +0.2232, -0.1917,
+ +0.1653, -0.0327, +0.3117, +0.2781, +0.2424, +0.1836, -0.3393,
+ +0.1929, -0.0290, +0.0036, -0.2437, +0.4067, -0.1402, +0.3959,
+ -0.2194, -0.3789, +0.1764, +0.1075, +0.5430, +0.1783, -0.7655,
+ +0.2199, -0.0012, +0.2896, -0.1150, +0.3509, -0.6355, +0.1095,
+ +0.3083, -0.0508, -0.0598, -0.0387, -0.0025, +0.4012, +0.0249,
+ -0.0440, +0.1306, -0.6685, -0.1638, -0.6928, +0.0289, -0.1748,
+ +0.1177, -0.2184, +0.1238, -0.2337, -0.0699, +0.0479, +0.2468,
+ -0.1428, -0.6832, +0.1362, +0.0542, +0.5767, +0.0347, +0.0209,
+ -0.0161, +0.2824, -0.1168, -0.1527, -0.1239, -0.1223, -0.1625,
+ +0.2880, -0.0471, -0.0704, +0.0848, +0.0982, -0.1967, +0.0792,
+ -0.3727, -0.1337, +0.1517, +0.3242, -0.2300, -0.3668, +0.0836,
+ +0.0464, +0.3718, +0.1789, -0.4262, -0.2959, -0.0873, -0.2063,
+ +0.1702, +0.1758, -0.9966, +0.4564, +0.1455, -0.0353, +0.1924,
+ -0.0855, +0.1689, +0.2077, -0.2827, +0.1126, +0.5277, -0.0065,
+ +0.2269, +0.1638, +0.0831, +0.4475, -0.0235, +0.0283, +0.1552,
+ +0.0741, +0.2731, +0.3797, -0.2383, +0.0321, +0.1676, -0.0378,
+ +0.2820, -0.2878, -0.2193, -0.1462, -0.0376, -0.2963, -0.1336,
+ +0.0065, +0.0854
+ ],
+ [
+ -0.0133, -0.0774, +0.1653, +0.1993, -0.1944, +0.2581, -0.5533,
+ +0.1396, -0.0609, +0.1267, +0.3908, +0.4858, -0.3452, -0.6476,
+ -0.1710, +0.0953, -0.0442, +0.1262, -0.5125, +0.2027, +0.3703,
+ +0.1319, -0.1080, -0.2917, +0.2201, -0.2632, +0.2595, +0.2278,
+ +0.6085, -0.0118, +0.0925, +0.3054, -0.0123, +0.2886, -0.1033,
+ -0.0968, +0.0884, +0.0583, -0.1286, -0.2528, -0.2092, +0.3955,
+ -0.2216, +0.1546, +0.1519, +0.1909, +0.3702, -0.0994, +0.0918,
+ -0.4807, +0.1935, +0.0671, +0.4320, +0.1125, +0.2946, +0.1016,
+ +0.2781, +0.0859, -0.0694, -0.0845, +0.6580, -0.3224, +0.0815,
+ -0.0230, +0.1600, +0.3728, +0.0250, +0.4401, +0.0357, -0.0074,
+ -0.1148, -0.3906, +0.0645, +0.1275, +0.0094, +0.1263, -0.3057,
+ -0.2418, +0.0812, -0.0549, -0.2169, +0.3138, -0.1004, +0.0720,
+ -0.3993, +0.2240, -0.2293, -0.6645, +0.0360, +0.2128, -0.2250,
+ +0.1115, +0.3698, +0.1463, +0.2279, +0.1816, +0.0021, +0.2644,
+ -0.0813, -0.3536, +0.3171, -0.0141, +0.1692, -0.0735, +0.1099,
+ -0.0055, -0.9204, -0.6968, -0.0667, -0.4571, -0.2269, -0.1844,
+ +0.2342, +0.0805, +0.1731, -0.0038, -0.0085, -0.0471, -0.8529,
+ -0.1257, -0.1424, +0.2724, -0.5343, -0.1496, -0.0828, +0.0974,
+ -0.1696, +0.1288
+ ],
+ [
+ +0.1253, -0.1387, +0.1862, +0.1052, -0.0798, +0.2158, +0.0780,
+ +0.0028, -0.1907, +0.0812, +0.4299, -0.1405, +0.0977, +0.0346,
+ -0.3432, -0.0439, +0.4926, +0.2405, -0.2341, -0.4948, -0.2674,
+ +0.2975, -0.1626, -0.0767, -0.1164, -0.0418, -0.1568, +0.0083,
+ -0.4281, +0.0491, -0.8546, +0.2168, -0.1845, +0.1116, +0.0233,
+ -0.3213, -0.2366, -0.3144, +0.1870, -0.1365, +0.0464, +0.2936,
+ +0.3069, +0.4470, -0.4670, -0.1529, -0.3486, -0.0822, -0.0776,
+ +0.0347, +0.0510, +0.4063, -0.2823, +0.3495, +0.0887, +0.2299,
+ -0.0561, -0.2744, +0.3720, +0.0752, +0.1584, +0.0464, -0.6384,
+ +0.2085, -0.0736, -0.1031, +0.0997, +0.0094, +0.1853, -0.1647,
+ +0.3305, -0.5368, +0.1890, -0.2845, +0.0550, +0.2342, +0.2572,
+ +0.0622, +0.0434, -0.0867, -0.4546, -0.0118, +0.1483, -0.0886,
+ -0.1938, +0.0504, -0.1731, +0.4389, +0.0260, -0.1393, -0.3271,
+ +0.0401, +0.3255, +0.0470, -0.1401, -0.2314, +0.0622, -0.4021,
+ -0.1835, +0.3193, +0.4884, +0.0147, -0.2552, +0.0416, -0.2928,
+ -0.2332, -0.5361, +0.2024, +0.1249, -0.1697, -0.0577, +0.2168,
+ -0.0566, +0.2298, +0.1822, -0.0007, +0.0391, -0.1377, +0.0574,
+ +0.0774, -0.3464, +0.0214, -0.2252, -0.0265, -0.6877, +0.4879,
+ -0.4100, +0.2385
+ ],
+ [
+ +0.1236, +0.0376, -0.2100, +0.1883, +0.6826, +0.0220, -0.1377,
+ -0.5746, +0.2344, +0.0867, +0.0319, +0.0259, -0.2913, +0.0787,
+ +0.3157, -0.0364, -0.1010, +0.1857, -0.2598, -0.5244, -0.1616,
+ -0.2685, -0.0613, -0.1655, +0.0230, -0.9140, +0.1744, +0.1221,
+ -0.0847, +0.1691, +0.3710, -0.3452, -0.3138, +0.2219, +0.0426,
+ +0.2347, -0.1529, +0.1309, +0.0586, +0.4190, +0.2861, -0.2072,
+ +0.1766, -0.3183, -0.2827, +0.0666, +0.2583, -0.0261, -0.2540,
+ +0.0545, -0.6264, +0.0025, +0.4261, +0.0022, -0.0614, +0.3319,
+ +0.3828, -0.1452, -0.5253, -0.1200, +0.0946, -0.0143, +0.2909,
+ -0.0688, -0.0306, +0.0080, +0.0100, -0.1666, -0.5132, -0.0863,
+ +0.2882, -0.1029, -0.3055, +0.0813, -0.5334, +0.0466, -0.5523,
+ +0.2712, +0.1460, -0.2548, +0.0861, -0.4035, -0.0165, +0.3279,
+ +0.0435, -0.0565, -0.3307, +0.3140, +0.0406, -0.3739, +0.3179,
+ -0.0782, +0.1537, -0.0256, -0.0541, +0.2213, -0.0156, +0.0488,
+ +0.1589, -0.2548, +0.2501, -0.2476, -0.0498, +0.1194, -0.1299,
+ -0.1299, +0.0690, +0.1347, -0.2261, +0.0083, -0.5431, -0.0652,
+ -0.3608, -0.0647, -0.4625, -0.2278, -0.0067, +0.2591, -0.0100,
+ +0.1405, +0.1602, +0.1952, +0.2865, -0.1792, -0.2396, +0.2345,
+ -0.4069, -0.2045
+ ],
+ [
+ +0.1412, -0.0696, +0.2341, +0.0624, -0.0594, -0.2349, -0.1230,
+ -0.1535, +0.3358, -0.1074, -0.3703, -0.0583, +0.1001, +0.1808,
+ +0.1181, +0.0321, +0.0653, +0.2051, +0.2186, +0.2763, +0.2867,
+ -0.0883, -0.1351, +0.0331, +0.0249, +0.1005, +0.1122, -0.1683,
+ -0.3847, -0.0855, -0.0645, -0.0530, -0.4018, -0.1309, +0.3548,
+ +0.1746, -0.0786, -0.2527, -0.3668, -0.2196, +0.1073, +0.0013,
+ +0.1540, -0.1488, -0.2231, +0.2583, +0.0985, +0.1557, -0.0295,
+ +0.0735, +0.1870, +0.1670, +0.1750, +0.1122, +0.0238, -0.1360,
+ +0.0549, -0.0896, +0.3355, +0.0450, -0.1712, -0.0521, -0.0163,
+ +0.1979, -0.0057, +0.3001, +0.2147, +0.2500, +0.2662, +0.0464,
+ +0.2511, -0.6088, +0.1502, -0.2170, +0.1770, +0.2396, +0.0731,
+ -0.1072, -0.1218, -0.1094, +0.4303, +0.2937, +0.3561, -0.4019,
+ +0.1205, +0.2295, +0.2342, +0.6585, -0.0954, +0.2403, -0.0643,
+ +0.1362, -0.5167, +0.2533, -0.1717, -0.0405, -0.6613, -0.0652,
+ -0.0399, +0.1727, +0.2228, +0.1647, +0.2706, +0.1907, +0.1552,
+ +0.1832, +0.0371, -0.1880, +0.3491, -0.1936, +0.3391, -0.2626,
+ +0.0834, -0.0342, -0.0088, +0.3202, +0.3206, -0.1806, +0.0846,
+ +0.0579, -0.3797, +0.0252, -0.0016, -0.1575, -0.0163, -0.1510,
+ -0.2674, +0.5437
+ ],
+ [
+ -0.4375, +0.0691, +0.0132, -0.1952, +0.3240, -0.5280, -0.2317,
+ +0.0060, +0.0420, +0.0655, +0.1332, -0.1609, +0.6019, +0.3035,
+ -0.0744, +0.1198, +0.0335, +0.2761, +0.0182, +0.1792, -0.1436,
+ +0.2985, -0.1630, -0.0314, -0.3092, -0.3348, -0.4410, +0.4206,
+ -0.5009, -0.1961, -0.0061, +0.0646, +0.0028, -0.2830, +0.3189,
+ +0.1332, -0.6681, -0.3721, +0.1576, -0.2649, -0.2122, -0.3793,
+ -0.0257, +0.1096, -0.4736, -0.3285, -0.1774, +0.1045, -0.0412,
+ -0.1999, -0.0392, -0.1256, -0.4455, -0.1380, -0.0893, -0.0456,
+ -0.1794, +0.3297, -0.3258, -0.1020, -0.0237, +0.0481, -0.0306,
+ -0.3762, +0.0582, +0.1159, -0.6488, +0.1295, -0.5503, +0.2942,
+ -0.1794, +0.2656, -0.3145, +0.0916, -0.1934, -0.3004, -0.0553,
+ -0.1828, +0.1933, -0.1394, -0.4347, +0.0881, -0.0648, +0.4279,
+ -0.5049, -0.2819, -0.0962, -0.1774, -0.1217, +0.0309, +0.1803,
+ -0.5215, +0.0935, -0.0073, -0.0846, -0.3536, -0.1036, -0.0593,
+ -0.0982, +0.1005, -0.2521, -0.2301, -0.0937, +0.1199, +0.0164,
+ -0.1238, -0.0819, -0.1452, -0.2476, -0.2147, +0.2090, -0.3116,
+ +0.1075, +0.0734, -0.1381, +0.5389, -0.2394, -0.0474, -0.3343,
+ +0.3611, -0.1414, -0.2948, +0.2472, +0.0805, +0.1058, -0.2458,
+ -0.5851, -1.0465
+ ],
+ [
+ -0.0729, -0.0000, -0.5724, +0.0407, +0.0246, -0.0118, -0.1285,
+ -0.9905, +0.1176, +0.2563, -0.0043, -0.0942, +0.2825, -0.0513,
+ +0.2612, +0.1671, -0.4420, +0.1831, -0.1955, +0.4174, -0.4772,
+ +0.2477, -0.2401, -0.0887, -0.1148, -0.1394, +0.2506, -0.0922,
+ +0.0623, -0.2368, -0.1567, -0.1732, +0.0966, +0.3062, +0.0234,
+ -0.1121, +0.0395, +0.0600, -0.0824, +0.3137, +0.0234, +0.0647,
+ +0.3534, -0.2083, +0.2899, +0.0567, -0.1504, -0.0071, -0.1387,
+ +0.2099, -0.2346, -0.5326, +0.0601, -0.1498, +0.1787, +0.2529,
+ -0.0069, -0.2794, +0.2950, -0.1160, +0.1059, +0.0679, +0.1995,
+ -0.2776, +0.5507, -0.1011, -0.3149, -0.0066, +0.0007, -0.2899,
+ -0.2901, -0.0797, -0.5042, +0.0141, -0.1412, -0.1831, -0.1403,
+ +0.2004, -0.2061, -0.0208, -0.0286, -0.4134, +0.1362, +0.1245,
+ +0.1593, -0.5630, -0.1738, -0.2171, +0.4737, -0.1202, -0.2229,
+ +0.1831, +0.1676, -0.3322, -0.2468, -0.2791, -0.9385, +0.2221,
+ -0.1161, +0.0797, -0.0176, +0.0949, +0.3332, -0.2890, -0.1364,
+ +0.0956, +0.0007, -0.1070, -0.5448, -0.2041, +0.2900, +0.6012,
+ +0.0403, +0.3847, +0.0888, +0.0928, +0.2970, +0.0699, -0.1121,
+ -0.2804, +0.0752, +0.0984, -0.0516, +0.0121, -0.1547, +0.0065,
+ +0.0952, -0.6576
+ ],
+ [
+ -0.1941, +0.1027, -0.0436, +0.2440, -0.3934, +0.0835, +0.0386,
+ +0.4993, +0.3126, -0.2644, +0.0530, +0.0557, +0.2344, +0.2061,
+ +0.1085, -0.0502, -0.3185, +0.2997, +0.1358, -0.0412, -0.1765,
+ -0.0993, +0.2982, -0.0366, -0.1480, +0.0941, +0.1698, -0.0107,
+ +0.1538, -0.2916, -0.1777, +0.1294, -0.3267, -0.2505, +0.1930,
+ +0.4406, +0.1421, +0.1251, -0.1535, -0.5110, +0.2285, -0.5197,
+ -0.3456, -0.3984, -0.1507, +0.2693, -0.0057, +0.1237, +0.5077,
+ -0.5996, -0.0316, +0.0890, -0.1346, -0.0719, +0.5849, -0.0047,
+ -0.1471, -0.2270, -0.3822, -0.2037, +0.4138, -0.0996, +0.2080,
+ -0.0058, +0.1905, -0.1074, -0.0531, +0.1024, +0.0889, -0.1927,
+ +0.3300, +0.1352, -0.3513, -0.0935, +0.1051, +0.0342, +0.6585,
+ +0.2677, +0.0296, +0.1483, +0.0249, +0.0613, -0.0130, +0.1439,
+ -0.6456, -0.2417, +0.1079, +0.0304, -0.2229, -0.2422, -0.3059,
+ -0.2534, -0.0870, +0.0549, +0.5176, -0.2529, +0.2052, -0.4333,
+ +0.3257, -0.6656, +0.0274, -0.0220, +0.3784, +0.3136, +0.0937,
+ -0.2548, -0.0259, +0.4648, +0.0983, +0.0135, +0.0472, -0.0407,
+ +0.0268, -0.0681, -0.2091, +0.1238, -0.0575, -0.3694, +0.2273,
+ +0.2093, -0.0348, -0.1528, +0.1878, -0.3958, -0.0159, +0.0110,
+ +0.1729, +0.0470
+ ],
+ [
+ -0.1267, -0.3113, +0.1357, +0.1027, +0.2379, -0.0068, +0.4349,
+ -0.0623, -0.5615, -0.1304, +0.1250, -0.3323, +0.3609, +0.4355,
+ -0.2552, +0.3060, +0.0983, -0.0872, -0.0180, +0.1222, +0.0775,
+ -0.1083, +0.0396, -0.1034, -0.0120, -0.3544, +0.2029, -0.2021,
+ +0.2533, +0.2070, +0.1599, -0.0763, -0.2680, -0.0949, -0.2347,
+ -0.3042, -0.1092, -0.5819, +0.0953, -0.2701, -0.1846, -0.2815,
+ +0.0169, -0.1685, +0.3497, -0.4498, +0.1862, +0.2418, +0.2738,
+ -0.1878, -0.6743, -0.2682, +0.1436, +0.0281, -0.0953, +0.3988,
+ +0.0264, +0.2932, +0.0583, -0.1579, +0.6084, +0.2165, +0.5541,
+ -0.0631, +0.0807, -0.2303, +0.3342, -0.2916, -0.0861, +0.0810,
+ -0.1595, -0.4391, -0.2134, -0.1567, -0.5746, -0.2862, -0.0570,
+ -0.0424, -0.0724, +0.0939, -0.4046, -0.3838, -0.0559, +0.3115,
+ +0.2509, +0.1488, -0.2606, +0.1532, -0.1418, -0.1425, -0.3906,
+ -0.0388, -0.1576, +0.2442, +0.0740, -0.0508, -0.0483, +0.2111,
+ -0.2049, -0.2607, -0.4858, +0.2897, -0.0702, +0.0321, +0.0956,
+ -0.1905, -0.4853, +0.1617, +0.2493, -0.1314, -0.4004, -0.2519,
+ -0.4157, +0.0929, +0.0758, +0.3717, -0.0497, +0.3306, -0.1561,
+ +0.2532, +0.0411, -0.4520, +0.2099, +0.2967, +0.1842, +0.1563,
+ -0.1585, -0.1759
+ ],
+ [
+ -0.0254, -0.0619, +0.3396, -0.0740, -0.0445, -0.1535, +0.1428,
+ -0.3223, -0.3919, +0.4651, +0.0604, +0.0437, +0.0966, +0.1825,
+ -1.2489, -0.0932, +0.4027, -0.2825, -0.1588, -0.4097, -0.0175,
+ -0.0916, +0.1347, -0.2389, +0.4690, +0.1414, -0.3526, +0.0226,
+ -0.3026, -0.0544, -0.6268, +0.2633, +0.1651, -0.4040, -0.1251,
+ +0.3515, +0.4103, -0.4826, +0.0880, +0.1935, -0.2374, +0.1883,
+ +0.2930, -0.0785, +0.0563, -0.2351, +0.1083, +0.0530, -0.4314,
+ +0.3210, +0.3915, +0.3193, +0.3019, +0.2164, -0.0151, -0.0877,
+ +0.2483, +0.0276, +0.2023, -0.5203, +0.2165, -0.5460, -0.6132,
+ -0.3681, +0.5059, -0.8269, -0.5508, -0.7987, -0.4734, +0.3606,
+ -0.0343, -0.4660, +0.2890, +0.1699, -0.0946, +0.1705, +0.1884,
+ +0.5705, -0.6233, +0.1696, +0.1865, +0.1485, +0.3090, +0.1678,
+ -0.2003, +0.4189, -0.6977, -0.4489, -0.2648, +0.3523, +0.0024,
+ -0.0019, -0.4196, +0.6541, +0.0061, -0.1462, +0.2370, +0.3574,
+ +0.0846, -0.0241, +0.4114, -0.3442, -0.4623, -0.2267, +0.2023,
+ -0.3360, +0.0956, +0.0317, +0.1955, -0.1893, -0.0042, +0.4674,
+ -0.1063, -0.1893, -0.2424, +0.2492, -0.1736, +0.3326, +0.2834,
+ +0.5649, -0.3040, -0.0840, -0.3259, -0.0314, -0.3128, -0.0751,
+ +0.0886, +0.2745
+ ],
+ [
+ -0.0964, +0.0265, -0.0213, -0.1072, +0.1414, -0.2006, -0.1852,
+ -0.0680, -0.3082, -0.0446, +0.0275, +0.2967, +0.3372, +0.3806,
+ -0.3462, -0.0765, +0.3793, -0.1660, -0.1671, +0.1254, +0.0304,
+ +0.2077, +0.1840, -0.0107, -0.5985, +0.0081, +0.3911, -0.0964,
+ -0.0192, -0.3845, -0.1633, +0.0627, +0.1709, -0.5199, -0.0662,
+ +0.2973, -0.0476, -0.0106, +0.2571, -0.4352, -0.0863, -0.0472,
+ +0.0214, -0.1154, -0.7335, +0.0613, -0.0339, +0.1994, +0.1911,
+ +0.2564, -0.0221, -0.1719, -0.0692, +0.1077, +0.0255, +0.2926,
+ +0.2895, -0.2671, +0.0639, -0.0263, +0.1419, +0.0450, -0.1025,
+ -0.0003, +0.0131, +0.0963, -0.0279, -0.1671, -0.3886, -0.2855,
+ +0.0036, +0.1207, +0.0048, -0.2887, +0.0294, -0.2211, +0.3091,
+ -0.0269, +0.0516, -0.6725, +0.3413, -0.1767, +0.1770, -0.0460,
+ -0.2211, -0.2099, +0.0021, -0.1276, -0.0644, +0.1490, -0.1115,
+ +0.2595, -0.3224, -0.4780, +0.0815, -0.5460, -0.0702, -0.3853,
+ -0.0679, -0.1372, -0.0327, +0.1929, -0.3156, -0.2680, +0.3684,
+ -0.4465, -0.1663, +0.1810, -0.1622, -0.0172, +0.0767, +0.0161,
+ -0.1824, +0.4669, -0.5076, -0.2199, -0.0133, +0.3653, +0.2747,
+ -0.0800, -0.3138, -0.0949, +0.2533, -0.0900, +0.1011, +0.2880,
+ +0.1251, -0.1881
+ ],
+ [
+ -0.0063, +0.1103, -0.1303, -0.0870, +0.0031, -0.2372, -0.1525,
+ -0.1338, -0.1362, -0.1119, -0.2048, -0.5003, -0.4117, -0.1900,
+ +0.2692, +0.0322, -0.2947, -0.0933, +0.4165, -0.1908, -0.2739,
+ -0.2490, +0.0153, +0.2060, -0.3180, -0.0127, -0.2742, -0.6272,
+ +0.1028, +0.0392, +0.0631, +0.4220, -0.0728, -0.0180, +0.0193,
+ +0.2475, -0.4501, -0.2177, +0.0264, -0.3409, -0.1080, +0.1319,
+ +0.2073, -0.1404, -0.1683, +0.0385, +0.4418, -0.0943, +0.3003,
+ -0.4947, -0.3381, +0.0047, -0.1739, +0.0727, -0.0840, -0.0679,
+ -0.6355, -0.1313, -0.5041, +0.1045, +0.5695, +0.3238, +0.1534,
+ -0.0200, -0.4393, -0.0425, -0.1652, +0.0850, -0.2406, -0.2257,
+ +0.0294, +0.4809, -0.2471, -0.0967, +0.2424, -0.5018, -0.2205,
+ -0.1493, +0.0341, -0.1234, -0.1192, -0.5870, -0.2536, -0.1993,
+ -0.1386, +0.0683, -0.3497, +0.0733, +0.2698, -0.1142, -0.0668,
+ +0.1648, -0.3611, -0.0740, -0.3633, +0.4252, -0.2167, -0.1510,
+ +0.0723, +0.1177, -0.1335, -0.0920, +0.1246, +0.0240, -0.1628,
+ +0.3220, +0.2826, +0.1347, -0.3111, -0.1399, -0.2744, -0.2070,
+ -0.0708, +0.0089, -0.2029, -0.2701, +0.0167, +0.2531, +0.0292,
+ +0.5538, +0.5037, -0.0892, -0.1198, -0.1806, -0.1155, +0.0682,
+ +0.0992, +0.1278
+ ],
+ [
+ -0.3892, -0.4112, +0.0692, -0.0743, +0.0754, +0.1185, -0.1115,
+ +0.0526, -0.1577, -0.3541, -0.1263, -0.0474, -0.5270, -0.1722,
+ -0.5393, +0.3133, +0.2965, -0.0296, +0.1989, -0.2590, +0.0554,
+ +0.0375, +0.1727, -0.8208, -0.0429, -0.1936, +0.1494, -0.1485,
+ +0.2725, -0.1334, -0.1841, +0.3110, -0.2692, -0.8445, +0.1759,
+ +0.1046, -0.0473, -0.2881, -0.0947, +0.0488, -0.1750, -0.1608,
+ +0.0893, +0.1647, -0.5554, -0.2797, -0.7124, -0.6744, -0.2102,
+ +0.1397, +0.0133, +0.1617, -0.1435, +0.0960, -0.1028, -0.0140,
+ -0.0536, -0.1890, +0.2581, -0.2165, -0.1061, -0.1182, +0.2503,
+ +0.5655, -0.3958, +0.0204, +0.2095, +0.3389, -0.1195, +0.0742,
+ +0.3064, -0.4154, -0.0185, +0.2993, -0.4896, -0.4842, +0.0000,
+ +0.2412, +0.1470, +0.2875, -0.0558, -0.3003, -0.1561, +0.2015,
+ -0.4600, +0.2405, -0.5617, +0.0419, +0.0919, -0.0401, -0.1036,
+ -0.4643, -0.3563, +0.0631, +0.2055, +0.1592, +0.4003, -0.1694,
+ +0.0298, +0.0438, +0.0447, +0.1505, +0.2846, -0.2341, +0.2087,
+ +0.0529, +0.1660, -0.2887, -0.4005, -0.0296, -0.2068, -0.0832,
+ -0.1425, -0.0368, -0.0351, +0.2398, -0.0911, -0.1891, -0.7638,
+ -0.0778, -0.1400, -0.1751, -0.3126, +0.1764, -0.0813, -0.2103,
+ -0.2434, +0.0032
+ ],
+ [
+ -0.0357, -0.2668, -0.1127, +0.0598, +0.2980, -0.0779, +0.1944,
+ -0.2414, +0.1748, +0.1547, -0.1568, +0.3791, -0.1141, -0.5528,
+ +0.0845, +0.0841, -0.6744, +0.1313, -0.2061, +0.1047, +0.1434,
+ -0.1319, -0.2199, -0.0972, -0.0120, -0.0425, -0.3748, +0.1776,
+ +0.1601, -0.0042, +0.2022, -0.3657, +0.1848, -0.0978, -0.1360,
+ +0.0169, -0.1384, +0.0957, -0.2801, +0.3112, -0.3811, -0.1796,
+ -0.1115, -0.1707, -0.2593, +0.1178, -0.1374, +0.1978, -0.4550,
+ +0.1624, -0.7096, +0.0412, +0.2822, -0.1694, -0.1609, +0.2064,
+ -0.0363, -0.1055, -1.1760, -0.0517, +0.3019, -0.1031, -0.0140,
+ +0.4577, -0.2882, -0.0930, -0.0780, +0.1255, -0.0155, +0.0442,
+ +0.1144, -0.0569, -0.3376, -0.0483, +0.0346, -0.4206, -0.0416,
+ +0.3018, -0.1322, +0.1616, -0.4345, -0.8509, +0.4203, -0.1752,
+ +0.4466, +0.0259, +0.2046, -0.1646, +0.1396, +0.0633, +0.2265,
+ +0.0700, -0.0138, -0.1109, -0.7053, -0.0275, +0.0227, +0.0829,
+ -0.4602, -0.2059, -0.1101, +0.1778, -0.3476, +0.2725, -0.6471,
+ -0.8565, -0.1445, +0.0229, -0.0902, -0.0000, +0.1050, +0.1833,
+ +0.0342, +0.1775, +0.1618, -0.1348, +0.2888, -0.1435, -0.3121,
+ -0.0145, -0.0838, +0.1918, -0.0012, +0.2892, +0.0822, -0.3897,
+ -0.1889, +0.3133
+ ],
+ [
+ +0.0687, -0.1425, -0.2918, -0.0124, -0.1191, +0.5113, -0.0458,
+ -0.2026, +0.1903, -0.2631, -0.1719, -0.0891, +0.1167, -0.4310,
+ +0.1749, +0.0637, -0.2985, +0.0289, +0.0650, +0.0673, -0.2936,
+ -0.1160, +0.0858, +0.1307, -0.3330, -0.8444, +0.4467, +0.2170,
+ +0.0191, +0.2063, +0.3432, +0.3044, +0.1887, -0.0953, +0.1251,
+ +0.2465, -0.0316, -0.1012, +0.3532, -0.0733, -0.5563, +0.0876,
+ -0.0479, +0.2727, -0.1127, -0.0031, +0.2553, +0.2084, -0.1991,
+ +0.0461, +0.2093, -0.1241, -0.1590, -0.2749, -0.3333, +0.2033,
+ -0.5573, +0.0258, -0.0032, +0.0843, -0.1145, +0.2153, +0.1418,
+ -0.1910, -0.0054, +0.0351, +0.1492, +0.3882, -0.0541, -0.3486,
+ -0.2434, -0.2268, +0.3660, +0.1080, -0.3659, +0.0102, -0.1396,
+ -0.1952, +0.0272, -0.2913, -0.3832, -0.0728, -0.3145, +0.0215,
+ -0.4121, -0.3307, +0.4352, -0.0253, -0.0588, +0.0272, -0.1483,
+ +0.1393, -0.0073, +0.1142, -0.0115, +0.1358, -0.1048, -0.1909,
+ +0.1376, +0.2979, -0.5140, -0.0762, +0.0734, -0.2475, +0.1982,
+ +0.1673, -0.0969, -0.0437, -0.3698, -0.1260, +0.0262, +0.0649,
+ +0.4337, -0.1104, -0.1702, -0.0254, +0.0276, +0.1572, -0.1630,
+ -0.0185, +0.0140, -0.0844, +0.2117, +0.0716, +0.0515, -0.0174,
+ -0.6157, -0.0414
+ ],
+ [
+ +0.4181, -0.1027, -0.5953, -0.2716, +0.0776, +0.0781, -0.5109,
+ +0.1030, +0.2771, -0.0260, +0.0929, -0.2771, -0.4549, +0.0623,
+ -0.3257, -0.0775, +0.1166, +0.1562, -0.0574, +0.3033, +0.1967,
+ -0.0404, +0.0676, -0.0867, -0.3187, -0.0758, -0.0009, -0.0113,
+ -0.0341, +0.0605, -0.4264, -0.6552, +0.1799, +0.0700, -0.0374,
+ -0.0114, -0.1146, +0.0999, -0.0757, -0.1578, +0.1074, +0.3107,
+ +0.1008, +0.1590, +0.1258, -0.0781, -0.1203, -0.0616, +0.3600,
+ +0.0990, -0.2904, +0.1173, +0.1832, -0.0751, -0.1231, +0.1683,
+ -0.0037, -0.2329, +0.1468, +0.0243, -0.1334, -0.0890, +0.0893,
+ -0.1151, -0.2679, +0.0001, +0.2118, +0.1272, -0.1189, -0.0188,
+ -0.3389, +0.4803, -0.0542, -0.0435, +0.2108, -0.0349, +0.0001,
+ -0.1910, +0.2580, +0.1186, +0.0134, +0.2241, +0.1215, +0.0804,
+ +0.1249, -0.4045, -0.7299, +0.2040, +0.1098, +0.1849, -0.2002,
+ -0.3071, +0.3402, +0.0603, -0.4271, -0.0413, -0.1134, -0.1907,
+ -0.0385, -0.1099, -0.2834, -0.2318, -0.0175, +0.1223, +0.0880,
+ -0.1988, -0.1323, +0.0046, -0.2709, -0.2632, -0.1952, +0.0714,
+ -0.2587, +0.0643, -0.4457, -0.0552, +0.1938, +0.0585, +0.3212,
+ -0.1974, +0.1730, -0.0263, +0.0388, +0.0617, +0.2161, -0.1703,
+ +0.1905, +0.2715
+ ],
+ [
+ +0.0930, +0.1679, +0.2751, -0.1692, -0.1356, +0.2604, +0.0225,
+ +0.1217, -0.2549, -0.3477, +0.2173, -0.3041, -0.1303, -0.0979,
+ +0.2413, -0.7162, -0.1729, -0.0653, +0.0465, +0.2631, +0.1323,
+ +0.0231, -0.0955, -0.4612, +0.1609, -0.2387, -0.1092, +0.2000,
+ -0.4562, -0.0711, -0.0483, +0.3552, +0.0795, +0.1893, -0.6706,
+ +0.0193, +0.0274, +0.2531, +0.2990, +0.2438, +0.0986, -0.1109,
+ -0.2137, +0.4588, +0.3006, -0.3244, -0.3664, +0.2272, -0.1332,
+ +0.0289, -0.2323, +0.0689, +0.1008, -0.5734, +0.0855, +0.0575,
+ +0.2418, -0.0182, -0.4540, -0.2439, +0.0172, -0.4748, -0.1435,
+ +0.0309, +0.0632, -0.2346, +0.2038, -0.0480, -0.7751, -0.0894,
+ +0.0641, +0.1264, -0.1953, -0.0275, -0.3926, +0.1423, +0.2923,
+ +0.1021, +0.1765, -0.1492, -0.1441, -0.0768, -0.1498, +0.1910,
+ +0.1953, -0.2800, -0.1201, -0.0883, +0.2172, +0.3554, -0.1773,
+ -0.4483, -0.3244, -0.1744, -0.3018, -0.2011, -0.2264, -0.0428,
+ +0.0575, +0.0580, -0.5973, +0.1492, -0.0185, +0.1127, -0.1138,
+ -0.0385, +0.2036, +0.2093, +0.0063, -0.1820, -0.1950, +0.0582,
+ -0.3649, +0.3262, +0.1356, -0.0211, +0.0755, +0.2815, -0.3010,
+ +0.0102, -0.0880, +0.0170, +0.2470, -0.2187, -0.3712, +0.1006,
+ +0.1422, +0.0947
+ ],
+ [
+ +0.3506, -0.4573, +0.0702, -0.0522, +0.0911, +0.3024, +0.0056,
+ -0.2354, -0.0218, +0.0672, +0.2162, -0.2104, -0.5043, +0.2148,
+ -0.0611, +0.2639, -0.3746, -0.1468, +0.2605, -0.0543, +0.2585,
+ +0.3026, -0.2448, +0.0680, +0.3110, -0.3245, -0.0491, +0.0020,
+ -0.2954, +0.1172, +0.0233, -0.1470, -0.1321, +0.2758, -0.0839,
+ -0.0035, +0.2861, -0.2431, +0.1937, +0.1139, -0.5602, -0.4088,
+ -0.1855, -0.9253, +0.0596, -0.0578, -0.2868, +0.1480, +0.2077,
+ -0.0143, -0.0022, -0.0470, +0.2199, +0.0734, +0.1023, -0.1480,
+ +0.1836, +0.3319, -0.1966, -0.0147, +0.0555, +0.0199, -0.2619,
+ +0.1983, -0.0588, -0.5989, -0.3336, +0.0868, +0.1067, -0.2179,
+ -0.3378, +0.1768, +0.3373, +0.3508, -0.2344, +0.0236, -0.1659,
+ +0.2833, -0.5192, -0.2062, -0.0494, +0.2147, +0.0610, +0.2614,
+ +0.0845, +0.5961, +0.1163, +0.3691, +0.1669, -0.2602, -0.1245,
+ -0.1340, -0.1114, -0.6348, -0.2305, +0.3599, +0.0009, +0.0564,
+ -0.1984, +0.2478, +0.0851, -0.4090, +0.0749, -0.1386, +0.1885,
+ -0.2480, -0.1254, -0.1255, +0.0577, -0.0142, +0.0102, -0.4250,
+ +0.2373, -0.3827, -0.0171, -0.1978, -0.2941, +0.2472, -0.2591,
+ -0.6289, +0.4534, -0.2792, -0.4134, +0.1043, +0.2448, -0.1319,
+ -0.1174, -0.1580
+ ],
+ [
+ -0.2358, +0.2350, -0.3523, +0.2959, -0.0367, -0.0344, -0.3328,
+ +0.4840, -0.3630, +0.1661, +0.1186, -0.2251, +0.0232, +0.2081,
+ -0.0328, -0.0450, -0.2070, +0.5389, +0.1277, -0.4275, -0.2921,
+ +0.1255, -0.4076, +0.2065, +0.2672, +0.2073, -0.0296, -0.4819,
+ +0.2005, +0.0445, +0.0668, +0.0876, +0.3081, -0.3881, -0.0585,
+ -0.6874, -0.0974, -0.0301, +0.1855, +0.3814, +0.1201, +0.1938,
+ -0.0995, +0.0912, -0.6631, +0.2574, -0.0729, +0.3474, -0.0604,
+ -0.3329, -0.0358, -0.9523, -0.4813, -0.3228, -0.4234, -0.4660,
+ -0.1092, -0.0337, +0.1697, -0.2094, -0.1469, +0.2326, -0.5977,
+ +0.0475, -0.3922, -0.4437, -0.3288, +0.3193, -0.7914, -0.0176,
+ +0.0502, -0.0523, -0.2862, -0.2429, -0.1000, +0.4249, -0.3641,
+ +0.1861, +0.1024, +0.0054, -0.2030, -0.0398, -0.2410, -0.3862,
+ -0.2337, -0.0892, -0.3876, -0.0436, +0.1507, -0.0999, -0.3943,
+ -0.9435, +0.5505, +0.1834, -0.0167, -0.0586, +0.0693, +0.1642,
+ -0.5236, -0.1637, +0.1487, -0.8338, -0.0206, +0.2822, -0.2105,
+ -0.0160, +0.3280, -0.1025, -0.3180, -0.3722, +0.0884, -0.2718,
+ +0.0536, -0.2959, -0.3745, -0.2457, +0.0991, -0.4547, +0.4061,
+ +0.0624, -0.0080, -0.1087, +0.2008, -0.1034, -0.0891, -0.6337,
+ +0.3613, -0.0931
+ ],
+ [
+ -0.6200, -0.1166, -0.4242, +0.3230, +0.0424, +0.1713, -0.0952,
+ -0.1583, -0.1884, -0.1920, +0.2690, +0.0879, +0.3036, -0.2299,
+ +0.1667, -0.0614, +0.1718, +0.4005, -0.0414, -0.2480, -0.0757,
+ +0.0657, -0.5465, -0.0342, -0.3754, -0.0016, -0.2577, -0.1944,
+ -0.4532, +0.3159, +0.2805, +0.0208, +0.3891, +0.4252, -0.1674,
+ -0.1789, -0.6264, +0.2770, +0.2155, -0.0509, -0.0612, -0.0500,
+ -0.3067, +0.1948, +0.2282, +0.1876, -0.2081, +0.0926, +0.2432,
+ -0.1317, +0.2425, -0.3167, +0.1566, +0.2607, -0.1562, -0.5820,
+ +0.2781, +0.2699, -0.0476, -0.2564, +0.5402, +0.1399, -0.0323,
+ -0.2961, +0.1806, +0.1641, +0.3719, +0.0294, -0.0031, +0.0016,
+ -0.0585, -0.4079, +0.3304, +0.1999, -0.3924, +0.0346, +0.0155,
+ -0.4827, +0.1847, -0.1982, -0.1880, -0.1174, +0.4202, -0.1538,
+ +0.3898, -0.3270, +0.2266, +0.0189, +0.0172, -0.0131, +0.4387,
+ +0.0762, +0.1472, +0.0556, -0.3252, -0.2261, +0.0449, +0.2520,
+ +0.0344, -0.2504, -0.3314, +0.2278, +0.1001, -0.0899, -0.0822,
+ -0.2645, -0.1534, -0.3389, -0.2310, -0.1803, -0.0725, -0.1741,
+ -0.2782, +0.0120, +0.0663, -0.1420, +0.1000, +0.0580, +0.2736,
+ -0.0962, -0.1784, +0.0454, +0.1217, -0.1503, -0.1855, -0.0065,
+ -0.2237, -0.1836
+ ],
+ [
+ -0.3115, -0.1903, +0.5137, -0.1865, +0.4864, +0.2623, -0.0747,
+ -0.0819, -0.0157, -0.6871, -0.0296, -0.3034, -0.2566, +0.1559,
+ -0.5077, -0.5202, +0.0065, +0.0832, -0.4281, +0.0602, +0.1776,
+ +0.0249, -0.3248, -0.5189, -0.5201, +0.2417, -0.4212, +0.0878,
+ -0.2480, -0.7528, -0.1374, +0.2482, -0.0171, +0.3787, -0.1415,
+ -0.0652, +0.2193, -0.5248, +0.1414, -0.1371, -0.2108, +0.1232,
+ -0.0979, +0.2075, -0.5518, -0.1070, +0.0641, +0.3360, +0.3089,
+ +0.2055, -0.2662, +0.0075, -0.1935, +0.0715, +0.2552, +0.3614,
+ -0.1943, -0.3510, +0.3832, +0.0128, +0.0049, -0.0661, -0.3146,
+ -0.1168, -0.0349, -0.0030, -0.1232, +0.1852, -0.1332, -0.0373,
+ +0.0300, -0.0487, -0.1961, +0.1165, +0.0229, +0.0938, +0.1951,
+ -0.2836, -0.0792, -0.0472, -0.2475, -0.5654, +0.1948, +0.2359,
+ +0.0157, +0.1590, +0.0085, -0.1436, +0.1589, +0.0345, +0.0138,
+ -0.1086, -0.0469, +0.1021, +0.1436, +0.2495, -0.0120, -0.0850,
+ -0.0485, -0.1638, +0.1941, +0.0767, -0.0602, +0.5445, -0.5856,
+ -0.0649, +0.0954, -0.4362, -0.1760, -0.0305, +0.1229, -0.2425,
+ +0.3525, -0.1718, +0.2081, +0.2920, +0.2802, -0.1463, -0.0372,
+ +0.2798, +0.1410, -0.2971, -0.0625, +0.2547, -0.4261, -0.0709,
+ -0.1671, +0.0714
+ ],
+ [
+ -0.2103, -0.0272, +0.3673, -0.4027, -0.4165, -0.3775, -0.2740,
+ -0.4518, +0.3899, -0.1959, +0.3833, -0.2781, -0.0257, -0.2010,
+ -0.3744, +0.1185, +0.0154, +0.0608, -0.1520, +0.3193, -0.1784,
+ -0.1706, -0.5693, +0.0589, +0.1819, -0.2368, +0.0002, -0.1581,
+ +0.1174, -0.3442, +0.0262, -0.5463, +0.4174, -0.1503, -0.3037,
+ +0.1006, -0.0416, +0.2902, -0.0367, -0.5241, +0.1610, +0.5887,
+ +0.2866, +0.1434, +0.0395, +0.1180, -0.0736, +0.3131, -0.2578,
+ -0.4074, -0.6594, +0.1505, -0.5157, +0.2380, -0.0458, -0.2018,
+ -0.0282, +0.3315, -0.1138, -0.3608, -0.0223, +0.2218, -0.2358,
+ +0.2699, -0.7728, +0.2867, -0.2453, -0.5425, -0.1967, -0.0232,
+ +0.2375, -0.4524, +0.4034, +0.0560, -0.2659, -0.0520, +0.1507,
+ -0.2088, -0.0948, +0.4523, +0.2961, -0.2171, -0.3837, -0.3430,
+ -0.0439, +0.4376, +0.1247, +0.1549, +0.3201, -0.2246, +0.0722,
+ -0.1387, -0.2841, -0.3820, +0.2112, +0.1155, +0.0457, +0.0849,
+ +0.0496, +0.2000, +0.3528, +0.1513, +0.2789, -0.5787, -0.0106,
+ -0.0224, -0.3136, -0.2720, -0.3962, +0.2735, +0.2201, -0.4635,
+ -0.2667, +0.3799, +0.0482, -0.3243, +0.2503, -0.1961, +0.2931,
+ -0.0249, -0.6142, +0.3921, -0.0819, +0.1537, +0.1795, -0.4286,
+ +0.3890, +0.0782
+ ],
+ [
+ -0.0876, +0.0339, +0.1373, +0.1845, +0.1049, -0.2126, +0.4155,
+ -0.2267, -0.1016, -0.3701, -0.2024, -0.6001, +0.1107, +0.1237,
+ -0.0572, -0.2163, -0.0753, -0.2021, +0.0705, -0.1143, -0.0157,
+ -0.3309, +0.3900, +0.0826, +0.0106, +0.2930, +0.0136, -0.8255,
+ +0.0238, -0.3730, -0.0691, +0.0495, -0.1372, +0.0351, +0.1440,
+ -0.1097, -0.6328, -0.2164, -0.1182, +0.1412, +0.0829, +0.2616,
+ -0.0581, +0.2463, +0.0033, +0.1873, +0.1287, +0.0292, -0.0618,
+ +0.4194, -0.0114, +0.3800, +0.4085, +0.2023, +0.1349, -0.4039,
+ +0.0351, -0.1197, +0.3388, +0.0180, +0.0524, +0.3924, -0.5456,
+ +0.3426, +0.0286, -0.1759, -0.0984, -0.0918, -0.0875, -0.0735,
+ -0.1989, -0.2863, -0.0470, -0.0234, -0.0645, -0.3891, -0.0790,
+ -0.1388, -0.2737, -0.6725, -0.1225, +0.2987, +0.5457, -0.1536,
+ -0.1787, +0.0739, -0.2458, -0.2498, +0.0537, +0.4109, -0.1707,
+ -0.2982, -0.3935, -0.3520, -0.0815, -0.2821, -0.4165, -0.0681,
+ -0.1594, +0.0789, -0.2301, +0.0582, -0.1564, +0.2033, +0.0964,
+ +0.2820, -0.1194, +0.0914, +0.0025, +0.3850, +0.0008, -0.6762,
+ +0.0372, -0.2743, -0.0836, +0.0765, -0.3693, +0.1311, +0.0767,
+ -0.4189, -0.1969, +0.1716, -0.2014, -0.1836, +0.0086, -0.5796,
+ -0.1696, -0.2689
+ ],
+ [
+ -0.5652, -0.0070, -0.2653, -0.2943, +0.2439, +0.1118, +0.0728,
+ -0.0968, -0.3874, -0.2193, +0.4227, -0.4908, -0.1880, -0.3136,
+ +0.0948, +0.2156, +0.6100, +0.2064, +0.1879, +0.1478, +0.0360,
+ -0.0379, -0.2390, +0.0572, +0.2056, -0.1321, -0.0847, -0.3560,
+ +0.1960, +0.1519, -1.1702, +0.1798, +0.0549, +0.3503, -0.1306,
+ +0.1877, -0.5265, -0.3751, -0.1159, +0.1669, +0.3965, +0.1393,
+ +0.0249, -0.1329, -0.0147, -0.0055, -0.0215, -0.2642, -0.4214,
+ -0.1231, -0.3051, -0.0133, +0.0672, -0.2792, -0.2496, +0.0984,
+ +0.4932, +0.3534, +0.0042, -0.1074, +0.2071, +0.0513, -0.4839,
+ -0.2368, -0.1557, +0.0947, -0.0207, -0.6396, +0.0899, -0.0886,
+ -0.1305, +0.2177, -0.0290, +0.1537, -0.3355, +0.2742, -0.2478,
+ -0.1225, -0.2504, -0.0776, +0.0167, +0.3300, +0.3200, +0.2386,
+ +0.4581, +0.0562, -0.0332, +0.0560, +0.1136, +0.2801, +0.0391,
+ +0.2024, +0.2941, +0.0766, -0.1749, +0.2298, +0.1376, -0.0507,
+ +0.0268, +0.0475, -0.3004, +0.2160, -0.0062, -0.2329, +0.0377,
+ -0.2296, +0.0611, +0.1093, +0.3586, -0.2859, -0.2399, +0.6020,
+ -0.3755, -0.0461, +0.1298, -0.5961, -0.3126, +0.1551, +0.1396,
+ -0.4280, +0.3916, +0.0049, -0.3861, +0.1474, -0.2064, +0.1811,
+ -0.2898, -0.2750
+ ],
+ [
+ +0.0819, +0.3396, +0.6644, -0.4791, +0.4484, +0.3738, +0.3009,
+ +0.4245, -0.0692, +0.1020, -0.1339, +0.4104, +0.0893, -0.3633,
+ +0.3444, -0.0436, +0.3646, +0.0856, -0.0671, -0.1069, +0.0030,
+ -0.1021, +0.5561, -0.4046, +0.1399, -0.2609, +0.1563, -0.1875,
+ +0.0044, +0.5717, -0.4551, +0.1222, -0.1040, +0.2842, +0.0044,
+ +0.3571, +0.2629, -0.5173, -0.3387, +0.0044, -0.0539, -0.1107,
+ +0.1069, -0.1870, -0.0774, +0.3390, -0.1788, +0.3467, -0.0369,
+ -0.1703, +0.0261, -0.7276, -0.0712, +0.0393, +0.0690, +0.1008,
+ -0.2375, +0.4717, -0.0653, -0.1273, +0.3284, -0.1475, +0.3745,
+ +0.3026, +0.2293, +0.1274, +0.1661, -0.2018, +0.0311, -0.0159,
+ +0.1497, +0.2360, -0.2298, -0.2898, -0.3821, -0.2285, +0.0855,
+ -0.2077, -0.4727, +0.0609, +0.1613, +0.2449, -0.0503, +0.1121,
+ +0.0116, +0.1638, -0.2348, -0.0742, -0.1956, +0.5764, -0.1819,
+ -0.1925, -0.1747, +0.0106, +0.3059, -0.7939, -0.3273, -0.0173,
+ +0.0771, -0.4543, -0.1425, -0.1515, +0.0516, +0.1927, +0.4261,
+ +0.2317, -0.2900, -0.4359, -0.2398, +0.2765, +0.0672, +0.1524,
+ -0.3440, -0.0897, +0.0850, +0.4672, -0.5525, -0.1277, -0.2299,
+ +0.5013, +0.2990, +0.1097, +0.1777, -0.0779, +0.2859, +0.0094,
+ -0.4870, -0.2335
+ ],
+ [
+ +0.1106, -0.2441, -0.0207, -0.2220, -0.3689, -0.1634, +0.0828,
+ -0.2131, -0.0443, +0.2476, -0.0322, -0.4817, -0.1937, +0.1710,
+ +0.2099, +0.1598, -0.6755, -0.1558, -0.1531, +0.1499, -0.2008,
+ -0.4290, +0.1572, +0.1114, +0.2724, +0.1565, -0.1044, -0.1196,
+ +0.1873, +0.3075, -0.0485, +0.4471, -0.1237, +0.4092, -0.0991,
+ +0.1165, +0.1534, -0.0387, -0.0965, +0.5520, +0.2848, +0.0698,
+ +0.0140, +0.0168, -0.1516, -0.0396, -0.5690, +0.3673, -0.2028,
+ +0.2079, +0.3912, -0.2749, +0.0421, +0.0121, -0.1195, +0.2930,
+ -0.5744, -0.0266, -0.3280, -0.2039, -0.6046, -0.0557, +0.1329,
+ +0.2431, +0.2108, -0.6411, +0.2877, +0.2222, +0.0724, +0.2789,
+ +0.0077, +0.2311, -0.3908, -0.1828, +0.0685, -0.0765, -0.1263,
+ -0.2053, +0.3030, +0.0021, -0.3130, +0.4412, +0.4471, +0.1203,
+ -0.4419, -0.0044, +0.0231, +0.1777, -0.1182, +0.4016, -0.0836,
+ -0.3208, -0.2156, +0.1623, -0.0150, -0.0775, +0.0234, +0.0310,
+ -0.1058, +0.2323, -0.3849, -0.5044, -0.3593, -0.2442, +0.1562,
+ +0.1421, -0.1440, +0.2766, -0.2231, -0.1259, -0.0108, -0.0871,
+ -0.0337, +0.0278, +0.1841, -0.0910, -0.2078, +0.1710, -0.1523,
+ +0.6016, +0.1046, -0.1343, -1.1743, +0.1045, +0.1077, +0.0598,
+ +0.2469, +0.1028
+ ],
+ [
+ -0.0543, -0.0520, -0.0337, -0.0404, +0.1425, +0.1348, +0.3168,
+ -0.2588, -0.2536, -0.1804, +0.0513, -0.2466, +0.2413, -0.0143,
+ -0.0072, +0.2906, +0.6229, -0.1328, -0.2948, -0.0062, -0.0023,
+ +0.2968, -0.1129, -0.1713, +0.0827, -0.0985, +0.0373, +0.3027,
+ -0.1809, -0.0222, +0.0336, +0.1493, +0.1600, -0.2339, +0.2103,
+ -0.2994, +0.0029, -0.0231, -0.2620, +0.0599, +0.1202, -0.2858,
+ +0.3041, -0.1582, -0.0641, -0.2478, -0.2629, -0.9977, +0.1291,
+ -0.4405, -0.1031, -0.2489, -0.1969, -0.0879, -0.4210, +0.0992,
+ +0.0513, -0.3871, -0.1446, +0.3532, +0.2695, +0.5117, +0.1277,
+ -0.6634, -0.6091, +0.2715, -0.1133, +0.1093, -0.1494, +0.0243,
+ -0.7959, -0.3742, +0.4444, +0.2359, +0.4380, +0.0365, +0.0249,
+ -0.2143, -0.5784, +0.3612, +0.2995, -0.2671, -0.0836, -0.1842,
+ -0.1041, -0.0031, -0.0125, +0.2039, +0.0862, -0.3960, +0.3796,
+ +0.3519, -0.1025, -0.2369, -0.4241, -0.0101, -0.1784, +0.1087,
+ +0.1407, +0.0627, +0.0779, +0.0970, +0.2389, -0.1938, -0.1186,
+ +0.0217, -0.4346, -0.1634, -0.2502, -0.0890, -0.3465, +0.2362,
+ +0.1421, +0.2332, -0.3333, -0.1481, +0.3306, -0.0235, +0.0863,
+ +0.1138, -0.2944, -0.1774, -0.2728, +0.0228, -0.3492, -0.0211,
+ -0.2253, +0.2095
+ ],
+ [
+ -0.5031, -0.0106, -0.5764, +0.2997, +0.0455, -0.2089, -0.0262,
+ +0.1678, +0.0179, +0.0361, -0.0682, -0.2984, -0.7560, -0.4558,
+ +0.1347, -0.1037, -0.2825, +0.1499, +0.1365, +0.3642, -0.6386,
+ +0.1581, -0.4962, +0.3903, -0.1766, +0.2820, -0.0779, -0.1685,
+ -0.2023, -0.1377, +0.4133, +0.0075, +0.2662, -0.0899, +0.2100,
+ -0.0853, +0.0316, -0.1310, -0.5245, -0.3770, -0.2010, +0.2296,
+ -0.1653, -0.2975, -0.2957, -0.1499, -0.2093, +0.0406, -0.0851,
+ +0.0893, +0.1815, +0.0560, -0.1637, +0.3338, -0.0075, -0.4040,
+ -0.3295, -0.0336, +0.1534, -0.5067, -0.5103, -0.0447, -0.0133,
+ +0.0738, -0.1764, -0.0509, -0.1104, -0.0568, +0.3894, +0.0515,
+ -0.2251, -0.2737, +0.0503, -0.3561, +0.0208, +0.0426, -0.2372,
+ +0.2387, -0.1670, +0.1123, +0.0645, +0.0064, -0.2416, +0.3130,
+ -0.2139, -0.4807, -0.3596, +0.0326, -0.2081, +0.2586, -0.3262,
+ +0.0230, -0.0541, +0.1587, -0.2205, +0.2711, -0.1692, -0.1007,
+ +0.0034, +0.2116, -0.2285, -0.3356, -0.4481, +0.0854, +0.4984,
+ +0.4606, +0.0105, +0.1204, +0.3893, -0.0277, -0.0226, -0.0351,
+ +0.1008, -0.1522, +0.0265, -0.1190, +0.2637, +0.0124, -0.0738,
+ +0.2898, +0.1958, -0.1738, -0.0098, +0.1932, +0.0268, +0.1603,
+ +0.6525, +0.0526
+ ],
+ [
+ +0.0485, +0.0268, +0.0319, -0.3053, -0.4060, +0.0753, -0.0605,
+ +0.1749, +0.2095, -0.1262, -0.2092, +0.1282, -0.3959, +0.1964,
+ -0.3560, +0.0875, -0.1696, -0.1043, -0.1539, +0.0617, +0.2019,
+ -0.2442, -0.3615, +0.0525, -0.0495, +0.2295, +0.1157, -0.0754,
+ +0.1260, -0.0017, -0.2547, -0.0923, +0.1053, +0.4380, +0.6004,
+ -0.3390, -0.0069, +0.2720, +0.1229, -0.1220, -0.0963, -0.0385,
+ -0.2458, -0.1614, +0.3232, -0.0474, +0.0076, -0.0876, -0.1707,
+ -0.2325, -0.3311, -0.1263, -0.1986, +0.0380, -0.1855, +0.1246,
+ -0.0602, -0.4341, -0.3513, -0.2822, -0.4292, +0.2778, +0.3388,
+ +0.1175, +0.1572, +0.3568, +0.4891, -0.1087, -0.8776, -0.3998,
+ -0.2541, -0.3995, +0.0364, -0.0664, -0.0990, -0.0679, -0.0806,
+ -0.1332, -0.0665, +0.1621, +0.0134, +0.0001, -0.2535, -0.1088,
+ -0.3660, -0.0472, -0.1492, -0.0049, -0.2184, +0.4806, -0.1792,
+ -0.0431, +0.2985, +0.0829, -0.1200, +0.3787, -0.2766, +0.0398,
+ +0.1273, -0.1870, +0.3448, -0.7261, +0.0924, -0.0436, +0.3037,
+ -0.3195, +0.0065, -0.1420, -0.1679, +0.1018, -0.3936, -0.2624,
+ -0.0564, +0.1715, -0.2367, -0.2993, -0.0956, +0.0663, +0.1161,
+ -0.0466, +0.2386, +0.2236, +0.1145, +0.2103, +0.0126, +0.2852,
+ +0.1745, -0.3843
+ ],
+ [
+ -0.4672, +0.2588, +0.0562, +0.1480, -0.4764, +0.1280, +0.4856,
+ +0.0112, +0.2037, -0.0415, +0.1757, +0.3030, +0.2553, -0.0274,
+ +0.2237, +0.2764, -0.0150, +0.1079, -0.3132, -0.0768, +0.0729,
+ +0.1800, +0.1761, +0.4058, +0.2768, -0.3452, -0.3097, -0.9129,
+ +0.0064, +0.0359, -0.0055, +0.2052, +0.0746, +0.1586, -0.3851,
+ -0.2572, -0.2362, +0.0177, -0.4950, +0.0380, -0.4321, -0.5949,
+ +0.2672, +0.1696, -0.1803, +0.1604, -0.1012, -0.2397, +0.2885,
+ -0.0145, -0.1970, +0.2272, +0.0729, +0.0965, +0.1213, -0.3012,
+ +0.1532, +0.1785, +0.1139, -0.3229, -0.0235, +0.0460, -0.1932,
+ -0.4243, +0.2980, +0.6384, +0.0036, -0.0376, -0.2725, +0.1097,
+ +0.0773, -0.0941, -0.2394, -0.0633, -0.4184, +0.0828, +0.3985,
+ +0.3665, +0.0428, +0.2717, +0.0889, -0.4750, -0.1839, +0.2336,
+ +0.0573, -0.1662, +0.2641, -0.2457, +0.1031, -0.1323, -0.1159,
+ +0.1930, +0.1754, +0.2182, +0.1884, +0.0969, -0.0915, -0.4317,
+ -0.1361, +0.1541, +0.2442, -0.2624, +0.2007, -0.1427, +0.1815,
+ -0.1010, -0.2929, -0.0172, +0.1583, -0.1212, -0.3831, +0.3188,
+ -0.0740, +0.1650, +0.2072, -0.1448, -0.0106, +0.1476, +0.0625,
+ +0.3715, -0.7368, -0.0247, +0.0065, -0.3615, -0.0060, +0.0279,
+ -0.3687, +0.1363
+ ],
+ [
+ +0.3754, -0.2605, +0.0323, +0.2464, -0.1368, +0.1968, -0.0651,
+ -0.0776, -0.4373, -0.3815, +0.4641, +0.5324, -0.1058, -0.0363,
+ +0.0765, +0.1648, -0.4148, -0.3646, +0.5048, -0.0458, -0.0971,
+ +0.2370, +0.2665, -0.1116, -0.0673, +0.1211, -0.1089, +0.2868,
+ -0.0596, +0.1425, -0.4598, -0.3449, +0.0562, +0.2441, +0.3310,
+ +0.2028, -0.5315, +0.2401, -0.0847, +0.3627, +0.0449, +0.0452,
+ -0.1913, -0.3452, -0.1771, +0.0831, +0.0537, -0.3353, +0.1358,
+ +0.3165, +0.1456, -0.7420, +0.0564, +0.2464, -0.1040, -0.1426,
+ +0.3086, -0.3616, -0.2352, -0.0093, +0.6517, +0.3513, -0.3664,
+ -0.3185, -0.2502, -0.2195, -0.2321, +0.0309, -0.0145, +0.1909,
+ +0.4287, +0.1918, +0.4122, +0.0126, +0.3436, -0.0501, -0.2590,
+ -0.3481, -0.1366, -0.1364, +0.2620, +0.1644, +0.3660, +0.4092,
+ -0.2268, +0.2222, -0.0204, +0.2245, +0.2123, -0.0841, -0.2532,
+ +0.0668, -0.0343, -0.4897, +0.2300, +0.2320, -0.3528, -0.3275,
+ +0.1535, -0.0580, -0.2584, -0.1686, -0.0956, +0.3153, -0.1885,
+ +0.0961, -0.1013, +0.2607, -0.1861, -0.0490, +0.0190, -0.1581,
+ -0.1222, +0.3552, +0.5830, -0.3812, +0.2291, -0.1613, +0.4073,
+ -0.5114, -0.0738, +0.4687, +0.0703, -0.5921, -0.0492, -0.3495,
+ +0.2038, -0.0015
+ ],
+ [
+ -0.1122, -0.4957, +0.4057, -0.1631, +0.0567, -0.1668, +0.3326,
+ -0.2213, +0.2227, +0.6027, -0.0509, -0.1572, +0.0635, +0.0257,
+ -0.3764, -0.2729, +0.0150, +0.3523, +0.3869, -0.0460, -0.2430,
+ -0.1304, -0.0551, +0.0108, -0.0267, +0.0985, -0.3189, +0.0703,
+ -0.6249, -0.2440, +0.5041, +0.1002, +0.3512, +0.3129, +0.1434,
+ +0.2645, -0.1019, -0.3615, +0.2815, -0.0825, +0.3513, +0.4494,
+ -0.1594, +0.1642, +0.0036, -0.1905, -0.2434, +0.1266, +0.2592,
+ -0.3465, -0.3797, -0.0483, -0.2283, -0.0797, +0.1920, -0.2345,
+ +0.1873, +0.4164, -0.6789, -0.2604, +0.3056, +0.0606, +0.3516,
+ +0.1032, -0.1513, +0.3542, -0.1142, -0.2307, +0.1800, +0.2824,
+ -0.2042, +0.0625, -0.0690, +0.2268, -0.3744, +0.0939, +0.2214,
+ +0.2345, +0.1130, -0.1187, -0.3137, -0.2488, -0.3648, -0.0565,
+ +0.0364, -0.2158, -0.5209, +0.0104, -0.6269, -0.1152, +0.1796,
+ -0.0065, -0.2958, +0.2548, -0.1919, -0.1996, +0.2111, +0.0362,
+ -0.0187, -0.2994, +0.1538, +0.0342, +0.1659, +0.2444, -0.1623,
+ +0.0468, +0.0540, -0.1784, +0.3852, -0.3855, -0.2606, -0.6163,
+ +0.1517, +0.1374, +0.1268, +0.0022, +0.2307, +0.2028, -0.0723,
+ -0.1358, -0.1072, -0.3337, -0.0602, +0.1512, -0.0703, -0.1210,
+ -0.3207, -0.2559
+ ],
+ [
+ -0.2911, -0.1009, +0.1391, -0.0244, -0.1153, -0.2357, +0.1661,
+ +0.4648, +0.3280, -0.1573, -0.4334, -0.0048, +0.1839, -0.0928,
+ -0.1499, +0.3940, -0.0577, -0.4509, +0.2161, +0.2168, -0.4486,
+ +0.1994, -0.0153, -0.3432, -0.1163, -0.2053, +0.0779, -0.2540,
+ +0.3683, +0.4146, -0.2337, +0.2252, -0.2090, +0.2881, +0.0109,
+ +0.0089, +0.2146, -0.1160, +0.0447, -0.1081, -0.0476, +0.1209,
+ +0.1485, +0.0825, -0.1552, +0.1390, +0.3149, +0.1107, +0.0671,
+ +0.1735, -0.5206, -0.4408, +0.3938, +0.0551, +0.2809, -0.0903,
+ -0.2065, -0.2171, -0.3155, -0.2297, +0.0945, +0.2610, +0.1254,
+ +0.0889, +0.1768, -0.1305, -0.2692, +0.0158, +0.1272, -0.2697,
+ -0.0698, +0.2225, -0.3673, +0.3703, +0.1918, -0.1972, +0.1838,
+ -0.0154, -0.2331, -0.5831, +0.0827, +0.1265, +0.3300, +0.4084,
+ -0.2463, +0.1464, -0.2197, +0.0450, -0.1694, -0.2000, -0.3338,
+ -0.0556, +0.0045, -0.6450, +0.0410, +0.0201, -0.5188, +0.1173,
+ -0.3162, -0.1067, -0.0088, +0.0243, -0.0778, +0.1921, +0.0385,
+ -0.0554, -0.1265, +0.0691, +0.3145, +0.2980, -0.1277, -0.0588,
+ +0.0949, -0.3787, -0.0691, -0.0276, -0.0251, -0.1589, -0.0207,
+ -0.1079, -0.4167, -0.2475, -0.2711, -0.0513, +0.3191, +0.6425,
+ -0.2709, -0.1689
+ ],
+ [
+ +0.0047, +0.0616, -0.1269, -0.0223, -0.1831, +0.3906, +0.2033,
+ -0.1767, +0.1908, +0.0738, +0.0442, +0.2406, +0.1871, -0.0993,
+ +0.0015, -0.1329, +0.0476, +0.5890, -0.2690, +0.0427, +0.1877,
+ +0.0073, -0.2394, +0.1549, +0.3307, -0.3357, +0.2112, +0.0156,
+ +0.3022, +0.0204, -0.1618, -0.2322, -0.1883, +0.1024, +0.0760,
+ -0.6147, +0.2509, +0.0126, -0.1969, -0.0979, +0.3660, +0.0898,
+ -0.0740, -0.0060, -0.1458, -0.0460, -0.4250, -0.3589, +0.0585,
+ -0.0567, -0.2184, +0.1149, +0.1346, -0.0299, -0.0425, -0.2282,
+ -0.0385, +0.1466, -0.4807, -0.3405, +0.0751, +0.5248, -0.1385,
+ -0.0819, -0.3010, -0.0021, +0.1113, +0.0553, -0.0328, +0.4945,
+ +0.3550, -0.0888, +0.0378, -0.2603, +0.1825, +0.1809, +0.0374,
+ -0.0740, +0.0838, +0.4879, +0.0374, -0.0534, -0.0180, -0.1993,
+ -0.4417, -0.3333, -0.3223, -0.3871, -0.0617, +0.2161, -0.0491,
+ +0.0336, -0.0206, -0.0922, -0.2727, +0.0829, -0.2567, +0.0960,
+ -0.1694, -0.5163, -0.0041, -0.0166, -0.4449, +0.1398, +0.2162,
+ -0.5065, -0.1253, +0.0833, -0.0705, +0.1840, +0.1504, +0.2364,
+ -0.1248, +0.1244, +0.2257, -0.0303, +0.3157, -0.2759, -0.1885,
+ +0.0851, -0.0481, -0.1577, -0.2389, +0.1950, +0.3905, +0.0810,
+ +0.0136, -0.0261
+ ],
+ [
+ -0.2776, -0.3588, -0.4710, +0.2055, -0.0982, -0.0288, +0.3268,
+ +0.0424, -0.1561, +0.3499, +0.4200, -0.5925, +0.2719, -0.5844,
+ -0.2293, +0.0549, +0.0285, -0.1706, -1.1541, +0.2360, +0.0970,
+ +0.0501, +0.0376, +0.1502, +0.0308, -0.0501, +0.1327, +0.3548,
+ -0.0756, -0.2112, -0.4810, -0.2197, -0.0827, -0.2571, +0.2539,
+ -0.2960, -0.0967, -0.1865, -0.2390, +0.2819, +0.2164, +0.0519,
+ +0.0464, +0.2448, -0.2410, -0.1175, -0.0993, -0.7210, -0.0141,
+ -0.0289, -0.1874, -0.2468, +0.1093, -0.2226, +0.1077, +0.3520,
+ -0.2411, +0.1714, -0.3071, +0.1988, +0.5781, +0.3843, -0.0926,
+ -0.2357, -0.4513, -0.3061, +0.3818, +0.3143, +0.4826, -0.1459,
+ +0.1707, +0.3978, -0.1669, -0.2427, +0.4658, -0.2464, +0.3491,
+ +0.1534, -0.1865, -0.3171, -0.0700, +0.0454, +0.4187, +0.2408,
+ -0.0124, +0.4662, +0.4847, +0.2388, +0.2800, +0.2012, -0.0927,
+ -0.2946, +0.1002, -0.2051, +0.0583, -0.2708, +0.0331, -0.0591,
+ -0.1156, +0.1790, -0.4946, -0.3300, -0.3836, -0.0449, +0.2630,
+ +0.1686, +0.0428, +0.0842, -0.0174, +0.0996, -0.0303, -0.3013,
+ -0.0502, -0.5230, +0.1715, -0.2806, -0.1776, +0.2469, -0.2864,
+ -0.3993, +0.2259, +0.1500, -0.3863, +0.2840, +0.0559, +0.2354,
+ +0.2897, +0.4232
+ ],
+ [
+ +0.0786, +0.3700, +0.2628, +0.0211, -0.5878, +0.3987, +0.0301,
+ +0.2936, +0.1753, -0.1643, -0.2340, +0.1637, +0.2365, +0.0329,
+ +0.0921, -0.0478, +0.1871, -0.1717, +0.0519, -0.1018, -0.3369,
+ -0.0651, +0.0361, -0.1157, +0.6206, -0.3262, -0.0921, -0.2719,
+ +0.5857, +0.1393, -0.3557, +0.0635, -0.3072, -0.5401, +0.0289,
+ -0.0330, -0.0507, +0.3589, +0.0363, -0.2177, +0.2639, +0.0678,
+ -0.1000, +0.1955, +0.1026, +0.1955, -0.0616, +0.5871, +0.1069,
+ -0.3716, -0.0883, -0.4984, -0.3853, +0.4456, -0.1893, +0.0767,
+ +0.1969, -0.0124, +0.0712, +0.0655, +0.4908, +0.2021, +0.1938,
+ -1.0127, -0.0061, +0.3511, +0.0834, -0.5368, +0.2761, -0.2155,
+ +0.0154, -0.1181, -0.1794, -0.2620, -0.2968, +0.4547, -0.4057,
+ -0.2744, +0.0613, -0.0414, +0.1598, +0.0669, +0.1854, +0.1409,
+ +0.0682, +0.1385, -0.0276, +0.0171, +0.1945, +0.0307, +0.0001,
+ -0.2223, +0.1962, +0.0133, +0.0785, +0.0997, +0.1798, +0.0109,
+ +0.1000, +0.4742, +0.0332, -0.5774, +0.2532, +0.0146, -0.1217,
+ +0.1973, -0.1829, -0.4806, +0.0419, -0.2457, -0.3725, -0.1983,
+ -0.1706, -0.3660, +0.0608, -0.1282, +0.3200, +0.0482, +0.5245,
+ +0.2118, -0.8071, +0.0611, +0.3456, -0.4500, +0.2488, -0.1320,
+ +0.4830, +0.2848
+ ],
+ [
+ -0.1073, +0.1037, -0.3255, +0.0693, +0.1400, -0.2319, +0.0581,
+ +0.0548, -0.0365, -0.1910, -0.2240, +0.2228, -0.2315, -0.2570,
+ -0.0562, -0.4512, +0.0993, +0.2102, -0.0621, +0.0652, +0.2532,
+ +0.1462, +0.2055, +0.4096, -0.0325, +0.0912, -0.2241, -0.0846,
+ -0.0290, -0.3131, +0.0912, -0.3046, +0.2735, -0.2764, -0.1748,
+ +0.0446, +0.0925, -0.3799, +0.2789, +0.1586, -0.1533, -0.0111,
+ +0.1665, -0.3099, -0.2307, -0.4259, +0.3205, +0.0423, -0.2089,
+ -0.1306, -0.0337, -0.4183, -0.4420, +0.2175, +0.1202, -0.0476,
+ -0.2734, +0.1719, -0.3250, +0.0094, +0.3707, +0.0904, -0.4614,
+ +0.1627, -0.3169, -0.3031, -0.0894, -0.1149, +0.3212, +0.3719,
+ +0.0059, +0.2209, -0.2337, -0.3808, +0.3385, -0.2686, -0.0678,
+ +0.5800, +0.3577, +0.0998, +0.2190, -0.1451, -0.4314, +0.2262,
+ -0.1531, -0.1131, +0.1177, +0.0831, -0.3033, -0.0453, -0.1597,
+ +0.2794, +0.0207, -0.4414, -0.1667, +0.1918, -0.0865, +0.3251,
+ -0.0287, -0.0736, -0.1075, -0.1250, -0.4520, +0.3047, -0.0875,
+ -0.2582, +0.4246, -0.0067, -0.0675, -0.0365, +0.3078, -0.2003,
+ -0.1038, -0.2029, +0.1792, +0.3332, +0.1595, -0.0987, -0.1700,
+ +0.2975, +0.5003, -0.2330, +0.2490, +0.3504, -0.2410, +0.5215,
+ +0.1684, -0.2419
+ ],
+ [
+ -0.0272, -0.0197, -0.0498, -0.3125, -0.1470, +0.2877, +0.0098,
+ +0.0828, +0.3936, +0.1087, -0.0007, -0.0460, -0.1392, +0.0118,
+ +0.2500, -0.1045, +0.0548, -0.0537, +0.1720, -0.2372, -0.1876,
+ +0.1110, +0.1386, -0.1052, -0.1087, -0.0159, +0.1606, -0.1951,
+ +0.2494, -0.1679, +0.1025, +0.3162, +0.2416, +0.0338, -0.0438,
+ -0.0798, -0.2180, -0.0090, -0.0330, -0.2608, -0.1611, +0.3750,
+ +0.3055, +0.1846, +0.1841, +0.3994, -0.0243, -0.3590, +0.0062,
+ +0.0208, -0.0984, +0.2669, -0.2289, -0.4093, -0.0409, -0.1831,
+ -0.1913, -0.2470, -0.1215, +0.1650, -0.3795, +0.0429, -0.0017,
+ -0.0563, -0.2910, +0.4329, -0.4084, +0.1284, -0.2935, -0.0446,
+ -0.1213, +0.0592, -0.3015, -0.1558, -0.4683, +0.1737, +0.1404,
+ -0.1560, -0.1683, -0.0704, -0.1695, -1.1899, +0.0634, -0.2749,
+ -0.3013, -0.6152, -0.0497, +0.4101, +0.3239, -0.3935, -0.0283,
+ +0.0037, +0.3283, +0.0818, -0.4429, -0.4364, -0.2240, +0.1993,
+ +0.0054, +0.3334, +0.5122, -0.0501, +0.2898, -0.1176, +0.1916,
+ +0.0811, +0.2813, -0.4673, +0.0826, -0.0553, -0.0349, -0.1847,
+ -0.1159, +0.4650, -0.1069, -0.3477, -0.0889, +0.0103, +0.0001,
+ -0.3395, +0.2372, -0.0297, +0.2345, -0.0795, +0.2465, -0.1002,
+ -0.1024, -0.0517
+ ],
+ [
+ +0.1808, +0.0077, +0.1769, -0.2979, -0.0312, +0.1853, +0.1740,
+ -0.3678, -0.0212, +0.0899, -0.2367, +0.2297, -0.1192, +0.1246,
+ -0.0043, -0.4725, -0.3428, -0.0674, +0.5052, -0.4794, -0.2887,
+ -0.4310, +0.1617, +0.4358, +0.3620, -0.0182, -0.1712, -0.1217,
+ -0.4400, +0.1939, +0.2990, -0.4162, -0.1362, +0.0944, +0.1773,
+ -0.2093, +0.1013, -0.0034, -0.2675, +0.1798, +0.0271, +0.2224,
+ -0.4245, -0.1975, +0.1742, +0.4710, +0.1564, +0.2407, +0.1071,
+ -0.2609, -0.6139, +0.1218, -0.2299, -0.1103, +0.4042, +0.0591,
+ -0.0113, +0.0456, +0.4728, +0.0059, +0.3071, +0.0690, +0.0480,
+ +0.4073, -0.0833, +0.0645, -0.3894, -0.2094, +0.0390, +0.2714,
+ +0.0559, -0.0315, -0.4724, -0.2619, +0.0623, +0.0794, -0.1085,
+ -0.0133, -0.0373, +0.1215, -0.5136, -0.4344, -0.4528, +0.2668,
+ +0.0667, -0.1481, -0.2553, +0.0380, +0.2029, +0.2780, -0.3474,
+ -0.2158, -0.3623, -0.0207, +0.1420, -0.0384, -0.0967, -0.0257,
+ -0.0592, +0.3893, -0.2964, -0.1850, -0.3109, +0.3306, -0.5495,
+ -0.0713, -0.0160, +0.2504, -0.3662, -0.4457, -0.1997, +0.0348,
+ +0.2545, +0.0796, +0.2407, -0.6725, -0.2860, +0.1711, -0.0364,
+ -0.3736, -0.0821, +0.1595, +0.0021, -0.0176, +0.0976, -0.1021,
+ -0.3775, -0.6194
+ ],
+ [
+ -0.1115, +0.2235, +0.1863, +0.2503, +0.1941, -0.1116, -0.0322,
+ +0.0161, -0.0706, +0.2388, -0.5055, -0.3318, +0.1156, -0.5982,
+ +0.2497, +0.2186, +0.0293, -0.0434, +0.5011, -0.4769, +0.2955,
+ +0.3118, +0.3163, -0.1813, +0.3505, -0.6790, +0.3490, +0.1289,
+ -0.0642, -0.0930, +0.5358, -0.3412, -0.2185, -0.0010, +0.0342,
+ -0.1512, -0.2240, -0.1741, -0.0852, -0.0242, +0.2095, +0.2727,
+ -0.1230, -0.2387, -0.1015, +0.0158, +0.0469, +0.0534, +0.1719,
+ -0.1393, +0.2014, +0.0348, -0.1869, +0.1339, -0.1371, -0.0463,
+ -0.0411, +0.2232, +0.0770, -0.0833, -0.1241, +0.1086, -0.1627,
+ -0.0193, +0.3628, -0.2017, +0.1716, +0.3239, +0.4415, +0.1805,
+ -0.2427, -0.5063, -0.2224, +0.1149, +0.2752, -0.1453, +0.1640,
+ -0.1874, -0.0713, +0.0449, -0.1494, -0.0192, -0.0468, +0.0316,
+ -0.6600, -0.1496, +0.2316, -0.2830, +0.0171, +0.0085, -0.5733,
+ -0.2160, +0.2207, +0.1985, -0.1002, +0.2795, +0.2018, -0.0175,
+ +0.0011, -0.1767, +0.0625, -0.1560, -0.3344, -0.7670, -0.1168,
+ -0.1633, -0.1385, +0.1261, +0.1919, +0.1725, +0.0319, -0.0165,
+ +0.0850, -0.2974, -0.4158, -0.3987, -0.0986, +0.2890, +0.3104,
+ -0.2340, -0.1918, -0.2878, +0.0301, +0.0279, +0.3777, -0.4659,
+ +0.0765, -0.0032
+ ],
+ [
+ -0.1247, +0.3309, -0.3103, +0.1687, +0.0976, -0.2351, -0.0116,
+ -0.1747, -0.6116, -0.0176, +0.2908, -0.1105, +0.1844, -0.6355,
+ +0.0104, -0.1551, +0.4021, -0.0415, +0.2615, +0.0888, -0.1101,
+ -0.0847, -0.1650, +0.5355, +0.3455, +0.0882, -0.0706, +0.1523,
+ -0.0444, +0.0061, +0.0724, -0.3089, -0.0143, -0.0126, -0.0448,
+ -0.2619, -0.0541, -0.2937, +0.1746, +0.0298, +0.2119, -0.1340,
+ +0.0650, -0.0277, -0.3615, +0.2201, -0.1907, +0.1040, +0.2692,
+ +0.4564, +0.1397, +0.1867, -0.0088, +0.3706, +0.3067, +0.0381,
+ +0.4252, +0.2832, -0.0726, -0.3068, -0.1553, +0.0957, -0.1835,
+ -0.1914, -0.2654, +0.1882, +0.4128, +0.0531, +0.0793, +0.3259,
+ +0.0693, -0.0804, +0.0350, -0.1218, -0.1162, -0.2567, -0.1921,
+ +0.1013, -0.0471, -0.1040, +0.3210, +0.0918, +0.1500, +0.0885,
+ -0.2175, +0.2143, -0.0960, -0.3534, -0.1179, +0.0871, +0.4107,
+ -0.3273, +0.0231, -0.1418, +0.0434, +0.2652, +0.3954, +0.1180,
+ -0.3608, -0.3019, +0.0631, +0.0295, +0.0942, -0.0744, +0.1798,
+ +0.0825, +0.3385, +0.2035, +0.1360, +0.0015, -0.3507, -0.3485,
+ +0.3279, +0.2493, +0.1420, -0.0464, -0.0018, +0.0730, +0.4359,
+ -0.0651, +0.3583, -0.1389, -0.6723, -0.3598, -0.0669, -0.1090,
+ +0.0912, -0.0810
+ ],
+ [
+ +0.2457, -0.1002, -0.3755, +0.1569, +0.2735, +0.0723, -0.2051,
+ -0.2408, +0.0090, +0.2706, +0.1030, -0.0864, -0.0750, +0.0613,
+ -0.0209, -0.0809, -0.3630, -0.3275, +0.2244, -0.0836, -0.0974,
+ +0.1007, -0.1786, +0.1611, -0.2397, +0.3843, +0.5103, +0.0555,
+ +0.2557, -0.2810, -0.0016, +0.2774, +0.1998, -0.2768, -0.3266,
+ -0.3404, +0.2155, +0.0193, +0.3186, +0.0729, +0.2436, +0.1745,
+ -0.1795, -0.2552, -0.9459, +0.4166, +0.0442, +0.0434, -0.1687,
+ -0.1794, -0.3971, +0.4327, -0.4028, +0.2954, +0.0494, -0.0953,
+ +0.2842, -0.0374, -0.3217, +0.1724, +0.1249, +0.0641, -0.1462,
+ +0.4803, -0.2048, +0.0251, -0.1623, -0.3777, -0.5728, +0.1280,
+ +0.0597, +0.1503, -0.1340, -0.0378, +0.0261, -0.5590, -0.2668,
+ -0.1524, +0.3065, -0.0374, -0.0692, +0.1520, -0.4180, -0.0488,
+ -0.7730, +0.1127, +0.2032, -0.6233, +0.4527, -0.2019, -0.0933,
+ -0.4223, +0.1502, -0.2655, +0.0123, -0.2330, -0.1848, +0.0627,
+ -0.6064, -0.3355, -0.3527, -0.3417, -0.1368, +0.0545, -0.2194,
+ -0.0615, -0.1130, +0.3267, -0.1764, +0.0686, -0.1893, +0.0566,
+ +0.0097, -0.1705, -0.3254, +0.1268, +0.3298, +0.2485, +0.0625,
+ -0.1229, -0.3688, -0.4070, -0.1600, -0.4408, -0.1673, +0.1722,
+ +0.1500, +0.0929
+ ],
+ [
+ -0.3784, +0.2427, +0.2142, -0.1156, +0.3994, -0.1667, -0.0100,
+ +0.3319, +0.1156, +0.0075, +0.4072, -0.1607, -0.4709, +0.1231,
+ +0.2051, +0.1843, -0.1108, -0.1801, -0.0897, +0.2885, -0.1098,
+ +0.1957, +0.1071, -0.2464, +0.7503, +0.6850, -0.1070, -0.0895,
+ +0.0858, -0.0243, -0.2785, +0.0489, +0.0823, +0.1822, +0.0367,
+ -0.4066, -0.0994, -0.2185, +0.1010, -0.5811, +0.0185, +0.0432,
+ +0.0955, -0.3456, -0.2426, -0.2875, -0.1263, +0.1389, +0.0185,
+ +0.2978, +0.3486, +0.0317, +0.0020, -0.0886, +0.3061, -0.8932,
+ +0.4772, +0.1074, -0.0251, +0.0624, +0.0784, +0.4083, -0.0261,
+ +0.4151, +0.0109, +0.3645, +0.0858, -0.0630, -0.4826, -0.3442,
+ -0.1942, -0.1690, +0.1250, -0.1372, +0.1137, -0.0636, -0.0974,
+ +0.0269, -0.0511, -0.4347, +0.1984, -0.5682, -0.2920, -0.0002,
+ -0.7504, -0.4458, -0.2896, -0.1026, -0.7266, +0.1155, +0.4279,
+ -0.2980, -0.1069, +0.2625, -0.1583, -0.3158, +0.2147, +0.1183,
+ +0.3104, -0.1082, -0.3283, -0.2075, -0.0452, -0.2999, +0.5244,
+ -0.2035, -0.1068, -0.1554, -0.2656, -0.3371, +0.5964, -0.4253,
+ -0.0956, +0.2555, -0.3485, +0.0816, -0.1378, +0.2922, -0.1855,
+ +0.1262, +0.1483, +0.0747, +0.4638, +0.1276, -0.1310, +0.2338,
+ +0.3094, -0.2473
+ ],
+ [
+ +0.1188, +0.4493, -0.9818, -0.2414, +0.1465, +0.0074, +0.1783,
+ +0.0959, -0.0730, +0.0722, +0.2628, -0.0635, -0.1643, -0.1292,
+ -0.0130, +0.3392, -0.0943, -0.0947, +0.2819, -0.2740, +0.0396,
+ -0.4328, -0.2749, -0.0812, +0.2344, +0.2273, -0.6296, +0.3417,
+ -0.2282, +0.0739, -0.1244, +0.4453, +0.3020, -0.4413, -0.1126,
+ +0.2636, -0.4832, -0.0293, +0.0941, -0.2804, +0.0153, -0.1717,
+ -0.1063, -0.2515, -0.3199, +0.3667, -0.2324, +0.2294, +0.0246,
+ +0.0593, -0.1996, +0.0713, +0.1961, +0.5011, +0.1511, +0.1357,
+ +0.0753, +0.1068, -0.9525, +0.1665, -0.6526, +0.1655, +0.0310,
+ +0.1485, +0.0571, -0.1391, +0.0852, +0.1682, +0.1411, -0.0472,
+ -0.2163, +0.3395, +0.0348, -0.3560, +0.1767, -0.6339, -0.3874,
+ -0.2927, +0.1617, -0.1497, +0.0753, +0.0138, +0.0094, +0.1580,
+ +0.1195, +0.0525, +0.5206, +0.0334, -0.2583, -0.1034, -0.2406,
+ +0.1169, -0.0148, +0.0985, -0.0254, +0.1124, +0.3449, +0.1616,
+ -0.2785, +0.2490, -0.0847, -0.1535, -0.4076, -0.3406, -0.2049,
+ -0.2246, +0.3235, +0.2426, +0.0597, +0.0995, +0.0328, +0.2919,
+ -0.0782, -0.1348, -0.0050, -0.0453, +0.3151, +0.0136, +0.2667,
+ -0.4870, +0.1822, -0.0651, +0.1189, +0.4254, -0.0163, -0.0231,
+ +0.1072, +0.3848
+ ],
+ [
+ -0.2626, +0.1906, +0.0159, -0.5722, -0.1372, -0.1161, +0.1322,
+ +0.4720, -0.0829, +0.0818, -0.2520, +0.2281, -0.4011, +0.1927,
+ +0.2289, -0.4195, +0.0081, +0.1158, -0.0402, +0.0950, -0.0919,
+ +0.0801, +0.2395, +0.0689, -0.3084, +0.0268, -0.1748, +0.1271,
+ +0.2266, -0.5446, +0.2666, -0.0929, +0.1289, +0.0600, +0.2130,
+ +0.1434, -0.5269, -0.2001, +0.1484, -0.1686, +0.1465, +0.2128,
+ +0.2418, -0.0679, +0.0942, -0.1425, +0.1829, +0.0297, +0.1505,
+ -0.0156, +0.1377, -0.2170, -0.3740, -0.3405, +0.3630, -0.2488,
+ +0.0566, -1.3841, +0.1982, +0.0943, +0.6569, +0.3589, +0.0511,
+ +0.0752, -0.1480, -0.0214, -0.3318, -0.3824, -0.2357, -0.2268,
+ -0.0264, -0.2861, +0.1390, -0.1438, +0.1137, +0.3078, -0.1841,
+ -0.4639, +0.0032, -0.1726, +0.0795, +0.3248, +0.1505, -0.3801,
+ -0.0616, -0.0979, -0.2185, +0.1893, +0.3569, +0.0229, -0.2571,
+ +0.0186, +0.0936, +0.1646, +0.6127, -0.1860, -0.1712, -0.3706,
+ -0.2717, +0.0496, -0.2094, +0.3110, +0.1764, +0.1597, +0.0294,
+ +0.4132, +0.0404, -0.5775, -0.4119, -0.1210, +0.3285, +0.1140,
+ +0.0009, +0.1166, +0.1456, -0.0536, -0.0209, -0.2326, -0.1501,
+ +0.1628, +0.2322, -0.2931, +0.1086, +0.0664, +0.4100, +0.0828,
+ -0.0044, -0.3212
+ ],
+ [
+ -0.2998, -0.0738, -0.1513, +0.1247, +0.1899, +0.0987, -0.1714,
+ +0.0683, -0.1489, -0.1247, +0.1166, +0.1891, -0.2348, +0.0066,
+ +0.4323, +0.1324, +0.0567, -0.0832, +0.3091, -0.0532, -0.0263,
+ +0.2447, -0.4638, +0.1947, -0.2422, +0.0567, +0.0925, +0.0819,
+ +0.2029, +0.6120, -0.1958, +0.2320, +0.4321, -0.4380, +0.1854,
+ -0.1932, +0.3976, +0.0167, -0.3029, -0.2789, -0.1836, +0.3506,
+ +0.1142, -0.3089, -0.0155, +0.2917, -0.0075, -0.2264, -0.1235,
+ -0.4551, -0.0861, +0.3406, -0.1878, +0.0997, -0.1639, -0.4325,
+ +0.2613, -0.0110, -0.2154, -0.1120, +0.1183, -0.0160, +0.0826,
+ -0.2044, +0.1645, +0.2868, -0.3488, +0.1002, +0.1681, +0.1152,
+ -0.1621, -0.0359, +0.1327, +0.1303, -0.0409, +0.2150, -0.0534,
+ +0.0391, +0.0398, +0.0562, -0.0010, -0.2104, -0.7669, -0.0526,
+ -0.6345, +0.1331, +0.2693, -0.2896, -0.1767, -0.0304, +0.2403,
+ -0.0068, +0.0947, +0.1147, +0.0409, -0.2276, -0.0863, +0.0982,
+ -0.0374, -0.3437, -0.2203, -0.2168, -0.4528, +0.0281, +0.1741,
+ +0.0721, -0.4683, +0.3592, -0.4125, -0.2943, -0.0418, -0.3669,
+ -0.0151, +0.2583, +0.0446, +0.0434, +0.2630, -0.1901, +0.1523,
+ -0.1569, -0.0261, +0.2346, -0.0361, -0.0086, -0.0521, -0.3845,
+ +0.1049, -0.1093
+ ],
+ [
+ -0.0168, -0.4458, +0.1942, +0.3798, -0.1351, +0.3490, -0.0996,
+ +0.3007, +0.3864, +0.2677, +0.1881, +0.4173, -0.0480, +0.0208,
+ +0.1373, +0.3895, -0.1900, -0.2243, -0.4441, +0.1671, -0.1908,
+ +0.1916, -0.2027, -0.0950, -0.3711, +0.0144, +0.0048, +0.2085,
+ +0.0899, +0.2141, -0.1910, +0.1190, -0.0588, -0.0655, +0.4096,
+ -0.0181, -0.2487, +0.1523, +0.0283, -0.7074, -0.1608, +0.1667,
+ +0.2706, -0.3745, -0.1894, +0.0808, +0.1107, -0.1004, +0.1992,
+ -0.2060, +0.0339, -0.3551, -0.0597, -0.0517, +0.1393, -0.1482,
+ -0.0038, -0.1573, +0.0883, -0.9840, +0.2895, +0.0765, +0.2400,
+ -0.2997, +0.3613, +0.0350, +0.1777, +0.2983, +0.1176, +0.2537,
+ -0.0739, +0.0006, -0.0600, +0.1464, -0.1229, -0.0311, -0.0771,
+ -0.7318, -0.2761, +0.1637, +0.0035, -0.0194, -0.0833, -0.1349,
+ -0.7954, +0.2362, +0.1254, -0.2388, +0.2375, -0.1963, +0.0404,
+ -0.3887, -0.0391, +0.2400, -0.1575, -0.3568, +0.2793, -0.2091,
+ +0.0211, +0.1187, +0.3964, +0.1564, -0.0736, -0.6786, -0.0531,
+ +0.1627, -0.5970, -0.1192, +0.1050, -0.0145, -0.0518, +0.0386,
+ +0.0412, +0.5335, -0.1619, -0.3176, +0.3743, -0.0002, -0.4408,
+ +0.1617, +0.0233, +0.3467, -0.1305, +0.1143, -0.2537, +0.3384,
+ -0.7350, -0.0479
+ ],
+ [
+ +0.1792, -0.0538, -0.2786, +0.1202, -0.6593, +0.2724, -0.3845,
+ +0.1834, +0.3114, +0.0188, -0.0799, +0.0130, +0.3213, -0.0154,
+ +0.1247, -0.3229, +0.2813, +0.2138, -0.0917, -0.2363, -0.3678,
+ +0.1511, -0.1976, -0.0504, -0.2789, -0.3925, -0.0762, -0.4634,
+ +0.1507, -0.1855, +0.1760, +0.5578, +0.0665, -0.6775, +0.1183,
+ -0.0891, +0.0081, -0.0551, +0.2224, -0.4622, -1.3207, +0.2661,
+ +0.2669, -0.4883, -0.0982, -0.1005, -0.9165, +0.0882, -0.2453,
+ +0.1193, -0.6679, +0.2242, +0.1134, +0.2089, +0.2412, -0.0726,
+ +0.2932, -0.1572, +0.1877, -0.1134, +0.0212, -0.4043, -0.0081,
+ +0.3070, -0.5104, +0.0023, +0.0509, +0.2641, -0.4226, +0.2353,
+ +0.1801, +0.2648, +0.4037, +0.3656, -0.0902, -0.2083, -0.0644,
+ -0.1504, +0.4869, +0.0089, +0.3296, +0.2200, +0.0874, +0.3023,
+ -0.2181, +0.4218, -0.0435, +0.2051, +0.0916, +0.0242, +0.3354,
+ -0.2871, +0.0763, -0.2531, -0.1972, +0.2802, -0.1290, +0.3825,
+ +0.0606, +0.1270, +0.1836, +0.6563, -0.0714, -0.0703, +0.1128,
+ -0.2506, -0.0631, -0.1636, -0.7413, +0.2609, +0.0319, -0.1291,
+ -0.1161, +0.2079, +0.1388, +0.1157, +0.1809, -0.2323, -0.1051,
+ -0.4299, +0.1876, -0.2504, +0.0617, -0.2639, -0.3319, +0.1634,
+ +0.1862, -0.1007
+ ],
+ [
+ -0.0147, -0.0639, +0.1008, +0.4990, +0.1531, -0.9325, +0.0238,
+ +0.2393, +0.2306, +0.0683, -0.1566, +0.3142, +0.2203, +0.2258,
+ -0.2943, +0.3765, -0.2988, +0.3902, +0.0185, +0.0039, -0.5539,
+ +0.2588, -0.6650, +0.1318, +0.2560, +0.3680, -0.4079, -0.3864,
+ -0.4923, +0.4272, +0.2314, -0.0254, +0.0104, -0.0265, +0.0352,
+ -0.1241, -0.1193, -0.1553, +0.2534, -0.3951, +0.0661, -0.1445,
+ +0.3153, +0.2310, -0.1020, +0.0582, +0.2351, -0.1744, +0.0568,
+ -0.0010, -0.1221, -0.1725, +0.2274, -0.1963, -0.1775, +0.2182,
+ +0.1631, -0.2170, +0.2137, +0.1525, -0.0944, +0.2513, -0.0597,
+ -0.1106, +0.0882, -0.3798, -0.0551, +0.0147, +0.4100, +0.2900,
+ -0.1498, +0.1748, -0.0446, -0.0909, +0.1704, -0.0100, +0.1317,
+ +0.2471, +0.0569, +0.0891, +0.0411, +0.0695, +0.5479, -0.4577,
+ +0.1407, -0.5910, +0.4646, -0.1887, -0.3553, -0.0068, -0.1807,
+ +0.2212, +0.3963, +0.3808, -0.2139, -0.1677, -0.1488, -0.0411,
+ -0.0385, +0.1535, -0.1921, +0.2639, -0.0658, +0.1008, +0.0469,
+ -0.5127, +0.2267, +0.0552, +0.1902, +0.1366, -0.0367, +0.1080,
+ +0.2582, -0.1765, +0.0865, -0.0173, -0.1502, +0.1298, +0.1194,
+ -0.0114, +0.5047, -0.6161, +0.1684, +0.1423, -0.0740, -0.0017,
+ -0.4251, +0.1572
+ ],
+ [
+ -0.2140, -0.3271, +0.0936, +0.1970, +0.0270, -0.0738, -0.1122,
+ +0.2351, -0.2764, -0.3042, +0.3065, +0.3369, -0.0030, +0.0794,
+ -0.4086, +0.0829, +0.0348, +0.4357, -0.3144, -0.3475, +0.2103,
+ +0.2416, +0.3890, -0.0766, -0.0491, -0.1185, +0.1126, -0.1474,
+ -0.1488, -0.2475, +0.5842, -0.4185, +0.4351, -0.5985, -0.2610,
+ +0.1723, +0.0568, +0.0440, -0.0690, -0.1620, -0.1744, -0.3308,
+ +0.0705, -0.0517, +0.0700, -0.1315, +0.2611, -0.3889, +0.0096,
+ -1.0121, -0.4038, -0.0688, -0.0475, -0.0606, -0.4827, -0.1614,
+ -0.3999, +0.1290, -0.2109, +0.0517, +0.2618, -0.0180, -0.1866,
+ -0.3439, -0.5200, -0.6740, +0.1756, -0.2538, -0.0803, +0.0834,
+ +0.4017, -0.0115, -0.1462, -0.0219, -0.3289, -0.4086, +0.0987,
+ +0.2068, -0.1242, -0.2455, -0.1314, +0.4457, -0.5468, +0.0506,
+ -0.2755, +0.5574, -0.0027, -0.1421, -0.2566, -0.0342, -0.6687,
+ -0.1825, -0.3673, -0.2854, +0.2990, +0.4404, +0.1242, -0.4129,
+ +0.0107, -0.9073, +0.4019, +0.0232, -0.6491, -0.6974, +0.2077,
+ +0.0170, +0.0305, -0.0179, +0.0274, -0.3503, +0.0749, +0.3969,
+ +0.1079, -0.3485, -0.0974, -0.5856, -0.3906, -0.2659, -0.5340,
+ -0.6874, +0.0822, -0.7379, -0.4552, +0.1984, -0.5178, +0.0519,
+ -0.0462, -0.2613
+ ],
+ [
+ -0.0990, +0.0647, +0.0344, -0.4416, -0.2603, +0.0360, -0.2100,
+ +0.1608, -0.0658, -0.1921, -0.4526, +0.4287, -0.3017, +0.2185,
+ -0.5238, -0.0081, +0.3877, -0.0125, +0.2629, +0.0482, +0.2608,
+ -0.1868, +0.1154, -0.3084, -0.0315, -0.2967, -0.3124, +0.3164,
+ +0.0632, +0.0385, -0.0028, -0.0044, +0.3284, +0.3250, -0.1464,
+ -0.4270, +0.0371, -0.1594, +0.2852, -0.0357, -0.2120, +0.0183,
+ +0.0538, -0.0239, +0.0921, -0.3313, +0.3179, -0.3367, -0.2236,
+ -0.2502, +0.3334, +0.3626, -0.0926, +0.1143, -0.2168, -0.4905,
+ +0.2027, +0.2457, +0.0761, -0.4009, -0.1845, +0.2317, +0.0458,
+ -0.2172, -0.0563, +0.2718, +0.1883, -0.1079, -0.5020, +0.5858,
+ +0.3020, -0.1742, -0.4436, +0.0164, -0.0947, +0.0592, -0.2733,
+ -0.1155, -0.3387, -0.0347, -0.0076, -0.3443, +0.0917, -0.0111,
+ -0.4430, +0.1455, -0.1546, +0.2988, -0.0642, -0.1858, +0.5505,
+ +0.4235, -0.2500, -0.0868, +0.0040, -0.0055, -0.1632, +0.4762,
+ +0.1038, +0.2019, -0.5454, -0.4380, -0.4388, -0.0981, +0.2046,
+ +0.0618, -0.1465, -0.3141, -0.0221, -0.2583, -0.6180, +0.4901,
+ +0.0557, +0.2242, +0.1174, +0.2609, +0.1025, +0.0762, -0.0803,
+ +0.2245, -0.0595, -0.4999, +0.4982, +0.0145, +0.2611, +0.4816,
+ -0.1663, +0.1402
+ ],
+ [
+ +0.1015, -0.2188, -0.0059, -0.0043, +0.3909, -0.0640, -0.0354,
+ +0.2428, -0.0448, -0.1089, -0.2626, +0.0875, +0.2317, +0.0832,
+ +0.3148, +0.3355, +0.1300, -0.2864, -0.2355, -0.0749, +0.1873,
+ -0.2631, -0.1110, -0.1718, +0.1023, -0.0858, -0.0301, -0.4857,
+ -0.2234, +0.1080, -0.0177, +0.0591, +0.0068, +0.3276, +0.4901,
+ +0.2524, -0.0358, -0.4197, -0.2396, -0.4071, -0.0771, +0.0941,
+ +0.1835, +0.5056, +0.1202, -0.2230, -0.0365, -0.5363, +0.0206,
+ -0.2307, -0.0866, -0.0068, -0.4793, -0.1669, -0.1043, -0.0190,
+ -0.1292, +0.1839, +0.4037, -0.0492, +0.0248, +0.0850, +0.2228,
+ +0.2684, +0.0174, -0.0150, -0.2136, +0.0006, -0.1773, +0.3960,
+ -0.1461, -0.3662, -0.0490, +0.4252, -0.0163, +0.0062, +0.2475,
+ -0.0128, +0.1257, -0.3295, -0.1532, -0.2940, +0.0892, -0.3498,
+ +0.5167, -0.1376, +0.1647, -0.0583, -0.0494, -0.0057, +0.2688,
+ -0.3080, -0.2907, +0.0631, +0.1013, -0.2300, -0.0029, -0.0787,
+ -0.2467, +0.2660, -0.2953, +0.1714, +0.1873, +0.0712, -0.2960,
+ +0.0469, -0.3154, +0.0570, +0.1899, +0.1088, +0.2432, -0.1520,
+ +0.4387, +0.0371, -0.1384, -0.1175, -0.3142, -0.0365, -0.0566,
+ -0.0038, +0.3015, -0.4169, -0.0828, -0.3635, -0.0764, -0.8747,
+ -0.0931, -0.0060
+ ],
+ [
+ -0.3422, +0.2775, -0.1187, -0.6212, +0.4813, +0.1672, -0.0518,
+ +0.0651, +0.2508, -0.0946, +0.1564, +0.4984, +0.2039, -0.1914,
+ +0.0976, -0.8370, -0.1036, -0.2344, +0.2363, +0.3397, +0.2027,
+ +0.0463, +0.0514, +0.0550, -0.0828, +0.1674, -0.2382, -0.2400,
+ -0.1485, +0.2035, -0.2854, +0.1030, -0.2427, +0.1639, -0.0835,
+ -0.2393, -0.3461, -0.2118, -0.3884, +0.1347, +0.1618, -0.3030,
+ -0.0894, +0.4111, -0.1494, +0.2086, +0.2784, +0.4828, +0.2448,
+ -0.1454, +0.0891, +0.1214, +0.1245, -0.0405, +0.2439, -0.2381,
+ +0.3009, -0.7438, +0.2052, +0.3910, -0.2746, +0.4468, -0.2083,
+ +0.2919, -0.0023, +0.3302, +0.1301, +0.3699, +0.3749, -0.0596,
+ +0.2589, +0.0147, -0.1022, -0.5102, -0.1049, -0.1672, -0.5536,
+ +0.1310, -0.2086, -0.7637, -0.0547, +0.2275, -0.5628, +0.0801,
+ -0.2362, +0.5717, -0.8625, -0.0002, +0.2962, +0.5086, -0.4095,
+ -0.0300, +0.0390, -0.1372, +0.0395, -0.1132, +0.2392, -0.0060,
+ +0.6539, -0.0819, -0.2881, -0.3017, +0.1395, -0.1411, -0.3518,
+ +0.0177, +0.0801, -0.1510, -0.8548, -0.0499, +0.1037, -0.0782,
+ +0.2467, +0.2622, +0.1534, +0.3487, -0.2784, +0.0157, -0.0292,
+ +0.0682, -0.0555, +0.1900, -0.0140, +0.1117, -0.0425, +0.2222,
+ +0.1421, +0.0896
+ ],
+ [
+ +0.3215, +0.1030, -0.5264, +0.3126, +0.4631, -0.0905, -0.1420,
+ +0.0617, -0.1247, -0.2717, -0.2152, -0.0178, +0.3707, -0.1003,
+ -0.3412, +0.0482, -0.2545, -0.1400, +0.0013, -0.2387, +0.0183,
+ +0.3234, -0.0895, -0.4326, -0.0078, -0.0021, +0.0602, +0.0094,
+ -0.5288, -0.0352, +0.3186, -0.2452, -0.7510, +0.0166, -0.0443,
+ -0.5046, +0.0900, +0.0308, +0.1221, -0.2926, -0.5428, -0.5815,
+ +0.0009, +0.1007, -0.0257, -0.2028, -0.0313, +0.1233, -0.0253,
+ +0.1077, -0.1430, +0.4582, -0.0574, -0.0861, +0.2536, -0.3528,
+ -0.5794, -0.0742, -0.2056, +0.1496, +0.0894, -0.2854, -0.1345,
+ +0.2715, -0.0201, +0.2340, -0.0941, -0.1626, +0.0095, +0.1054,
+ +0.1596, -0.6335, +0.2332, -0.3196, +0.3785, +0.1697, -0.1321,
+ -0.0227, -0.3515, +0.1661, +0.1890, -0.0586, +0.1805, +0.0600,
+ -0.7643, +0.2405, -0.0662, +0.0525, -0.0916, +0.0225, -0.1066,
+ +0.5072, -0.1718, +0.1307, -0.1050, -0.1172, -0.5932, -0.0769,
+ -0.1079, -0.0396, -0.0203, +0.1204, +0.2182, -0.0285, -0.0734,
+ +0.1621, -0.2796, -0.2511, +0.5154, -0.1256, +0.0575, +0.4053,
+ -0.3265, +0.5537, +0.1468, +0.0024, +0.0659, +0.3903, -0.2981,
+ +0.0748, -0.7142, +0.0211, -0.0084, +0.2114, -0.0336, +0.2062,
+ -0.1641, +0.0345
+ ],
+ [
+ -0.1767, +0.4111, +0.0166, +0.1680, +0.3432, -0.1508, -0.3377,
+ +0.1994, -0.2411, -0.5138, -0.1948, -0.4879, -0.0517, -0.5196,
+ +0.4378, -0.1487, +0.1221, -0.0241, -0.0411, -0.3271, +0.0504,
+ +0.4184, -0.2106, +0.0274, -0.2030, +0.0138, -0.3463, +0.4342,
+ -0.3886, -0.1702, +0.0772, -0.6914, -0.1251, -0.5027, -0.2141,
+ +0.1692, +0.0531, -0.0134, +0.1365, -0.0471, -0.5026, -0.5345,
+ -0.0750, -0.6540, +0.4107, -0.0253, -0.4962, -0.0475, -0.0567,
+ -0.0428, +0.1786, -0.1019, -0.0177, -0.3989, +0.0805, -0.6437,
+ +0.0826, -0.0812, +0.2180, +0.0356, +0.1099, +0.1517, -0.2150,
+ +0.2837, +0.3894, +0.0356, -0.1908, -0.0985, -0.1478, -0.0040,
+ +0.0349, +0.3303, -0.1168, +0.0131, +0.1204, +0.0645, +0.1481,
+ -0.0304, -0.0489, -0.2517, +0.1785, -0.4240, +0.3172, +0.0560,
+ -0.0079, +0.3547, -0.0889, -0.3845, -0.1570, +0.0567, +0.2413,
+ +0.3162, -0.5907, -0.1475, +0.0735, +0.1308, +0.0247, -0.2660,
+ -0.7232, -0.1863, -0.3806, +0.0829, -0.2574, -0.0379, +0.0206,
+ -0.2949, +0.1580, +0.2900, +0.0795, +0.0523, +0.0383, +0.0524,
+ -0.0755, +0.0862, +0.3876, -0.0720, -0.2409, +0.0926, -0.3902,
+ -0.5682, +0.0380, -0.0429, +0.0813, -0.2425, +0.3830, +0.0894,
+ -0.3435, -0.0040
+ ],
+ [
+ +0.2445, -0.3221, -0.2894, +0.1155, -0.0250, +0.0264, +0.4052,
+ +0.1500, +0.2113, +0.1744, -0.1288, -0.0519, -0.4755, +0.0138,
+ -0.1508, -0.0906, +0.1170, +0.1912, -0.0426, +0.1228, -0.3168,
+ -0.1103, -0.4555, -0.0277, -0.3807, -0.7228, +0.1508, +0.0784,
+ +0.3282, +0.0603, +0.0172, -0.0236, +0.2048, +0.2340, -0.0488,
+ -0.1596, +0.0161, +0.0815, +0.2955, -0.1378, -0.5930, +0.2498,
+ +0.1344, -0.5621, -0.2068, -0.0203, +0.2416, -0.0432, +0.3372,
+ +0.0234, -0.2795, +0.1132, -0.2562, +0.2618, +0.4585, +0.1456,
+ -0.1266, +0.3029, +0.2788, -0.1247, -0.5935, -0.1186, +0.0734,
+ -0.0350, -0.0946, -0.0564, -0.0764, -0.0607, +0.0953, +0.1742,
+ -0.1591, +0.0559, -0.0171, -0.0351, -0.3491, +0.2183, -0.3547,
+ +0.2335, +0.2555, +0.2547, +0.1248, -0.0061, +0.1710, +0.0383,
+ +0.0616, +0.2185, -1.0023, -0.1936, -0.0807, +0.2063, -0.0745,
+ +0.0708, +0.1399, -0.0537, +0.2268, -0.2947, -0.4455, -0.1865,
+ -0.1535, -0.0317, -0.0848, -0.2121, +0.3018, +0.0905, +0.0159,
+ +0.3521, -0.0130, +0.5538, +0.0833, +0.2445, +0.2165, +0.1367,
+ -0.0128, -0.4681, +0.1047, +0.2925, +0.0895, -0.1273, -0.3037,
+ +0.0461, -0.2035, +0.0707, -0.0067, +0.1958, -0.1122, -0.0648,
+ -0.2368, +0.3070
+ ],
+ [
+ +0.0332, +0.1108, +0.1055, -0.2215, -0.2207, -0.0961, +0.1551,
+ -0.0297, -0.1572, -0.0777, -0.1128, +0.1579, +0.1274, -0.1284,
+ +0.3304, +0.1920, +0.1354, +0.0697, -0.1628, -0.2876, -0.5614,
+ +0.0893, +0.0028, +0.3967, -0.1001, -0.5001, +0.3025, -0.1845,
+ -0.2045, +0.2131, +0.3582, -0.1054, -0.0401, +0.1481, +0.1523,
+ -0.2040, +0.1310, +0.3809, -0.0179, +0.0166, -0.4429, -0.1629,
+ +0.0148, -0.0044, +0.1835, +0.0591, -0.2337, -0.2281, -0.2868,
+ -0.0554, +0.5748, +0.0107, +0.2273, -0.0109, +0.0614, +0.2047,
+ -0.3292, +0.2108, +0.1956, +0.6115, -0.0865, +0.5195, +0.4667,
+ +0.1747, +0.5170, -0.3925, -0.0643, +0.3511, +0.0903, +0.0125,
+ -0.4273, +0.0862, -0.0428, +0.3079, -0.0357, +0.4272, -0.2383,
+ +0.1451, +0.0454, -0.3505, -0.3626, -0.3535, +0.0587, -0.0526,
+ -0.4949, -0.3365, +0.1256, +0.3631, +0.1206, +0.0588, +0.1959,
+ +0.3120, +0.0314, +0.1693, +0.0071, -0.1606, -0.4374, -0.0889,
+ +0.3226, -0.1604, +0.2967, +0.0151, +0.2558, +0.1964, -0.4702,
+ +0.2784, -0.2398, -0.1751, +0.3346, +0.1903, +0.1093, +0.0678,
+ -0.0278, +0.1809, -0.0615, +0.0831, -0.0425, +0.2375, -0.0217,
+ -0.0493, +0.0006, -0.5245, +0.2295, +0.1216, -0.1974, +0.0019,
+ +0.2227, -0.0325
+ ],
+ [
+ -0.0106, -0.1795, -1.0107, +0.1485, +0.0512, +0.1046, -0.0372,
+ +0.1391, -0.0793, +0.0596, -0.1329, -0.4680, -0.0769, +0.3540,
+ -0.0180, +0.1307, -0.2648, +0.0104, -0.2447, -0.4669, -0.3711,
+ -0.1303, +0.3316, -0.4659, +0.0336, -0.3014, -0.0991, -0.1378,
+ -0.0605, -0.1779, -0.1278, +0.1260, -0.0011, +0.4265, -0.3470,
+ +0.2697, +0.2172, -0.0653, +0.4049, +0.1824, -0.1354, -0.2110,
+ +0.0009, +0.3092, -0.5611, +0.0180, +0.1930, +0.0349, +0.1076,
+ +0.1885, -0.1494, -0.3548, -0.5295, +0.1498, +0.1237, -0.0220,
+ -0.3594, -0.3349, +0.1907, -0.4955, -0.0173, +0.4271, +0.1763,
+ +0.2866, -0.2870, +0.0845, +0.4142, -0.2350, -0.1335, -0.1367,
+ +0.1219, +0.2963, -0.2772, +0.1208, -0.2441, +0.2727, -0.0634,
+ -0.0623, +0.1754, -0.2124, -0.0798, -0.2362, -0.0698, -0.0271,
+ +0.2826, +0.0072, -0.1003, -0.2082, -0.3241, -0.1478, +0.3451,
+ +0.4445, +0.0610, -0.3286, +0.0459, +0.1432, -0.2174, -0.1884,
+ -0.6035, -0.4182, -0.0975, -0.4158, -0.6764, -0.0864, -0.2861,
+ -0.1959, +0.3165, -0.2087, -0.2985, -0.1759, +0.7873, -0.1147,
+ +0.0419, +0.0908, -0.4405, -0.1625, +0.1020, -0.0612, +0.1512,
+ +0.1949, -0.4173, -0.0379, -0.2300, +0.0369, -0.8316, +0.4121,
+ -0.2343, +0.2659
+ ],
+ [
+ +0.1448, -0.1895, -0.5758, +0.2787, -0.4682, -0.3342, +0.0381,
+ +0.0380, -0.0829, -0.0685, +0.4234, -0.0387, -0.3712, -0.3754,
+ +0.1963, +0.2970, +0.0013, +0.1070, +0.1149, -0.2418, -0.6026,
+ +0.0593, -0.4548, +0.1573, +0.2813, -0.0247, +0.1728, +0.1163,
+ -0.2966, -0.1769, +0.4794, +0.4870, +0.3165, -0.4123, -0.5271,
+ -0.2275, -0.1985, +0.2085, -0.1278, -0.1492, +0.2016, +0.2230,
+ -0.5315, +0.3724, -0.2279, +0.3739, -0.2783, +0.2231, +0.2948,
+ +0.4648, -0.0578, -0.0601, +0.1040, +0.0309, -0.2686, +0.1441,
+ -0.0070, -0.1436, +0.0716, -0.7209, -0.1215, +0.1427, -0.1684,
+ -0.5173, -0.5214, +0.1143, +0.3508, +0.4406, +0.3437, +0.0705,
+ -0.2436, -0.3793, +0.2907, -0.2979, +0.0523, -0.3974, -0.2396,
+ +0.2500, +0.1000, +0.0783, -0.1054, -0.3239, -0.4000, -0.1940,
+ +0.2530, -0.0669, +0.4804, +0.1698, +0.2403, -0.1348, -0.1391,
+ +0.2299, -0.2724, +0.2885, -0.1325, -0.2227, +0.3584, -0.1698,
+ -0.0972, +0.5424, +0.0150, -0.1798, -0.3112, +0.3349, -0.2409,
+ -0.7392, +0.4496, +0.0811, +0.1761, -0.3272, -0.4055, -0.3795,
+ -0.1939, +0.2573, -0.0481, +0.4074, +0.0931, +0.0257, -0.0308,
+ +0.0334, +0.0584, -0.1926, +0.2368, +0.0248, -0.0502, +0.1326,
+ +0.1125, +0.0755
+ ],
+ [
+ -0.0107, -0.2142, -0.2136, -0.0900, +0.1327, -0.4218, +0.1241,
+ -0.0774, -0.3471, -0.2286, -0.1076, +0.3155, +0.0430, -0.2002,
+ +0.0599, +0.2265, -0.1557, +0.1386, +0.0237, +0.0503, +0.0536,
+ -0.0295, -0.1443, -0.3330, +0.1421, +0.1977, -0.4083, -0.0982,
+ -0.3459, -0.0667, +0.0876, -0.0609, +0.1196, -0.0744, -0.2453,
+ +0.2029, +0.4330, -0.0031, -0.1952, +0.3225, -0.1235, -0.2048,
+ +0.1982, -0.2002, -0.1531, -0.0925, +0.5035, +0.0646, +0.0497,
+ +0.2475, +0.3087, -0.2175, -0.3011, +0.2460, +0.1380, -0.1187,
+ +0.1174, +0.0075, +0.0148, +0.0186, +0.3429, -0.0175, +0.2382,
+ +0.0246, +0.1629, +0.0974, -0.0822, -0.0381, +0.0131, +0.0314,
+ +0.1902, -0.0336, -0.0286, +0.3354, +0.0584, -0.1462, -0.0521,
+ +0.0856, +0.5001, +0.5584, -0.3181, +0.1374, +0.0173, +0.1763,
+ +0.0470, +0.0321, +0.0882, -0.6272, -0.0242, +0.1606, -0.1326,
+ +0.2423, +0.2048, +0.0627, +0.4490, -0.0008, -0.0345, -0.1498,
+ -0.0128, -0.0674, +0.0725, +0.0137, -0.0963, +0.2060, -0.1878,
+ -0.3905, -0.1744, -0.2246, +0.0068, +0.4614, +0.3251, -0.3699,
+ -0.0626, -0.3641, -0.2819, +0.4233, +0.1520, +0.2650, -0.0881,
+ -0.0252, +0.1102, -0.0721, -0.0903, +0.1662, +0.0963, -0.2380,
+ -0.1902, -0.2317
+ ],
+ [
+ +0.1042, +0.0129, +0.0591, +0.1099, +0.0746, -0.3372, -0.1807,
+ -0.1851, +0.1693, -0.1435, -0.0469, -0.1883, +0.2842, -0.1832,
+ +0.2719, -0.1084, -0.6379, -0.0003, -0.2695, +0.2047, +0.1416,
+ -0.2237, +0.0454, -0.4013, -0.0354, +0.1184, -0.0375, -0.1689,
+ +0.0844, -0.2277, -0.0154, -0.1369, +0.2907, -0.1738, -0.0193,
+ +0.6037, +0.0534, -0.0553, -0.0678, +0.1018, -0.3696, +0.2454,
+ -0.4718, -0.0576, +0.2242, -0.4343, +0.1482, -0.2811, +0.1014,
+ +0.3586, -0.0633, -0.7224, -0.5258, +0.2335, -0.0151, -0.1089,
+ -0.1031, -0.1024, -0.3131, +0.1387, -0.4169, -0.0255, -0.0380,
+ +0.2975, +0.0797, -0.1790, -0.0312, -0.2449, +0.0739, -0.1094,
+ +0.1020, -0.3045, -0.0331, -0.1971, -0.2380, -0.2288, -0.0653,
+ +0.1428, +0.1224, +0.1660, +0.1744, -0.3307, -0.2782, +0.2870,
+ +0.0958, -0.3593, -0.1365, -0.1877, -0.2087, -0.2748, -0.2107,
+ +0.1078, +0.0981, +0.0487, +0.3310, +0.2330, +0.1792, -0.2385,
+ +0.0179, -0.4904, -0.4892, -0.2479, +0.0317, -0.0302, +0.1790,
+ +0.1996, +0.3029, +0.4338, -0.2445, -0.3634, -0.0027, +0.0235,
+ +0.0697, -0.2882, -0.6100, +0.0349, +0.1505, -0.0612, +0.2060,
+ +0.1764, +0.1363, +0.1618, +0.0997, -0.0475, -0.3545, -0.2044,
+ -0.2669, +0.1903
+ ],
+ [
+ -0.6690, -0.4061, +0.3611, -0.0323, -0.1826, +0.1533, +0.4289,
+ +0.4041, -0.0787, +0.1813, -0.2523, -0.2508, -0.1368, +0.2832,
+ +0.2357, +0.0674, +0.2526, -0.0948, +0.0302, -0.2113, -0.0810,
+ -0.1121, +0.0445, -0.3236, +0.1171, -0.2315, -0.1339, +0.3387,
+ +0.0430, +0.4383, -0.1667, +0.1842, -0.3316, +0.0995, -0.0591,
+ -0.2052, -0.0729, -0.1248, -0.1520, -0.0145, +0.4185, +0.2712,
+ +0.2678, -0.4791, +0.3847, +0.1647, +0.1293, -0.2229, -0.0904,
+ +0.1532, +0.1299, +0.3114, -0.5892, -0.0975, -0.0179, +0.1936,
+ -0.7019, -0.5316, +0.1220, +0.0368, +0.2585, +0.2070, +0.0252,
+ -0.3224, -0.1460, -0.0624, +0.4077, +0.0120, -0.1081, +0.3095,
+ -0.0344, +0.4012, -0.1926, -0.2384, +0.1148, +0.2245, -0.3863,
+ -0.0477, -0.0072, -0.1912, -0.2179, +0.1650, -0.1340, +0.1677,
+ -0.1649, -0.1423, +0.2822, -0.0503, -0.2050, -0.1846, -0.7356,
+ +0.0478, -0.0624, +0.0528, -0.1191, -0.1598, +0.2577, -0.0716,
+ +0.0590, +0.1427, -0.1972, -0.3610, -0.3062, -0.0018, +0.0144,
+ +0.1937, +0.1316, +0.0844, -0.3294, +0.0496, -0.0912, -0.0461,
+ -0.4000, -0.6219, -0.0409, +0.4040, -0.1048, -0.3856, +0.0791,
+ +0.2092, +0.0674, +0.0472, +0.0275, -0.4645, +0.1749, +0.2235,
+ -0.3431, -0.1454
+ ],
+ [
+ -0.0879, -0.0935, -0.1936, +0.5197, -0.1219, +0.3352, -0.0133,
+ -0.0712, +0.3519, -0.0763, -0.3465, -0.3300, +0.1453, -0.0745,
+ -0.0164, -0.3817, -0.1034, +0.0888, -0.2118, -0.0584, +0.3611,
+ -0.2505, +0.2527, +0.1162, +0.3649, +0.4534, -0.4969, +0.3260,
+ -0.1154, -0.0981, -0.1811, -0.5510, -0.0919, +0.3503, +0.4335,
+ -0.0208, +0.1106, -0.3258, -0.0314, +0.3403, -0.3097, +0.0929,
+ -0.1616, +0.0126, +0.0622, -0.5417, -0.1849, +0.1308, +0.3605,
+ +0.2931, -0.2155, -0.4689, +0.2639, +0.2679, -0.5587, -0.4971,
+ +0.2446, +0.6374, -0.5243, -0.3544, +0.3024, +0.0500, +0.0144,
+ -0.6006, +0.3731, -0.3271, +0.1171, -0.2156, -0.6001, +0.1787,
+ +0.1919, +0.0786, +0.0515, -0.2108, -0.0592, +0.0262, -0.0166,
+ +0.3152, +0.1522, +0.0947, +0.4798, -0.2640, +0.0736, +0.3035,
+ -0.0324, -0.1794, -0.0064, +0.5053, -0.0685, +0.0393, +0.6935,
+ -0.5272, -0.0964, +0.2572, +0.0731, -0.1272, -0.6316, -0.3586,
+ -0.0719, -0.0145, -0.1083, +0.0464, -0.2846, +0.2393, -0.2754,
+ -0.0077, -0.0043, +0.2452, -0.7249, -0.2202, +0.2876, -0.1782,
+ +0.1292, +0.3699, +0.3619, -0.0287, +0.3014, -0.2317, +0.1422,
+ +0.3546, +0.2010, +0.4777, +0.0428, -0.5397, -0.1933, -0.1243,
+ -0.1496, +0.0371
+ ],
+ [
+ -0.0777, +0.0994, +0.0355, +0.0499, +0.0912, -0.4674, +0.2269,
+ +0.0750, +0.2211, -0.2368, +0.1482, -0.1467, +0.4354, +0.0821,
+ +0.1812, -0.1193, -0.0613, +0.0097, +0.2792, +0.0710, -0.1106,
+ +0.1912, +0.2040, +0.2364, -0.2097, +0.0622, -0.2466, -0.4281,
+ +0.2414, +0.2629, +0.0371, -0.1220, -0.1557, +0.0406, +0.0109,
+ +0.0814, -0.1393, +0.1957, +0.0884, +0.0513, +0.2586, +0.1415,
+ -0.0214, -0.1080, -0.0189, -0.0288, -0.0338, -0.1389, -0.0299,
+ -0.2894, +0.2674, -0.4489, -0.9645, -0.3974, +0.1226, -0.6343,
+ -0.1116, +0.0569, +0.1864, -0.3531, -0.0256, -0.0620, -0.1864,
+ -0.0002, +0.1601, -0.1476, +0.0685, -0.7779, +0.0333, +0.0839,
+ +0.0528, -0.0343, +0.0053, -0.0560, +0.1991, +0.2184, +0.3194,
+ +0.2558, +0.1077, +0.2000, +0.2533, +0.7330, -0.0616, -0.0165,
+ -0.7192, +0.1282, +0.0961, -0.2649, -0.1855, -0.1103, +0.0819,
+ +0.0470, -0.1331, -0.0771, +0.0484, -0.0178, +0.2832, +0.2894,
+ +0.1649, +0.1913, +0.2145, +0.1483, -0.1606, +0.1300, -0.8030,
+ +0.1443, -0.1876, +0.1261, +0.0714, -0.0429, +0.3861, +0.1758,
+ +0.0043, -0.0500, +0.0689, +0.3115, +0.0667, -0.2230, +0.1086,
+ +0.2952, -0.3109, -0.3093, +0.0554, -0.0245, -0.0397, +0.2274,
+ -0.2004, +0.3354
+ ],
+ [
+ +0.3834, -0.2970, +0.0693, -0.0619, -0.2312, +0.0044, +0.1783,
+ -0.0599, +0.0585, +0.0275, +0.4338, -0.0722, -0.0090, -0.0405,
+ -0.3517, +0.1827, +0.1690, -0.2387, +0.0735, -0.5833, -0.0576,
+ -0.0895, -0.1242, +0.1094, +0.1448, +0.0156, -0.2802, -0.2083,
+ +0.1598, -0.2769, -0.3661, +0.1990, -0.3264, -0.8629, +0.1671,
+ -0.1886, -0.0530, -0.0574, -0.1298, +0.2935, -0.4790, -0.5351,
+ -0.1290, +0.3031, +0.2099, -0.1599, -0.3362, -0.2019, +0.3001,
+ +0.2095, -0.2143, -0.3300, +0.0041, +0.0362, -0.1581, +0.2439,
+ -0.0697, +0.2571, -0.0095, -0.0982, +0.0056, -0.1928, -0.4881,
+ -0.0052, -0.3691, +0.0098, -0.2662, -0.1979, -0.0825, -0.2171,
+ -0.2089, +0.0930, +0.3293, +0.1200, -0.5116, -0.2453, +0.2801,
+ -0.1298, +0.0679, -0.0766, -0.2082, +0.2169, +0.2892, +0.3407,
+ -0.1135, +0.4344, +0.2666, +0.0543, -0.1126, -0.0424, +0.2620,
+ +0.4735, -0.1789, +0.0870, +0.3178, +0.5883, +0.2862, +0.0072,
+ -0.0330, +0.0150, +0.1277, -0.3052, -0.1006, +0.1095, -0.5257,
+ -0.0278, -0.0217, +0.4799, -0.1704, -0.0741, +0.4283, +0.0792,
+ +0.2134, -0.0473, +0.1116, -0.1416, -0.0489, -0.1338, +0.1532,
+ +0.0737, -0.0105, -0.4169, -0.1468, +0.0573, -0.7244, -0.0113,
+ -0.0027, -0.0978
+ ],
+ [
+ +0.5952, +0.3408, +0.0172, +0.2719, -0.0426, +0.4306, -0.2634,
+ +0.1054, -0.0128, -0.2360, -0.2531, -0.2114, -0.3016, -0.1541,
+ +0.4044, +0.1914, -0.2081, -0.2766, -0.1250, -0.4496, -0.0649,
+ +0.1175, -0.1754, +0.0928, +0.0995, -0.1906, +0.1887, -0.1689,
+ -0.2972, -0.4089, +0.0109, +0.1868, +0.3658, +0.1497, -0.3773,
+ -0.1926, -0.1043, +0.3018, -0.1868, +0.0769, -0.1214, +0.2259,
+ +0.1076, -0.3811, +0.3021, -0.0662, -0.1938, +0.0730, -0.0141,
+ +0.0559, -0.5150, +0.0252, +0.2179, -0.1829, -0.1317, -0.0134,
+ +0.3307, +0.1064, -0.2619, -0.0376, -0.2149, -0.1717, -0.1534,
+ -0.1198, -0.3179, +0.1305, -0.2788, +0.0140, +0.0286, +0.1083,
+ -0.0183, +0.2554, -0.0158, +0.0695, +0.2224, +0.0491, -0.3450,
+ +0.0567, +0.1413, +0.4495, +0.3825, +0.3585, +0.3753, -0.0599,
+ -0.0589, -0.1657, +0.1589, +0.0386, +0.1114, -0.1198, -0.0319,
+ +0.1412, -0.2602, -0.3174, +0.0411, -0.4132, -0.4969, +0.0281,
+ +0.1082, -0.2284, -0.2720, -0.0416, +0.0901, +0.0221, -0.0072,
+ -0.1729, +0.0065, -0.0727, -0.2902, -0.0596, +0.3046, -0.2508,
+ +0.2946, +0.1691, +0.1094, -0.0917, -0.3400, +0.3388, +0.2042,
+ -0.4066, +0.0417, +0.3045, +0.2068, -0.2250, +0.6056, +0.2218,
+ +0.0393, +0.4209
+ ],
+ [
+ -0.2163, -0.6735, +0.0472, +0.1662, -0.5386, -0.0774, +0.3303,
+ -0.3197, -0.2423, +0.0745, -0.0520, -0.1698, +0.2596, +0.2897,
+ +0.2793, -0.0700, -0.5526, -0.0755, -0.1457, +0.1181, -0.2148,
+ +0.1500, +0.2115, +0.1809, -0.0527, +0.0106, +0.2840, -0.1520,
+ +0.0891, +0.3374, -0.1232, -0.3531, -0.0097, +0.2622, -0.2089,
+ -0.2767, -0.0589, +0.2649, -0.0973, +0.2521, -0.4166, -0.0252,
+ -0.1418, -0.2941, -0.1256, +0.1203, -0.8522, +0.2147, -0.4110,
+ -0.1044, -0.1519, -0.0206, -0.0897, +0.2957, +0.0209, +0.2436,
+ -0.4134, -0.4883, +0.1503, -0.4706, -0.3203, +0.2962, -0.3609,
+ -0.1774, -0.0657, +0.4048, +0.2880, -0.2606, -0.1999, -0.3142,
+ -0.2496, +0.0014, -0.2788, -0.2473, -0.1292, -0.3910, -0.1895,
+ +0.2267, +0.2975, -0.1391, -0.0612, -0.3902, -0.2660, -0.2387,
+ -0.1752, +0.0437, -0.5681, -0.1894, -0.1217, +0.0587, -0.3576,
+ +0.0542, -0.1070, +0.0588, +0.0074, -0.2412, -0.1207, +0.1427,
+ +0.0138, +0.2233, -0.2847, -0.5626, +0.1141, +0.0012, -0.1819,
+ -0.5993, -0.1351, -0.3189, -0.0335, +0.2624, -0.2439, -0.0997,
+ -0.0933, -0.0714, +0.2292, +0.2202, +0.1539, -0.0646, -0.1718,
+ +0.2672, +0.0056, +0.2323, +0.1605, +0.1107, +0.1549, +0.0173,
+ -0.4915, -0.0520
+ ],
+ [
+ -0.2395, +0.1082, -0.2151, -0.2240, -0.2508, +0.0407, +0.1677,
+ -0.0084, +0.2400, -0.2400, -0.2007, -0.5287, -0.0877, +0.0286,
+ -0.1740, -0.2005, -0.2105, -0.1344, +0.1480, -0.2683, +0.2106,
+ -0.2851, -0.1725, -0.2883, -0.0091, +0.0635, -0.0457, -0.0655,
+ +0.0114, -0.1064, +0.0256, -0.4652, +0.0746, -0.1420, +0.0475,
+ -0.3308, -0.0352, -0.2817, +0.2106, -0.4369, +0.0512, +0.1639,
+ -0.0393, +0.0127, -0.1861, +0.3706, -0.1326, -0.3111, -0.1802,
+ +0.0468, -0.8695, -0.3946, +0.2512, +0.2067, -0.0320, +0.1788,
+ +0.1295, +0.1133, -0.1315, +0.1520, -0.0059, +0.0645, +0.1516,
+ -0.0698, +0.1031, +0.3508, +0.0518, +0.0838, -0.0202, +0.0608,
+ +0.1026, -0.2504, -0.3488, +0.0680, +0.0823, -0.0485, -0.2392,
+ +0.1838, +0.2340, +0.0864, -0.8238, -0.0096, -0.7539, -0.6396,
+ -0.0508, -0.2817, +0.0456, +0.2159, -0.0016, +0.0315, -0.0073,
+ +0.0620, +0.1535, -0.1015, +0.0306, +0.0454, -0.3272, -0.0547,
+ -0.1030, -0.5685, -0.2921, +0.3394, -0.2310, +0.2159, -0.3338,
+ -0.0358, +0.0009, -0.0201, +0.0131, -0.0974, -0.1829, +0.1706,
+ -0.2684, -0.0444, +0.1660, +0.3105, -0.2563, -0.0454, -0.0842,
+ -0.1093, -0.0536, +0.0302, -0.0972, -0.2005, +0.0107, +0.0732,
+ -0.0438, +0.0663
+ ],
+ [
+ +0.0686, -0.1319, +0.1578, -0.3115, -0.1053, +0.1549, +0.2026,
+ +0.3332, -0.1355, +0.2737, -0.0735, +0.1123, +0.4531, +0.2477,
+ -0.0257, +0.1564, -0.3674, -0.1256, +0.1678, +0.2737, +0.3228,
+ +0.2598, +0.3361, -0.1607, -0.5808, -0.1166, +0.2046, +0.1681,
+ +0.2143, -0.0169, +0.1161, -0.2318, +0.0337, +0.1461, +0.0441,
+ +0.2919, -0.4899, -0.0727, +0.0982, +0.2526, +0.0552, +0.6004,
+ +0.5736, -0.2223, -0.5650, +0.1801, +0.3024, -0.3968, +0.1984,
+ -0.2853, -0.0482, -0.1149, -0.0921, +0.0218, +0.0841, +0.2279,
+ -0.1176, -0.3152, -0.1646, -0.1158, -0.1729, +0.0370, -0.3291,
+ -0.5383, +0.0670, -0.3762, -0.6796, -0.0860, +0.1358, +0.1148,
+ +0.3606, -0.1959, -0.1589, -0.0206, -0.1312, -0.4897, +0.3045,
+ -0.1620, +0.2109, -0.3497, -0.1020, -0.8788, -0.1518, -0.2748,
+ +0.2034, +0.0852, -0.3075, -0.4856, -0.2341, -0.2566, +0.1598,
+ +0.0043, -0.3940, -0.3725, -0.0530, -0.1074, +0.2087, -0.2613,
+ -0.0982, -0.0016, -0.0411, +0.2699, +0.2735, -0.2934, -0.1908,
+ +0.4955, -0.1301, -0.1888, -0.4906, +0.1670, +0.1018, +0.0266,
+ +0.1781, +0.0031, -0.1535, -0.2982, -0.0919, +0.1921, -0.1798,
+ -0.0400, +0.0564, +0.1094, -0.0851, -0.3558, +0.2266, +0.1664,
+ -0.4936, +0.1331
+ ],
+ [
+ -0.0829, +0.2182, -0.2100, -0.3694, +0.2186, -0.4523, -0.1754,
+ -0.0425, -0.0305, -0.2166, -0.0025, -0.2198, -0.1057, -0.6204,
+ -0.1104, -0.2452, -0.0211, +0.5433, +0.2327, +0.1093, -0.5577,
+ +0.3080, +0.1366, -0.1060, -0.0860, +0.0222, -0.5332, +0.0402,
+ -0.0464, -0.2748, +0.3140, -0.2646, -0.2442, -0.0596, +0.0979,
+ +0.0090, +0.4731, -0.1337, -0.0610, +0.3120, +0.0909, +0.0894,
+ -0.0416, -0.1903, +0.2731, +0.1343, -0.0011, +0.2264, +0.2334,
+ -0.0798, -0.2831, -0.4700, +0.0756, +0.0981, -0.0202, -0.8060,
+ -0.0174, -0.3160, -0.1816, -0.3639, -0.5384, -0.1215, +0.1117,
+ +0.0785, +0.1101, +0.0604, -0.4289, +0.0027, +0.4064, +0.0620,
+ +0.0758, +0.1001, +0.4822, -0.0900, +0.3217, +0.1433, -0.2441,
+ +0.0867, -0.2211, +0.2055, +0.0874, -0.3285, -0.3667, -0.3910,
+ +0.0201, +0.0028, -0.0189, -0.0373, -0.4464, -0.2321, +0.1192,
+ +0.0026, +0.0681, -0.0103, -0.4804, +0.0796, -0.1562, +0.3017,
+ -0.1060, -0.1943, +0.1367, -0.1407, -0.0056, -0.1167, +0.3077,
+ +0.2067, +0.1155, -0.0106, +0.0584, +0.1148, -0.0285, +0.2770,
+ +0.2312, +0.0976, +0.1672, +0.1084, +0.0535, +0.2593, +0.1339,
+ -0.2000, -0.1449, -0.1224, -0.3657, +0.0403, +0.0104, +0.0909,
+ -0.0858, -0.1809
+ ],
+ [
+ +0.2250, -0.0840, -0.1109, +0.4521, -0.1736, -0.4552, -0.4446,
+ -0.2480, +0.2552, +0.1624, +0.3405, -0.3831, +0.0898, +0.3713,
+ -0.0383, +0.0324, +0.0093, -0.0135, +0.4027, +0.1250, -0.4553,
+ +0.4680, -0.1777, -0.2760, -0.0973, +0.0846, +0.2103, -0.1712,
+ +0.2130, -0.2609, -0.1162, -0.5625, +0.3581, -0.1252, +0.0018,
+ -0.1454, +0.0153, +0.0041, -0.8839, +0.3062, -0.0624, +0.3578,
+ +0.1142, -0.6404, +0.1066, +0.1546, -0.1064, -0.1424, -0.2725,
+ +0.2147, -0.4004, +0.1040, -0.0824, +0.0742, +0.0688, +0.0577,
+ -0.2756, -0.3082, +0.0641, -0.0017, -0.0118, -0.3003, -0.3433,
+ +0.2483, -0.2644, +0.1392, -0.0649, +0.0865, +0.2920, -0.1501,
+ -0.0798, -0.1315, -0.2475, -1.0970, -0.2964, +0.0029, +0.1222,
+ +0.1754, +0.3431, +0.2812, -0.2805, +0.1654, +0.1724, +0.1199,
+ +0.1651, +0.2226, +0.2878, -0.1049, +0.0502, -0.0128, +0.1162,
+ +0.0814, +0.0784, -0.1172, -0.0458, -0.0220, +0.2004, +0.0171,
+ -0.3293, -0.3714, +0.2733, -0.4124, +0.1587, -0.2548, -0.2213,
+ -0.2156, +0.1612, +0.0821, +0.1077, -0.0277, -0.2058, +0.1690,
+ +0.0936, -0.1400, -0.3448, -0.3278, +0.2127, -0.0748, +0.0359,
+ -0.1594, +0.2732, +0.3175, +0.0153, -0.5548, -0.1313, +0.1161,
+ +0.6082, -0.6926
+ ],
+ [
+ -0.0732, +0.2253, +0.0032, -0.0549, -0.2564, +0.3007, +0.3424,
+ +0.0831, -0.1338, -0.3387, -0.0127, +0.0345, -0.0145, -0.1680,
+ +0.1195, +0.0837, -0.0707, -0.0937, +0.2572, -0.0441, -0.0152,
+ -0.4240, -0.3129, -0.0871, +0.0003, -0.3298, -0.2884, +0.1462,
+ +0.2674, -0.2651, -0.2476, +0.0750, +0.1392, -0.3641, +0.2545,
+ +0.0877, +0.3429, +0.1779, -0.1412, -0.1485, -0.0703, +0.1189,
+ +0.0306, +0.1297, -0.0944, -0.1656, +0.0831, -0.1307, +0.1673,
+ +0.3148, -0.2151, -0.1995, +0.1090, +0.1548, -0.3994, +0.2153,
+ +0.1078, +0.1781, -0.0598, -0.4006, -0.5840, +0.0388, +0.0068,
+ +0.1585, +0.0454, -0.2677, -0.0196, -0.0652, -0.0635, -0.0819,
+ +0.4911, +0.2954, +0.1933, -0.0785, +0.0523, -0.0260, -0.2621,
+ +0.0674, +0.1783, +0.1606, -0.0044, +0.0092, -0.1628, +0.5500,
+ -0.4279, -0.5668, +0.3769, +0.0797, -0.0083, -0.2193, -0.3738,
+ -0.2367, +0.0116, -0.2397, +0.0234, +0.2543, -0.1666, +0.2266,
+ +0.4588, -0.0574, +0.3247, -0.4261, -0.0089, +0.4571, +0.0313,
+ -0.4023, -0.0465, -0.0825, +0.0458, +0.1550, -0.3583, +0.0507,
+ +0.2776, -0.0226, -0.1508, -0.6477, +0.1156, +0.1034, +0.2133,
+ +0.1774, +0.4070, +0.0463, -0.0209, +0.0353, -0.4120, +0.0919,
+ -0.0687, -0.0749
+ ],
+ [
+ -0.2686, -0.0329, +0.2912, -0.1666, -0.2764, +0.3305, -0.0058,
+ -0.4653, +0.1527, +0.1564, -0.4896, +0.0291, +0.3071, -0.7088,
+ -0.3624, -0.2830, +0.0256, -0.3474, -0.3822, -0.2457, -0.4814,
+ -0.2442, -0.3495, -0.2978, -0.4703, +0.3340, +0.3642, -0.0408,
+ +0.0182, -0.1530, -0.1611, +0.0198, -0.0378, +0.2289, +0.0803,
+ -0.5098, +0.1630, +0.3059, +0.4614, -0.0014, -0.3160, +0.0719,
+ +0.0972, -0.2106, -0.0173, -0.0813, -0.4421, -0.2463, -0.7197,
+ -0.5828, -0.0493, -0.0797, +0.3699, -0.0639, +0.1526, +0.2862,
+ -0.7293, -0.2326, +0.0791, +0.2545, +0.0515, -0.7931, -0.3388,
+ +0.1758, +0.3957, -0.1495, +0.0333, -0.3643, +0.0482, -0.0024,
+ +0.0111, -0.2663, +0.4862, +0.1918, -0.4241, +0.2587, -0.0027,
+ -0.0372, +0.3184, +0.3913, +0.0524, -0.3319, -0.0694, +0.2023,
+ -0.2400, +0.1287, -0.2312, -0.0678, -0.1319, +0.2564, +0.0159,
+ -0.0392, +0.0918, +0.1219, -0.2442, +0.0310, -0.0213, -0.2321,
+ +0.1482, +0.1481, -0.2212, -0.1167, -0.1511, +0.3179, +0.2984,
+ -0.0132, -0.3760, +0.2300, -0.2227, +0.0670, -0.2268, +0.1566,
+ +0.0284, +0.2196, -0.0754, -0.1894, -0.5378, -0.2590, +0.0665,
+ -0.0787, -0.0238, +0.0843, +0.0179, +0.0325, +0.1260, +0.0748,
+ +0.3066, +0.2551
+ ],
+ [
+ +0.2968, -0.2520, +0.2843, -0.6742, +0.1921, +0.0292, -0.1531,
+ -0.0155, -0.5983, -0.1721, -0.2882, -0.0314, +0.1263, -0.2607,
+ -0.3498, +0.1108, +0.0609, -0.0140, -0.0950, -0.0512, -0.0920,
+ +0.0698, -0.5251, +0.3910, +0.0909, +0.1045, -0.2000, -0.1434,
+ -0.4206, -0.0071, +0.2461, +0.0603, -0.2128, +0.0181, +0.1641,
+ +0.2612, +0.2315, -0.3620, +0.0315, -0.3138, +0.2062, -0.0888,
+ -0.3100, -0.3093, +0.0671, +0.1117, +0.1244, -0.2791, +0.3243,
+ +0.1450, -0.2218, +0.1180, +0.0675, -0.1432, +0.1664, -0.0586,
+ +0.1428, -0.0584, +0.2146, -0.0220, +0.2256, -0.0408, -0.4546,
+ -0.4819, +0.0717, +0.5182, +0.1655, -0.1134, +0.1405, +0.0945,
+ -0.0972, -0.0684, -0.2629, +0.1064, -0.1235, +0.3470, -0.3405,
+ -0.1843, +0.2565, +0.1616, +0.3482, +0.1659, +0.0035, -0.1445,
+ +0.2763, -0.5614, +0.1946, +0.0868, +0.1259, +0.1728, +0.0006,
+ -0.3359, -0.5973, +0.2830, +0.0261, +0.3082, +0.0400, -0.0577,
+ -0.0499, -0.0597, -0.3174, +0.0512, -0.0551, +0.3253, -0.1913,
+ -0.0550, -0.0718, -0.1346, -0.4629, +0.3681, -0.1247, +0.0814,
+ -0.0478, -0.0722, -0.4642, +0.2460, +0.0200, -0.2498, +0.1885,
+ +0.0868, -0.0035, +0.1116, +0.3947, -0.2608, +0.0356, -0.0511,
+ +0.5914, +0.0289
+ ],
+ [
+ -0.0472, +0.0291, -0.2015, -0.3400, -0.0293, +0.1229, -0.1336,
+ +0.2527, +0.0665, +0.2563, +0.3501, -0.0805, +0.1462, -0.6395,
+ -0.2547, -0.1008, -0.3647, +0.2239, -0.2914, -0.1160, -0.6349,
+ +0.0306, -0.5290, -0.3486, +0.0615, -0.4155, -0.0256, -0.0700,
+ +0.0291, +0.0889, -0.0647, +0.1953, +0.0807, +0.1264, -0.1552,
+ +0.1852, +0.2415, +0.1817, +0.1409, +0.0679, -0.1280, -0.0297,
+ +0.2072, -0.0792, -0.1122, -0.2793, -0.0724, -0.2612, +0.0395,
+ +0.0733, -0.2032, +0.1459, -0.2105, +0.0847, -0.0401, +0.0033,
+ -0.1316, +0.0334, -0.1861, -0.0395, -0.2530, -0.0225, -0.1109,
+ -0.0984, +0.0103, -0.1257, -0.3871, -0.1836, +0.0309, +0.1372,
+ -0.0636, -0.0293, +0.1551, -0.5412, +0.0332, -0.2848, -0.2884,
+ -0.0788, -0.2465, -0.0299, -0.0706, -0.3344, -0.2211, -0.0945,
+ +0.2794, +0.2708, -0.4605, -0.1758, +0.4140, -0.0400, -0.2299,
+ -0.1933, +0.3417, -0.1830, +0.1497, -0.2801, +0.2764, +0.1630,
+ -0.1395, -0.1100, -0.0719, -0.3203, -0.1424, -0.2747, +0.1537,
+ -0.0182, +0.1668, -0.0978, +0.2400, -0.1709, -0.6090, +0.1737,
+ +0.2128, -0.4995, +0.3784, -0.3555, -0.0216, +0.3171, +0.0818,
+ +0.1288, +0.1428, -0.2269, -0.4011, -0.1041, -0.4746, -0.0047,
+ +0.4549, -0.0321
+ ],
+ [
+ -0.1855, +0.1624, +0.3269, -0.0836, +0.0791, +0.2012, -0.1678,
+ -0.2719, -0.0091, -0.0395, -0.1173, +0.2669, -0.1938, +0.2195,
+ -0.0345, -0.1397, -0.7391, -0.0199, -0.2329, -0.1489, +0.0571,
+ +0.2921, -0.1523, +0.1569, -0.2668, -0.5009, -0.2381, +0.0651,
+ -0.3336, -0.2194, -0.3238, -0.5012, +0.1450, +0.1525, -0.0115,
+ -0.5428, +0.3294, +0.2525, -0.3526, -0.4212, -0.1837, +0.2515,
+ +0.4614, -0.1264, -0.3103, +0.1074, +0.0827, -0.1964, +0.2053,
+ +0.2600, +0.0388, -0.2054, +0.1345, +0.0519, -0.1489, +0.6301,
+ -0.9479, +0.2510, -0.0498, -0.0527, +0.2920, -0.0529, -0.1293,
+ +0.2472, +0.1368, -0.0785, -0.6581, +0.2106, -0.2905, -0.3379,
+ +0.3484, +0.1134, -0.1174, +0.2157, -0.2320, +0.1710, +0.4458,
+ +0.2454, -0.0388, +0.3026, -0.1289, -0.3110, +0.1891, +0.1288,
+ +0.1204, +0.0897, +0.2136, -0.0600, +0.0676, +0.0901, +0.4644,
+ -0.3749, +0.3909, -0.0519, +0.2061, -0.1888, -0.0771, +0.0332,
+ -0.0471, -0.1393, +0.0479, +0.0953, -0.2018, -0.0382, +0.5181,
+ +0.5044, -0.2500, +0.3214, +0.3163, +0.1999, -0.0691, +0.1075,
+ +0.1390, -0.1640, -0.1320, -0.0301, +0.3794, +0.3905, +0.0873,
+ +0.1993, -0.0542, +0.0399, -0.2078, -1.0854, +0.1759, +0.1768,
+ -0.0782, -0.6677
+ ],
+ [
+ +0.4761, -0.0663, +0.2249, +0.4687, +0.4725, +0.2613, +0.1594,
+ +0.1505, +0.4235, +0.6645, -0.2783, -0.0612, -0.1099, -0.1565,
+ -0.2852, -0.1671, -0.3037, +0.0379, -0.3604, -0.1752, +0.2092,
+ -0.2202, +0.0912, +0.0729, -0.3226, +0.2457, +0.3629, -0.1730,
+ +0.1914, -0.3294, -0.2261, +0.2895, +0.1302, -0.1379, -0.4952,
+ -0.1735, +0.1255, +0.1457, -0.2376, +0.4720, -0.1775, -0.2509,
+ -0.0624, -0.3632, -0.1322, -0.2055, +0.2150, -0.0768, -0.2688,
+ +0.0285, +0.2131, -0.0390, -0.1769, +0.0622, -0.5151, -0.2979,
+ -0.1739, -0.0890, -0.5254, -0.1478, +0.1088, +0.0856, +0.1429,
+ -0.1501, -0.1204, +0.0028, +0.1770, +0.1505, +0.1766, -0.2425,
+ +0.0513, +0.1667, -0.1476, +0.0032, +0.2798, +0.2076, -0.2384,
+ -0.2674, -0.0056, -0.3287, +0.1107, -0.2459, +0.3851, +0.1876,
+ -0.7106, +0.1685, -0.0777, -0.0396, +0.0233, -0.3481, -0.0286,
+ +0.0261, +0.2921, +0.1093, +0.5630, -0.2347, -0.0734, +0.0249,
+ -0.1631, -0.1040, -0.1983, +0.0782, +0.0169, -0.0628, +0.3248,
+ -0.1194, -0.0962, +0.0759, +0.0300, +0.2348, -0.1425, +0.2524,
+ -0.0761, +0.3306, -0.3798, +0.4838, -0.1037, -0.2962, +0.1173,
+ +0.1771, -0.0053, -0.0782, +0.2047, -0.4244, -0.5660, -0.2483,
+ -0.0742, +0.1371
+ ],
+ [
+ -0.7837, +0.3095, -0.1549, +0.4699, +0.2115, -0.0081, +0.0906,
+ -0.5313, +0.0900, +0.1685, -0.0934, +0.2521, +0.0657, +0.0308,
+ +0.3482, +0.2503, -0.2744, -0.3240, -0.0740, +0.1500, -0.2711,
+ -0.8182, +0.1058, -0.6611, +0.1644, +0.2737, -0.1406, +0.3843,
+ +0.1629, -0.2753, +0.1177, -0.0826, +0.0228, -0.3950, +0.0955,
+ +0.1949, -0.0512, -0.4978, +0.6406, +0.4895, -0.0706, +0.0241,
+ +0.0077, +0.2287, -0.2623, -0.0209, -0.4220, +0.0309, -0.4720,
+ +0.0209, -0.1377, +0.0795, -0.1714, +0.3406, +0.0194, +0.2401,
+ +0.0310, -0.1351, -0.3521, +0.0880, +0.0080, -0.0377, +0.0105,
+ +0.0208, +0.4825, +0.2324, -0.2039, -0.1672, +0.1403, -0.2034,
+ -0.1150, -0.3834, +0.2307, -0.2626, +0.3508, +0.0194, +0.0509,
+ +0.0261, -0.0052, +0.3438, +0.3812, -0.3947, +0.1851, -0.2038,
+ +0.2409, +0.0487, +0.1921, -0.0589, -0.0823, -0.1547, -0.0094,
+ +0.2807, -0.1863, +0.2581, -0.5180, +0.2735, +0.0679, -0.0425,
+ +0.2492, +0.0626, -0.2417, +0.1224, -0.4576, +0.0019, -0.2846,
+ +0.1742, +0.0963, +0.0151, +0.0683, -0.0064, -0.2868, -0.5366,
+ +0.2815, -0.4247, -0.0912, -0.3046, +0.2440, -0.1965, +0.3091,
+ -0.0060, -0.2051, -0.1130, -0.5411, -0.0762, -0.1445, -0.1454,
+ +0.5050, +0.1822
+ ],
+ [
+ +0.3144, +0.3819, +0.2419, +0.0922, +0.0429, -0.3290, +0.1856,
+ +0.4736, -0.1334, -0.0262, +0.3854, +0.4328, -0.3297, +0.0124,
+ +0.3946, -0.2004, -0.1335, -0.3736, -0.0125, +0.2646, +0.0420,
+ +0.1566, +0.4801, +0.1118, +0.2162, +0.1331, +0.3887, +0.0611,
+ +0.0682, -0.1750, +0.0144, -0.5737, +0.2758, +0.5027, -0.1053,
+ +0.0747, +0.2747, -0.5884, +0.1063, +0.1297, +0.2853, -0.2151,
+ +0.0384, +0.1121, +0.1156, -0.3261, -0.2196, -0.2840, +0.2635,
+ -0.2653, +0.2610, +0.3597, +0.2027, +0.3429, +0.1128, +0.2219,
+ +0.0890, -0.9434, -0.4802, +0.0291, +0.1028, -0.2123, -0.7981,
+ -0.0337, +0.1043, -0.1856, -0.1165, -0.7604, +0.4207, +0.1316,
+ -0.1630, -0.1340, +0.2341, +0.0638, +0.0082, +0.4444, -0.0889,
+ +0.2510, -0.1293, +0.1636, +0.1292, +0.1792, +0.5046, +0.3834,
+ +0.3265, -0.2243, -0.0312, +0.5578, +0.0375, +0.1042, +0.6282,
+ +0.2495, +0.0827, -0.0625, -0.3792, +0.2411, -0.3971, +0.1935,
+ -0.0277, +0.0583, +0.0248, +0.0072, -0.0745, +0.1451, +0.4696,
+ -0.2705, -0.3263, -0.1435, +0.0060, +0.2168, +0.0691, +0.1550,
+ -0.0545, -0.4145, -0.1294, -0.1860, +0.0599, +0.0933, +0.3489,
+ -0.0588, -0.6730, -0.0014, -0.1882, -0.0109, +0.3134, +0.0732,
+ +0.2342, -0.0701
+ ],
+ [
+ -0.4699, +0.1514, -0.0154, -0.3478, +0.0343, -0.0497, -0.0152,
+ +0.0470, -0.2834, +0.2245, +0.2150, +0.2684, +0.1975, +0.1795,
+ +0.0021, -0.1774, -0.2690, -0.1259, +0.0359, +0.2673, +0.2466,
+ -0.6775, +0.1818, -0.2542, -0.0860, +0.0557, -0.0839, +0.1314,
+ +0.4670, +0.0573, -0.4284, +0.0683, +0.0504, -0.2500, +0.0094,
+ +0.1884, -0.0390, +0.0074, +0.1370, +0.1728, -0.1499, +0.2658,
+ +0.1145, +0.4719, -0.0818, -0.0320, -0.4460, +0.0367, +0.0119,
+ -0.2110, +0.2144, -0.3712, +0.0372, -0.3181, +0.0912, +0.4061,
+ -0.3131, -0.1783, +0.2388, -0.1973, +0.4523, -0.2634, +0.1795,
+ -0.4581, +0.1947, -0.0949, +0.3675, -0.1383, -0.1664, +0.0202,
+ +0.1948, +0.2591, +0.2297, -0.0015, +0.0871, +0.0261, +0.4011,
+ -0.1088, +0.0393, +0.4041, +0.0308, +0.0876, +0.2043, -0.2669,
+ -0.0601, -0.4393, +0.3183, -0.3609, -0.0744, -0.2842, -0.1721,
+ -0.3318, -0.4258, +0.1342, -0.0367, +0.1849, -0.0477, -0.0253,
+ -0.0246, +0.5795, +0.2513, -0.1796, +0.0389, -0.2756, -0.2147,
+ -0.1793, -0.3558, +0.1717, -0.5249, -0.2464, -0.2796, +0.0084,
+ -0.4634, -0.4674, +0.0974, -0.6623, -0.1960, -0.3836, +0.3861,
+ +0.0189, +0.0154, +0.0476, -0.2305, +0.5758, +0.2525, -0.0329,
+ +0.1363, +0.0140
+ ],
+ [
+ +0.1584, -0.2431, -0.4291, -0.0556, -0.0026, -0.0591, +0.0079,
+ +0.2857, +0.5122, -0.0429, +0.0946, -0.0176, -0.1437, -0.4700,
+ -0.1170, -0.0089, -0.9586, +0.0163, -0.1208, -0.0524, -0.5580,
+ -0.0817, +0.2039, +0.0742, +0.1551, +0.1373, +0.2931, +0.1389,
+ +0.0872, +0.4183, +0.2291, -0.1455, -0.0433, +0.0148, -0.0700,
+ -0.1430, +0.2038, +0.0410, +0.2482, +0.0350, -0.1243, +0.4496,
+ -0.4407, -0.0929, -0.2963, +0.0717, -0.4156, +0.1121, -0.1748,
+ -0.1919, +0.0048, +0.2755, +0.0206, +0.1184, -0.0737, -0.0412,
+ +0.2178, +0.2808, +0.1509, +0.1811, +0.4659, -0.1062, +0.1664,
+ -0.2212, -0.0014, -0.1563, -0.1154, +0.1744, +0.3064, -0.1688,
+ +0.1446, -0.0575, -0.0905, -0.3147, -0.0151, +0.0908, -0.2138,
+ -0.0062, -0.4875, +0.1172, -0.4038, -0.0998, -0.4557, -0.2347,
+ -0.2588, +0.4226, -0.0394, -0.3219, -0.1141, -0.0317, +0.4031,
+ -0.0246, -0.1727, +0.3119, -0.0216, -0.0531, -0.5102, +0.3536,
+ -0.0753, -0.0344, -0.0014, +0.1370, +0.2231, -0.1346, +0.1867,
+ +0.0349, +0.5278, -0.1242, +0.2596, +0.0785, -0.0118, -0.5340,
+ -0.2786, +0.3199, +0.5706, -0.0367, -0.1211, +0.1921, -0.0304,
+ -0.0165, -0.7356, -0.0265, -0.0345, -0.0259, -0.1789, +0.2872,
+ +0.0105, +0.0023
+ ],
+ [
+ -0.0948, -0.6136, +0.1338, +0.2859, +0.2843, +0.1589, +0.3171,
+ +0.1116, +0.0251, -0.3971, +0.1193, -0.0195, +0.1007, -0.0852,
+ -0.4118, -0.6561, +0.1210, -0.3247, -0.1158, +0.2462, +0.0070,
+ +0.7074, -0.1219, +0.3642, -0.1473, +0.0770, -0.2086, +0.0595,
+ +0.2505, +0.1809, -0.2073, -0.2064, -0.0406, -0.1938, +0.5908,
+ +0.2508, +0.0160, -0.3687, -0.1630, -0.0886, -0.1468, +0.1621,
+ -0.3309, +0.0106, -0.1562, -0.3625, -0.1486, +0.0956, -0.1234,
+ +0.2483, +0.1274, -0.0325, -0.5725, -0.1404, +0.2292, +0.1529,
+ +0.1485, -0.6426, -0.1224, -0.7842, -0.6767, -0.2635, +0.2111,
+ -0.1074, -0.0401, +0.2259, -0.2166, -0.0548, -0.5997, +0.1720,
+ +0.3251, -0.3682, -0.5274, +0.3112, +0.1504, +0.1655, -0.1621,
+ +0.3063, -0.0267, +0.0948, +0.1665, +0.0362, -0.2802, +0.1145,
+ -0.2702, +0.1772, -0.0679, -0.0066, +0.1101, -0.3134, +0.0609,
+ -0.3491, -0.3556, -0.0979, +0.1742, +0.1731, -0.1578, -0.1343,
+ +0.2913, -0.2018, -0.0909, +0.1385, -0.2056, +0.3355, -0.1970,
+ -0.5646, -0.1139, -0.2043, -0.2269, -0.0852, +0.0780, -0.4946,
+ -0.0939, -0.1656, +0.1789, -0.1628, -0.1001, -0.1311, -0.2221,
+ +0.1109, -0.0267, -0.1764, +0.0130, +0.1221, +0.0218, +0.1728,
+ -0.1723, -0.0075
+ ],
+ [
+ -0.2605, +0.0353, +0.2466, -0.1899, +0.3099, -0.1404, -0.0830,
+ -0.3665, -0.0910, -0.2279, -0.2234, +0.0620, -0.0908, +0.1768,
+ -0.2442, -0.0961, +0.4299, +0.5436, -0.0917, +0.1503, -0.4064,
+ -0.1430, +0.3162, -0.1345, -0.2937, -0.2846, -0.0193, -0.4533,
+ -0.2261, -0.1222, -0.1129, -0.3290, -0.7750, -0.7098, -0.2727,
+ -0.4024, -0.3958, -0.1634, +0.2665, +0.2756, +0.3278, +0.1937,
+ +0.1005, +0.0523, -0.4366, -0.4162, -0.4772, -0.6068, +0.1382,
+ -0.2529, +0.1909, +0.2588, -0.1264, -0.1671, +0.1244, -0.2088,
+ -0.2605, -0.2164, -0.1077, +0.2208, -0.2664, -0.1563, -0.1458,
+ +0.2787, -0.2938, +0.0286, -0.2725, -0.2118, -0.8733, -0.0993,
+ +0.0586, -0.1400, -0.0703, -0.4281, -0.1749, +0.0300, +0.0037,
+ +0.1338, -0.1955, -0.0700, +0.1824, -0.0540, -0.5073, +0.0921,
+ -0.2120, -0.2902, +0.0384, +0.0185, -0.1626, -0.1056, -0.1276,
+ -0.4195, -0.0912, +0.1371, -0.0623, -0.2995, -0.4663, +0.0512,
+ -0.0026, -0.4283, -0.2461, -0.3679, -0.2999, -0.1748, +0.3672,
+ -0.1192, -0.3204, -0.4311, -0.5912, +0.2561, -0.1581, +0.1043,
+ +0.0342, +0.1055, +0.3497, -0.0382, -0.2530, +0.1865, -0.1179,
+ -0.0760, +0.1321, -0.0716, -0.0144, -0.8554, -0.3417, -0.1275,
+ -0.6589, -0.4030
+ ],
+ [
+ -0.1494, +0.2796, +0.6247, -0.1217, -0.5509, +0.1932, -0.3013,
+ +0.2302, -0.2809, +0.4553, +0.8404, +0.6199, +0.1385, +0.0331,
+ +0.0042, -0.3285, +0.7295, -0.0294, -0.2949, +0.2366, -0.1214,
+ -0.2502, +0.1027, -0.1812, +0.0601, +0.0918, +0.0842, -0.2180,
+ +0.1772, +0.1091, +0.0319, +0.1944, +0.3898, +0.0086, -0.0401,
+ +0.3614, +0.1588, -0.0477, +0.0817, -0.2710, +0.1184, +0.3287,
+ +0.0520, +0.0873, -0.0546, +0.2455, -0.3417, +0.1815, +0.1621,
+ +0.4219, +0.2716, -0.2428, -0.1344, -0.1576, -0.0302, +0.5591,
+ -0.0856, +0.0391, -0.0706, +0.1696, -0.1670, +0.2060, -0.1463,
+ -0.2110, +0.0190, -0.2716, -0.0083, -0.0410, +0.3671, +0.0815,
+ +0.0396, +0.0587, -0.5697, -0.2391, -0.0851, -0.2115, -0.3303,
+ -0.2223, +0.0156, -0.0134, +0.1195, -0.3392, +0.3763, +0.2745,
+ +0.2823, -0.1685, -0.2651, -0.5157, +0.0531, +0.2002, -0.1954,
+ -0.5074, +0.0382, -0.2447, +0.2179, -0.0397, -0.1100, -0.1513,
+ -0.5015, +0.1645, -0.1978, -0.1060, +0.1523, -0.0885, +0.5535,
+ +0.1233, -0.0542, -0.1614, +0.0226, -0.3105, +0.2335, +0.1445,
+ +0.2908, +0.3610, -0.1125, +0.1442, -0.5119, -0.4982, -0.0518,
+ -0.0982, +0.0628, -0.2149, +0.1120, -0.3184, +0.0706, +0.2166,
+ -0.0593, +0.2342
+ ],
+ [
+ -0.4702, +0.2855, +0.2377, +0.4376, +0.3679, -0.3997, -0.6166,
+ -0.3178, -0.2796, +0.2986, +0.2720, -0.4592, +0.0554, -0.1440,
+ +0.0894, +0.1256, +0.1074, -0.0987, +0.0614, -0.0554, +0.1557,
+ +0.2701, +0.2058, -0.3176, -0.1309, +0.1015, +0.3681, -0.0635,
+ -0.3277, -0.4017, +0.1520, +0.0121, +0.0391, +0.4677, -0.3155,
+ +0.2477, -0.0688, -0.0943, -0.1454, -0.1356, -0.0908, -0.0301,
+ -0.0320, -0.0458, +0.2653, +0.0690, -0.2753, -0.1739, +0.1913,
+ -0.1664, -0.1362, +0.1426, -0.0177, -0.6053, -0.0134, +0.0343,
+ +0.4409, -0.1975, -0.1725, +0.3437, -0.0083, +0.1510, -0.3973,
+ -0.3923, +0.1405, -0.4148, +0.0643, +0.0743, +0.0900, -0.0314,
+ +0.3553, -0.2868, -0.5054, -0.4221, -0.2862, +0.3371, +0.0124,
+ -0.3379, -0.3411, +0.0120, -0.4792, +0.0782, +0.0266, -0.2176,
+ -0.1019, -0.1444, +0.2339, +0.2821, -0.1225, -0.6002, -0.1393,
+ +0.0344, +0.0794, -0.1954, +0.1310, -0.1781, +0.1504, -0.5873,
+ +0.0662, +0.2200, -0.3643, +0.1428, +0.1181, +0.2227, +0.0351,
+ +0.3137, -0.0639, +0.2621, +0.0867, -0.4185, +0.4271, -0.2175,
+ +0.3637, +0.0762, +0.3777, +0.0536, -0.4615, +0.1710, -0.1355,
+ -0.2227, -0.2198, +0.4569, +0.2799, +0.1827, +0.0663, -0.2756,
+ -0.2490, +0.0575
+ ],
+ [
+ -0.3158, -0.2890, -0.4563, +0.2022, +0.2738, -0.0046, +0.1538,
+ +0.1298, +0.0805, -0.3854, +0.2968, -0.0891, +0.1086, -0.1544,
+ -0.1091, -0.0038, +0.2394, +0.1428, +0.1451, +0.1642, +0.0884,
+ +0.1361, +0.3659, +0.0653, -0.3340, -0.1729, -0.2188, -0.1349,
+ -0.6069, +0.2593, +0.2640, +0.1862, -0.0958, -0.3917, +0.0204,
+ -0.0919, -0.3527, +0.1264, +0.2719, -0.1150, -0.0379, -0.1760,
+ +0.1280, +0.1394, -0.2072, +0.1258, +0.0038, +0.2749, -0.1239,
+ -0.2301, -0.2318, -0.1367, +0.1408, -0.4113, -0.1182, +0.2907,
+ -0.2517, +0.4406, -0.5794, +0.5441, +0.0836, +0.3771, -0.3604,
+ -0.1408, +0.1624, +0.0721, -0.0188, -0.0591, +0.1975, +0.2387,
+ +0.1724, -0.1423, -0.2921, +0.1689, -0.0011, +0.1190, +0.3210,
+ -0.2240, -0.2403, +0.0686, +0.2049, +0.2141, +0.1355, -0.0492,
+ +0.3084, +0.2674, +0.2580, -0.0334, -0.0380, +0.0609, +0.0727,
+ -0.0208, -0.3951, -0.0971, -0.0746, +0.1689, -0.2867, -0.0426,
+ -0.0759, +0.0607, -0.0946, -0.1379, +0.1288, +0.2070, +0.1780,
+ +0.0318, +0.0791, +0.2944, +0.1643, -0.1279, +0.1636, -0.2282,
+ +0.3231, +0.1229, +0.0527, -0.0999, +0.4245, -0.1590, -0.1847,
+ -0.2990, +0.0007, -0.4040, +0.2940, -0.1194, -0.1485, +0.1357,
+ -0.0388, +0.1547
+ ],
+ [
+ +0.2944, -0.0848, +0.2579, -0.0769, +0.0367, -0.1508, -0.0799,
+ +0.1506, -0.5360, -0.5105, -0.2680, +0.3761, -0.0984, -0.1279,
+ -0.0854, -0.4862, -0.1900, +0.0773, +0.2905, -0.3772, +0.0393,
+ +0.0788, +0.3949, -0.0481, -0.0241, +0.0634, -0.1031, +0.3015,
+ +0.0363, -0.2645, +0.1064, +0.0839, -0.1983, -0.0033, +0.0028,
+ -0.2902, +0.0515, +0.5166, -0.1934, +0.5010, -0.1492, +0.0573,
+ -0.5875, +0.2650, -0.0200, +0.0005, -0.1724, +0.2043, +0.1789,
+ +0.3558, +0.3493, -0.5738, +0.0967, -0.2975, -0.1559, -0.3763,
+ +0.1093, -0.2211, -0.6357, -0.3903, -0.2948, -0.0557, -0.1826,
+ +0.2398, -0.1994, -0.1868, +0.1089, -0.1865, -0.3610, -0.0968,
+ +0.4419, -0.3118, -0.2249, +0.0200, -0.0137, +0.0620, -0.0263,
+ -0.0354, -0.3181, +0.0951, -0.1742, +0.0410, +0.0277, +0.2432,
+ -0.1072, -0.8202, +0.1892, +0.0147, +0.0294, -0.0535, -0.1385,
+ +0.2784, +0.1882, -0.1426, -0.3074, +0.1407, -0.1039, -0.1103,
+ +0.3239, -0.4395, -0.1791, -0.7191, -0.3185, +0.2656, +0.1225,
+ -0.6429, -0.0387, +0.1237, +0.1838, +0.0711, +0.2533, -0.1331,
+ -0.1134, -0.2910, +0.2044, -0.0388, +0.0626, +0.1412, +0.1137,
+ +0.2226, -0.2584, -0.0146, +0.2596, +0.1135, +0.0691, +0.3466,
+ +0.2905, -0.0696
+ ],
+ [
+ -0.1760, -0.1217, -0.3795, -0.2323, -0.3084, -0.3339, +0.0679,
+ -0.2687, -0.1492, -0.0599, -0.1726, -0.3135, -0.3037, +0.1118,
+ +0.2548, +0.3155, +0.1431, -0.2431, -0.1661, -0.0699, -0.9992,
+ +0.2107, +0.3735, -0.2927, -0.1955, -0.3139, -0.2026, +0.1920,
+ -0.6132, -0.4711, -0.0742, +0.1080, -0.0416, +0.0951, +0.1098,
+ -0.2020, +0.1225, -0.0162, -0.0274, -0.1246, +0.2805, +0.1266,
+ -0.0951, +0.0442, -0.2731, +0.0854, +0.1064, +0.3674, +0.1202,
+ -0.1633, -0.2323, +0.0118, +0.1668, +0.2000, -0.0074, -0.2767,
+ +0.2407, +0.2778, +0.0913, -0.4847, -0.2661, +0.0978, -0.0287,
+ -0.2928, +0.2952, +0.2562, +0.3024, -0.1540, -0.1158, +0.0737,
+ +0.1926, -0.2975, -0.0198, -0.1989, +0.5044, +0.2622, -0.2509,
+ -0.0482, -0.3922, -0.2320, +0.2627, -0.5306, +0.1435, -0.1229,
+ +0.0975, -0.2044, +0.3711, +0.5703, -0.2517, +0.2023, -0.1297,
+ -0.0668, +0.2527, -0.3172, -0.0962, +0.2348, -0.0926, -0.1353,
+ -0.2692, -0.0836, -0.1542, -0.6537, -0.3239, -0.0091, +0.0764,
+ +0.1303, -0.1943, +0.1143, -0.0766, +0.2083, +0.2246, +0.1451,
+ +0.0498, +0.5236, -0.1377, +0.1596, +0.2191, -0.0597, -0.0479,
+ -0.1694, -0.0409, +0.2463, -0.0010, +0.1896, -0.2039, -0.0561,
+ +0.1272, +0.0267
+ ],
+ [
+ +0.0824, +0.2985, -0.1818, +0.0165, +0.0263, -0.5175, +0.2023,
+ -0.1214, -0.0877, -0.0604, -0.3464, -0.0074, -0.4014, -0.4151,
+ -0.3583, +0.2385, +0.2991, -0.0496, -0.0716, +0.3102, +0.4009,
+ -0.2886, +0.1585, +0.3956, +0.1316, -0.1330, +0.0819, -0.8692,
+ +0.0305, -0.0919, +0.1576, -0.1164, -0.1979, +0.1581, -0.4819,
+ -0.3179, +0.0952, +0.0742, -0.0756, -0.1220, +0.2545, +0.1710,
+ +0.2293, +0.1042, -0.1671, +0.2841, +0.2452, -0.0069, -0.1438,
+ +0.2662, +0.2906, -0.5143, +0.0832, +0.0869, +0.0342, +0.1816,
+ +0.1987, +0.1581, -0.2079, -0.2572, -0.0307, +0.0320, +0.0527,
+ +0.0727, -0.1465, +0.1661, +0.3956, +0.2894, +0.3917, -0.3396,
+ +0.1105, -0.1391, +0.0012, +0.0047, +0.1477, -0.0037, +0.0068,
+ -0.0856, -0.0221, -0.0400, +0.0016, -0.2696, -0.0206, +0.3180,
+ +0.0199, -0.4817, +0.2159, -0.1470, -0.0328, -0.2933, -0.2309,
+ -0.0132, -0.5960, +0.1896, -0.3994, +0.1314, -0.0203, +0.1437,
+ +0.0735, -0.4605, -0.3787, +0.1167, -0.1250, +0.4293, +0.1606,
+ +0.0700, +0.1333, +0.1119, +0.1243, +0.5194, -0.2171, +0.2917,
+ -0.0548, +0.0077, -0.0448, +0.2492, +0.0562, +0.0089, -0.1307,
+ +0.1116, +0.2347, +0.0543, -0.3370, +0.1276, +0.3027, +0.3021,
+ -0.0860, -0.0131
+ ],
+ [
+ +0.2947, +0.4664, -0.1349, +0.1488, +0.4577, +0.0345, +0.1262,
+ -0.1107, -0.0102, +0.3115, -0.2085, -0.0483, -0.0688, -0.2319,
+ +0.3405, -0.1426, +0.0672, -0.0733, +0.1650, -0.0575, +0.0016,
+ -0.3747, -0.1244, +0.0266, +0.5940, -0.2003, -0.4178, -0.0582,
+ -0.2234, +0.0603, +0.3361, +0.2174, -0.3606, -0.3432, +0.0885,
+ +0.0415, -0.0098, -0.0425, -0.6034, -0.2420, -0.1222, +0.0111,
+ +0.0947, +0.2406, -0.0548, +0.3810, +0.3556, +0.0501, -0.3077,
+ +0.0226, -0.0411, +0.0700, -0.0193, +0.2049, +0.0679, -0.3123,
+ -0.1020, +0.3252, +0.1818, +0.0001, +0.1062, -0.1898, +0.2527,
+ -0.1705, -0.0496, +0.1033, +0.2974, +0.3670, -0.3341, +0.4862,
+ -0.0519, -0.3752, +0.1897, +0.3296, +0.0165, -0.0893, -0.2605,
+ +0.3128, +0.3071, -0.0489, +0.0398, -0.0809, +0.1974, -0.0703,
+ -0.3026, +0.0867, +0.0182, +0.0037, +0.0997, -0.2375, -0.2754,
+ +0.2210, +0.0194, +0.1234, -0.4653, +0.3221, -0.2906, +0.0797,
+ +0.1010, +0.2052, -0.1877, +0.3158, -0.0343, +0.0848, -0.0680,
+ -0.0419, -0.3498, -0.0545, -0.3220, +0.1888, -0.4147, +0.1408,
+ -0.0431, +0.1205, +0.1096, -0.1536, +0.3244, -0.2722, +0.2300,
+ +0.2949, +0.1560, -0.3925, -0.2552, +0.0259, -0.1633, -0.1839,
+ -0.0563, +0.1257
+ ],
+ [
+ +0.2148, +0.0047, -0.5010, -0.1166, +0.0344, -0.2950, -0.0669,
+ +0.2197, +0.0749, +0.2859, -0.0708, +0.3323, +0.4038, -0.1302,
+ +0.0795, +0.3921, -0.0013, -0.2661, -0.2596, -0.1604, -0.1498,
+ +0.0585, +0.4799, -0.1394, -0.2289, +0.2356, -0.3931, -0.2290,
+ -0.0818, +0.2484, +0.1705, -0.3872, -0.0328, +0.0271, -0.0874,
+ -0.0768, -0.7135, +0.0105, +0.1771, -0.2271, -0.0836, -0.1756,
+ +0.0977, -0.0529, -0.0650, +0.0444, -0.2159, +0.3083, +0.2212,
+ +0.0188, -0.0080, -0.1380, +0.1597, +0.2834, +0.1947, +0.1630,
+ -0.2205, +0.0559, -0.2156, -0.2409, +0.0107, -0.2687, +0.1016,
+ -0.2704, +0.3349, +0.2165, -0.1543, +0.0014, -0.0324, +0.3259,
+ -0.0701, +0.1057, -0.0211, -0.1465, +0.4340, -0.1941, +0.0097,
+ -0.1941, -0.2310, +0.1882, +0.0257, +0.3041, -0.5347, +0.1756,
+ +0.2526, +0.2409, +0.3229, +0.1697, +0.6469, +0.1586, -0.4125,
+ +0.2139, -0.5680, -0.1800, +0.1256, -0.0353, +0.4003, +0.0268,
+ +0.0944, -0.1399, +0.1552, +0.0373, -0.1222, +0.0031, +0.2078,
+ +0.3396, -0.2205, +0.2581, -0.5238, -0.4429, -0.0474, -0.5244,
+ -0.4636, +0.2577, -0.0144, -0.0862, +0.2369, +0.3335, -0.3155,
+ +0.0177, -0.3951, +0.2018, +0.0872, -0.0961, -0.2180, -0.0140,
+ +0.4505, -0.1433
+ ],
+ [
+ -0.1068, -0.0263, -0.1388, -0.1157, -0.1234, +0.0694, -0.0963,
+ +0.3236, -0.0838, -0.4470, +0.1331, +0.2199, +0.0891, +0.4354,
+ -0.3252, -0.0962, -0.1358, +0.1375, -0.3047, -0.3211, -0.1624,
+ +0.2874, -0.3383, -0.2534, -0.0498, +0.1309, -0.0004, -0.4051,
+ -0.1960, -0.3383, -0.2622, -0.2444, -0.2500, +0.0469, -0.4247,
+ -0.0853, -0.1119, -0.1316, +0.0171, -0.0362, +0.0522, -0.2861,
+ +0.0766, +0.0506, -0.1964, -0.0899, +0.2697, -0.3270, +0.5962,
+ -0.2216, +0.1118, +0.1582, -0.3296, +0.0793, +0.2890, -0.4065,
+ +0.0924, -0.0746, +0.2517, +0.2001, -0.0501, -0.1863, +0.1175,
+ -0.2080, +0.0020, -0.0169, -0.1251, -0.0714, +0.3016, -0.1755,
+ +0.2065, +0.1221, +0.0706, +0.2269, -0.2703, -0.3755, +0.0792,
+ -0.2415, +0.1048, -0.3250, +0.2936, -0.4018, -0.1319, -0.3685,
+ +0.0964, +0.2001, -0.0373, +0.1277, -0.0891, -0.4724, +0.0329,
+ +0.3696, +0.1104, -0.1315, -0.1854, -0.0938, -0.3303, -0.0011,
+ +0.3145, -0.5522, +0.1904, -0.2422, +0.1405, -0.1609, +0.1170,
+ +0.1209, +0.2885, +0.1152, +0.1770, -0.0836, -0.3173, -0.1085,
+ -0.1493, +0.0094, +0.2494, +0.0030, +0.0778, +0.1527, -0.1594,
+ -0.1341, -0.0434, +0.1502, -0.2476, -0.2058, +0.2545, +0.2769,
+ +0.1098, -0.0083
+ ],
+ [
+ +0.2106, -0.1300, +0.0485, -0.7346, +0.0840, -0.0914, +0.1989,
+ +0.4280, +0.4626, +0.3009, -0.0244, +0.0138, -0.0378, -0.0385,
+ -0.1281, -0.3317, -0.2086, -0.2537, -0.2534, -0.6887, +0.0834,
+ -0.2205, +0.3126, -0.3583, +0.2112, +0.0573, +0.1206, +0.1378,
+ +0.1218, -0.4811, +0.1413, -0.2197, -0.0216, +0.0774, -0.2460,
+ +0.2520, -0.3548, -0.3999, +0.2720, +0.0545, +0.3093, -0.7499,
+ -0.2457, +0.3429, +0.2207, -0.3214, -0.2397, -0.0006, -0.3268,
+ +0.0159, +0.1594, -0.0966, +0.2911, -0.1839, -0.1116, +0.0606,
+ +0.0206, -0.0959, -0.3201, -0.1717, +0.0481, +0.1382, -0.1964,
+ +0.4383, -0.1060, -0.3150, -0.1749, -0.7198, +0.5017, +0.3316,
+ -0.4407, -0.4595, -0.4555, -0.3972, +0.3232, -0.4576, -0.0748,
+ +0.0102, +0.2671, +0.2561, +0.1418, +0.2160, -0.0213, -0.2403,
+ +0.1480, +0.3040, -0.0377, +0.3424, -0.2381, +0.0744, -0.4117,
+ -0.0661, +0.2971, +0.5014, -0.9249, +0.0502, -0.3293, +0.1345,
+ -0.4735, +0.1441, +0.0026, -0.0259, -0.9353, -0.5167, +0.1392,
+ -0.3059, -0.1233, -0.2771, +0.2003, +0.3982, +0.0078, +0.1673,
+ -0.4770, -0.4842, -0.2908, +0.0975, -0.0728, +0.3615, +0.1398,
+ +0.0180, +0.3402, +0.1516, -0.0569, -0.0071, +0.1601, -0.0516,
+ +0.2392, -0.5066
+ ],
+ [
+ -0.8802, +0.1699, +0.1054, +0.0240, +0.1706, +0.1335, -0.1155,
+ -0.3890, +0.0630, -0.1447, +0.3381, -0.1320, +0.1034, +0.2878,
+ -0.0441, -0.1470, +0.3491, +0.3904, -0.1225, -0.1650, -0.1266,
+ -0.1012, +0.3379, -0.3566, -0.3020, -0.5177, +0.0250, +0.1512,
+ +0.2122, -0.3095, -0.0402, -0.2094, +0.3877, -0.1007, -0.0152,
+ -0.1819, +0.0907, +0.2006, -0.0020, -0.1510, +0.1542, +0.0429,
+ -0.3614, +0.0143, +0.0544, -0.0749, -0.0547, +0.2007, +0.0829,
+ -0.2418, +0.2694, -0.1332, -0.0991, -0.1609, +0.2025, -0.4393,
+ +0.0703, +0.1062, +0.2181, -0.1352, -0.3935, +0.4110, -0.0509,
+ +0.0621, +0.2605, -0.0382, +0.3192, -0.1091, +0.0318, -0.1395,
+ -0.1186, +0.1220, +0.2714, -0.0848, -0.0499, +0.0187, -0.1677,
+ -0.2008, -0.0645, -0.2873, -0.0607, -0.1093, -0.0814, -0.1771,
+ -0.2174, +0.3143, +0.0269, -0.5732, -0.0363, -0.1689, +0.1948,
+ +0.0059, -0.0279, +0.2271, +0.1691, -0.0134, +0.0548, +0.0756,
+ +0.0620, -0.3728, +0.3562, -0.5897, -0.3423, +0.0185, +0.0146,
+ +0.2151, -0.3176, -0.2987, +0.0348, +0.0252, -0.1359, +0.1920,
+ -0.2293, +0.2033, +0.0593, +0.0956, -0.3218, -0.0207, -0.2550,
+ +0.1762, +0.0230, -0.0570, -0.0746, +0.1369, -0.0651, -0.2736,
+ -0.0851, +0.0131
+ ],
+ [
+ -0.8832, -0.1124, +0.3068, -0.2348, -0.0845, +0.1651, -0.0848,
+ -0.3490, -0.3582, -0.8653, +0.1148, -0.5777, -0.0275, +0.1159,
+ +0.3220, -0.4598, +0.2011, +0.0046, +0.2821, -0.2998, -0.1787,
+ -0.1737, +0.3377, +0.0090, -0.4418, -0.1343, +0.0606, -0.3029,
+ -0.3504, -0.3433, -0.3918, +0.1668, +0.2931, -0.2543, -0.0114,
+ -0.3211, -0.3044, +0.1758, -0.3798, -0.2485, -0.1906, -0.2615,
+ +0.1321, -0.2962, +0.1544, +0.2058, +0.3810, +0.3139, +0.0916,
+ -0.0725, +0.2238, +0.2081, -0.4715, -0.0871, -0.0508, -0.3160,
+ -0.0327, -0.0550, -0.1204, -0.9481, -0.1351, -0.1102, -0.0333,
+ -0.0181, -0.1707, +0.0076, -0.0827, -0.2646, -0.2107, -0.4914,
+ -0.1390, -0.0170, -0.4054, -0.0107, +0.2280, -0.0472, +0.4655,
+ +0.2280, +0.3590, +0.0616, -0.3474, +0.1742, -0.1811, -0.1085,
+ -0.3157, -0.6880, +0.0180, -0.0004, -0.2667, -0.0929, -0.0167,
+ -0.1256, +0.0701, -0.3705, -0.4304, +0.3143, -0.2352, +0.1948,
+ -0.0775, -0.0602, -0.1135, +0.1950, +0.0860, -0.2415, +0.1209,
+ -0.5315, +0.2986, +0.0702, +0.0776, -0.2087, -0.1640, -0.5140,
+ -0.1156, -0.3753, -0.3619, +0.1426, -0.0180, -0.4435, +0.3894,
+ -0.0649, +0.0194, +0.2156, -0.0400, -0.0441, -0.3793, -0.2438,
+ +0.1116, -0.2393
+ ],
+ [
+ -0.0564, -0.2013, +0.3803, -0.1042, -0.0933, -0.0053, -0.3388,
+ +0.2630, -0.4021, -0.2141, +0.0750, +0.3583, +0.0882, +0.2297,
+ -0.0828, -0.3131, -0.1735, +0.3028, -0.7214, +0.0045, -0.1908,
+ -0.0893, -0.3378, -0.3102, -0.0531, -0.4406, -0.3636, -0.3734,
+ -0.3279, -0.0664, +0.0979, -0.2246, +0.0568, +0.0598, +0.1435,
+ -0.2430, -0.4036, +0.2383, +0.2321, +0.3876, -0.0346, +0.0722,
+ -0.2538, -0.2412, +0.0604, -0.1563, -0.4940, +0.2605, +0.2478,
+ -0.2374, -0.2984, +0.0057, -0.2369, +0.1294, +0.0174, +0.5807,
+ -0.0718, -0.3781, -0.3258, -0.5421, -0.0009, +0.0742, -0.0556,
+ -0.0871, +0.0130, -0.4105, -0.8956, +0.1436, +0.1205, -0.0754,
+ -0.1488, +0.2092, -0.7182, -0.0507, -0.0535, +0.3105, +0.1438,
+ -0.2952, +0.0385, +0.0672, +0.0364, +0.0696, -0.1960, +0.2819,
+ +0.0306, -0.0762, +0.3345, -0.1293, -0.1608, -0.1541, -0.0351,
+ -0.4728, -0.3493, -1.1941, -0.1454, +0.3901, +0.1090, -0.1694,
+ -0.2511, +0.1375, +0.0238, +0.1331, -0.0784, -0.3095, -0.3079,
+ -0.4227, -0.2915, +0.0166, +0.1902, -0.0587, -0.2205, +0.1881,
+ -0.3936, -0.1078, -0.2047, -0.0764, +0.3708, +0.3702, -0.1016,
+ +0.0040, -0.1311, -0.3788, -0.2263, +0.3114, -0.3604, +0.0038,
+ -0.1860, +0.1821
+ ],
+ [
+ +0.3922, +0.0453, +0.5451, -0.2539, -0.3151, -0.0529, -0.0315,
+ +0.0386, +0.3905, +0.0847, +0.0692, -0.1342, +0.2468, -0.0541,
+ +0.3193, -0.0176, +0.0102, +0.1388, +0.1445, -0.2237, +0.1713,
+ +0.1079, -0.1579, +0.1329, -0.3138, -0.0993, +0.2535, +0.2280,
+ +0.1970, +0.5129, -0.3800, +0.4691, -0.4482, -0.0378, +0.3220,
+ -0.0184, +0.0875, -0.1760, +0.5265, -0.2199, -0.1342, -0.3460,
+ +0.1824, -0.3727, +0.2315, -0.0991, -0.1387, -0.1143, -0.0743,
+ -0.1338, -0.0654, +0.3019, -0.1920, +0.0478, +0.0189, +0.1041,
+ +0.5841, -0.2401, -0.4096, +0.2503, -0.0746, +0.0600, -0.0135,
+ -0.0188, -0.4462, -0.0420, -0.0338, +0.0796, -0.0532, -0.1258,
+ -0.1273, -0.1757, +0.1009, -0.0217, +0.0317, +0.2119, -0.4266,
+ -0.2404, +0.2424, -0.3341, -0.0366, -0.5047, -0.5699, -0.0441,
+ -0.0389, -0.0268, -0.5898, +0.0766, +0.0640, -0.0788, +0.0573,
+ +0.1757, +0.1714, +0.3059, +0.0664, +0.2298, -0.0712, +0.0755,
+ -0.1056, +0.2291, +0.1614, +0.3680, +0.0709, -0.0690, -0.0891,
+ +0.0240, +0.2207, +0.1425, +0.7755, +0.1882, -0.6451, -0.0345,
+ +0.1063, -0.0540, -0.0989, -0.5350, +0.1494, +0.2128, +0.1890,
+ -0.1394, -0.0377, -0.2619, +0.4138, -0.1444, -0.4859, -0.2464,
+ -0.3172, -0.1692
+ ],
+ [
+ -0.0923, -0.4212, -0.2414, -0.4825, +0.2255, +0.2309, -0.4897,
+ +0.0304, -0.0860, -0.1170, -0.1571, +0.1275, -0.1820, -0.3654,
+ +0.0232, -0.3386, -0.5037, +0.1978, -0.0036, +0.0813, -0.1647,
+ -0.8769, -0.3028, -0.3804, -0.7696, +0.0939, -0.1970, -0.0756,
+ +0.2388, +0.4887, -0.2240, +0.0294, -0.4167, -0.3421, -0.2896,
+ +0.0338, +0.3542, +0.1363, -0.0421, -0.3361, -0.3763, +0.5503,
+ +0.1136, +0.0669, -0.3017, -0.1507, -0.6288, -0.5275, +0.4184,
+ -0.4006, +0.2278, +0.0248, -0.2301, -0.3362, -0.1329, -0.3787,
+ -0.0273, +0.3377, +0.1465, -0.0040, +0.3127, -0.1651, -0.0978,
+ +0.4950, -0.1856, -0.2066, -0.0279, -0.0435, +0.3200, +0.2473,
+ -0.0725, -0.0819, -0.2703, -0.3825, +0.1863, -0.0269, +0.2441,
+ -0.1633, +0.0109, -0.1532, -0.1801, +0.3215, -0.0189, +0.3776,
+ +0.2735, +0.2794, -0.3058, +0.2496, -0.2674, +0.2918, +0.3530,
+ -0.2802, +0.1357, +0.2323, -0.2258, +0.3445, -0.3727, -0.1343,
+ -0.2584, +0.3894, +0.3088, +0.4367, +0.4166, -0.3000, +0.3440,
+ +0.1129, -0.5826, -0.0498, +0.1875, -0.3181, +0.2863, +0.0757,
+ -0.1553, +0.0070, -0.0151, +0.5215, -0.0413, +0.0430, +0.2005,
+ -0.0768, +0.4908, -0.1021, +0.0298, -0.4536, -0.3938, -0.7115,
+ -0.3281, +0.0436
+ ],
+ [
+ +0.1429, -0.7486, -0.0175, -0.1436, -0.0643, -0.1031, +0.3570,
+ +0.4050, -0.0815, +0.0001, -0.1782, +0.0159, -0.0068, -0.4581,
+ -0.0356, +0.0264, -0.3577, -0.1983, +0.0125, -0.6086, +0.1955,
+ -0.7601, +0.2107, +0.1950, -0.2277, -0.2083, +0.3890, +0.0133,
+ -0.2579, -0.2204, -0.2568, +0.3742, -0.4256, +0.2367, -0.0544,
+ -0.0623, -0.0004, -0.1718, +0.3199, +0.0778, +0.1319, +0.1961,
+ -0.2971, -0.0769, -0.0987, -0.3242, +0.3422, +0.2269, -0.2482,
+ -0.0209, +0.1743, -0.4017, +0.1609, +0.3292, +0.0796, -0.3552,
+ +0.1177, -0.6123, -0.8029, -0.4316, +0.0467, -0.1625, -0.0685,
+ -0.1786, -0.1052, +0.0359, -0.8246, -0.1224, -0.2311, -0.1663,
+ -0.4349, +0.5463, +0.3116, +0.0843, -0.0817, +0.4950, -0.2378,
+ -0.3152, -0.5438, -0.2174, -0.0641, +0.2376, +0.1389, +0.1698,
+ -0.3016, -0.0105, +0.0238, -0.0417, -0.0840, -0.1700, +0.0105,
+ +0.1367, +0.2720, +0.6785, -0.3363, +0.1792, +0.0067, -0.3054,
+ +0.1514, -0.0196, -0.1702, -0.0847, +0.0017, -0.2192, +0.0678,
+ +0.1268, -0.4652, -0.3753, -0.0238, -0.5654, -0.0350, +0.3150,
+ -0.3401, -0.2279, -0.3434, +0.0283, +0.0703, -0.2647, -0.2636,
+ -0.1750, -0.5818, -0.2056, -0.0293, +0.4088, -0.5704, -0.1289,
+ -0.2542, -0.1802
+ ],
+ [
+ -0.2887, +0.3308, +0.1327, -0.5094, -0.0622, -0.2413, -0.3148,
+ +0.0616, -0.1550, +0.2265, +0.3879, -0.1951, -0.6486, +0.0115,
+ -0.2057, +0.3291, +0.1942, -0.2094, +0.3025, -0.0428, +0.0823,
+ +0.4690, -0.7880, +0.6142, -0.6011, -0.1640, -0.2154, +0.5126,
+ +0.0807, +0.3205, +0.1592, -0.1571, +0.2994, -0.3585, +0.2420,
+ -0.1281, +0.1821, -0.1843, +0.1903, -0.3561, +0.5856, +0.0123,
+ +0.0916, +0.3216, -0.2577, -0.5488, -0.3684, +0.2314, +0.0460,
+ -0.0247, +0.0782, +0.3424, +0.0063, +0.2094, -0.3286, +0.3532,
+ -0.1614, +0.2834, +0.1043, -0.4423, -0.0256, +0.0870, +0.4249,
+ -0.3413, -0.2285, +0.1121, -0.0555, +0.0010, +0.1207, +0.2360,
+ -0.0790, +0.1614, -0.0735, +0.0818, +0.2746, +0.2402, -0.7183,
+ +0.1044, -0.4774, +0.4292, -0.2664, -0.0594, +0.2838, -0.4776,
+ -0.0046, -0.6516, -0.0835, +0.1015, -0.1679, -0.2869, -0.3426,
+ +0.2073, +0.3420, -0.2174, +0.3160, -0.0505, +0.2485, +0.1510,
+ +0.2260, -0.4438, -1.1494, +0.0271, +0.4070, -0.0237, -0.2114,
+ +0.2593, +0.2260, -0.1828, -0.0544, +0.3111, +0.0166, +0.0297,
+ +0.3485, -0.0505, -0.3387, -0.0293, +0.1108, +0.0087, -0.2202,
+ -0.0637, -0.0756, -0.2728, -0.0198, -0.1262, -0.3164, +0.3487,
+ +0.3104, +0.3920
+ ],
+ [
+ -0.2575, +0.1666, +0.3256, -0.1886, -0.2590, -0.1386, +0.3521,
+ -0.3582, -0.2922, +0.2653, +0.2938, +0.0030, -0.3808, +0.1105,
+ +0.0449, -0.2666, -0.1739, -0.2229, +0.0833, +0.3438, -0.7196,
+ +0.0778, -0.0854, +0.1274, +0.3981, -0.0870, -0.1869, -0.0256,
+ -0.0882, -0.0591, -0.2645, +0.3365, +0.1646, +0.2441, -0.3281,
+ -0.1445, -0.2442, +0.1015, -0.0256, +0.2571, +0.1649, -0.0259,
+ -0.0699, +0.1460, -0.1046, +0.2116, -0.1376, +0.0917, -0.0286,
+ -0.0055, +0.0966, -0.0678, +0.0400, +0.1181, -0.0878, -0.1292,
+ +0.0265, +0.0441, +0.0287, -0.0853, -0.1342, -0.0030, -0.2036,
+ -0.0305, +0.0461, -0.1499, -0.1201, -0.0007, +0.0579, -0.0417,
+ +0.0633, -0.2599, +0.1975, +0.0240, -0.1304, -0.0229, -0.2079,
+ +0.0305, +0.5747, +0.0475, -0.5645, -0.2887, -0.5164, +0.0432,
+ -0.3610, -0.2888, +0.1067, -0.0617, -0.4146, +0.3116, +0.2835,
+ -0.0129, -0.4083, -0.0518, -0.0702, -0.2992, +0.3599, -0.0642,
+ -1.2739, -0.1203, -0.5464, +0.1658, +0.3236, +0.0734, +0.4132,
+ -0.0319, -0.2330, -0.3762, -0.1676, +0.0437, -0.0187, +0.3352,
+ -0.1844, -0.3109, +0.1229, +0.1187, +0.3067, -0.1564, -0.1249,
+ +0.2623, -0.2028, -0.2382, -0.0641, +0.0678, +0.2706, +0.2068,
+ -0.0180, -0.3670
+ ],
+ [
+ -0.0107, -0.0179, -0.3622, +0.0487, -0.2037, -0.2486, +0.4088,
+ -0.4331, +0.1125, +0.3157, -0.0246, -0.1149, -0.2634, +0.5252,
+ -0.0316, -0.0396, +0.0342, -0.3630, +0.1595, +0.2105, -0.0896,
+ +0.1590, +0.2375, +0.0225, -0.1746, +0.1284, +0.2204, +0.3032,
+ +0.3802, -0.3472, -0.2104, +0.0068, +0.2576, -0.0977, -0.3281,
+ -0.1515, -0.0040, +0.1479, +0.1452, +0.2931, -0.4903, -0.0811,
+ -0.0917, +0.0062, +0.2323, -0.8050, -0.1784, +0.4353, -0.0573,
+ +0.4593, +0.1577, -0.3910, +0.0392, +0.0360, +0.4710, +0.2190,
+ -0.1018, -0.4349, +0.0778, +0.4254, -0.6687, +0.0132, +0.0726,
+ -0.0929, -0.2873, -0.0379, +0.3106, +0.1391, -0.0208, -0.0201,
+ -0.4040, -0.0819, -0.1079, -0.1654, -0.6052, +0.3173, +0.3248,
+ -0.1358, -0.4220, +0.0344, -0.0460, -0.1394, -0.2428, -0.1595,
+ +0.2178, -0.1904, +0.2255, +0.0940, +0.0954, -0.4658, -0.3351,
+ +0.4072, -0.0390, -0.0776, +0.3697, -0.0263, -0.0450, -0.1758,
+ +0.1951, +0.1053, -0.2358, +0.1302, -0.4079, +0.2972, -0.0111,
+ -0.5701, -0.1274, -0.2291, +0.1902, -0.1665, +0.0604, -0.4641,
+ -0.6633, +0.2213, -0.7764, +0.0351, +0.3093, +0.0849, -0.4626,
+ +0.0663, -0.1490, +0.5589, -0.3444, -0.1921, +0.2102, +0.4465,
+ +0.2145, -0.4431
+ ],
+ [
+ +0.2271, +0.0093, -0.0987, -0.3881, -0.0350, +0.0747, -0.0680,
+ +0.1378, +0.3064, -0.2883, -0.3261, -0.0059, -0.1537, -0.1148,
+ -0.2007, +0.0185, -0.1833, -0.2434, +0.0928, +0.2168, +0.1473,
+ -0.6421, +0.1321, -0.0033, -0.1413, +0.1213, +0.3580, +0.4134,
+ +0.6291, -0.1581, +0.2093, -0.0749, +0.1321, +0.0703, -0.1864,
+ +0.2468, +0.1223, -0.0090, -0.5070, +0.0125, -0.4041, -0.0245,
+ -0.1620, -0.1767, +0.0946, -0.0966, +0.2019, +0.0895, +0.0181,
+ +0.3667, +0.3279, -0.1238, +0.2064, +0.1062, -0.4617, -0.5064,
+ +0.1865, +0.0008, -0.6320, -0.0860, +0.0246, -0.1346, -0.0486,
+ -0.1026, +0.1784, +0.2213, +0.0952, -0.2822, -0.4380, -0.4222,
+ -0.2064, -0.1091, +0.0198, -0.2463, +0.4210, -0.2130, -0.0964,
+ +0.2051, -0.2638, -0.4065, -0.2067, -0.0830, -0.1476, +0.0103,
+ -0.1342, -0.4563, -0.1189, +0.3326, +0.3363, -0.1587, -0.1181,
+ +0.1159, +0.2865, -0.0199, +0.4299, +0.2091, -0.0407, -0.2726,
+ +0.2658, -0.0264, +0.2548, +0.4658, -0.5378, +0.1585, -0.2706,
+ -0.2006, -0.0351, -0.2616, -0.5981, +0.1679, -0.0143, -0.0829,
+ +0.2944, -0.0259, +0.0198, -0.0762, -0.0588, -0.0206, -0.3015,
+ -0.2721, -0.0874, +0.4428, -0.1835, -0.4881, +0.1817, +0.6561,
+ -0.2540, +0.0049
+ ],
+ [
+ -0.1863, -0.3087, +0.1671, +0.3022, +0.1499, -0.1739, -0.1339,
+ -0.8251, -0.4191, +0.1242, +0.0518, +0.2402, -0.4053, +0.3328,
+ -0.3223, -0.1882, -0.0025, -0.1106, +0.0680, +0.3380, +0.0086,
+ -0.2912, -0.0337, -0.5541, +0.4255, -0.0656, -0.0838, +0.0699,
+ -0.0293, +0.2684, +0.2524, -0.2258, +0.1109, -0.0906, -0.5153,
+ -0.0830, +0.4158, +0.1373, +0.2967, +0.1961, +0.4988, +0.2814,
+ -0.3652, +0.0527, -0.0147, +0.2100, -0.0213, -0.2260, -0.0895,
+ -0.2451, +0.0256, +0.0032, +0.2069, -0.0900, +0.0620, -0.4997,
+ +0.3689, +0.4957, +0.7216, +0.0192, -0.0090, -0.0156, +0.1036,
+ -0.2198, -0.1575, +0.0765, +0.0615, -0.3929, -0.4157, +0.2005,
+ +0.0277, +0.1536, +0.3945, +0.1446, -0.2494, +0.0705, +0.1071,
+ -0.1884, -0.9040, +0.2916, +0.1474, -0.3503, -0.0670, +0.0115,
+ -0.3431, -0.2466, +0.0172, -0.3685, -0.2423, -0.3563, +0.0568,
+ -0.2901, +0.3279, -0.0507, -0.3400, +0.0597, -0.7429, +0.1562,
+ +0.1374, +0.1472, +0.2591, -0.1652, -0.3572, -0.2839, +0.3681,
+ -0.3434, -0.0406, +0.6815, +0.4870, +0.0323, +0.0971, -0.3273,
+ -0.5715, -0.6297, +0.0130, -0.2182, -0.2410, +0.0553, +0.0848,
+ -0.1464, +0.1847, -0.1045, -0.0546, +0.4837, -0.1203, +0.2788,
+ -0.4522, -0.3611
+ ],
+ [
+ -0.2749, +0.1106, +0.1256, +0.2567, +0.3371, +0.0996, +0.0218,
+ +0.2143, -0.0076, -0.0124, -0.3150, -0.3540, -0.3688, -0.0342,
+ +0.0547, +0.0646, +0.0438, -0.0632, -0.0416, +0.1328, -0.4048,
+ +0.2881, -0.1259, +0.2477, +0.1902, +0.2809, -0.0925, +0.1505,
+ -0.0625, -0.0313, -0.0193, +0.1215, +0.0865, -0.0537, +0.2175,
+ -0.2814, -0.3741, -0.1073, -0.2286, -0.1381, +0.0330, -0.4756,
+ +0.5680, +0.0102, +0.2286, +0.1292, -0.2090, -0.1476, +0.0124,
+ -0.1540, -0.0888, +0.1818, -0.0768, +0.2275, -0.3759, +0.2016,
+ -0.2089, -0.0438, -0.3113, +0.0180, +0.1691, -0.0824, -0.1768,
+ +0.3830, -0.2112, +0.5549, +0.2310, -0.1869, +0.2288, -0.0184,
+ +0.1784, +0.1876, +0.0629, +0.1112, +0.0433, -0.2884, -0.3035,
+ +0.2641, -0.0658, -0.2794, -0.0242, -0.0812, +0.0007, +0.1537,
+ +0.0732, -0.0304, -0.0965, +0.1865, +0.1234, -0.0193, -0.2290,
+ -0.0515, -0.3263, -0.4178, -0.0107, -0.0935, +0.1205, +0.4655,
+ -0.3045, -0.3361, -0.1098, -0.1217, -0.1009, -0.1051, +0.2145,
+ -0.3336, -0.0991, +0.1733, +0.1618, +0.3899, +0.0669, +0.1899,
+ +0.2073, +0.2872, -0.1592, +0.5334, +0.3533, +0.1068, -0.3265,
+ +0.0487, +0.1393, -0.2843, -0.5188, -0.2346, +0.1350, -0.2899,
+ +0.1907, -0.3176
+ ],
+ [
+ +0.2274, -0.6246, -0.0895, +0.0151, +0.2102, +0.1204, -0.0907,
+ -0.2346, +0.1844, +0.0237, +0.1189, -0.0365, -0.1414, -0.5732,
+ -0.1049, +0.1028, -0.1074, +0.2010, -0.1969, -0.4422, -0.3890,
+ +0.5785, -0.1674, +0.1003, -0.0714, -0.1012, -0.4929, +0.1018,
+ -0.2820, -0.1159, +0.1425, +0.3787, +0.0404, -0.1041, +0.3751,
+ -0.0828, -0.0284, -0.0910, -0.0095, +0.2729, +0.1558, +0.3046,
+ +0.1402, -0.4915, +0.4200, -0.4424, +0.3019, +0.0146, +0.0158,
+ -0.2747, +0.2268, -0.3321, +0.0220, -0.4112, +0.2537, +0.2902,
+ -0.5166, -0.0034, -0.1136, +0.2072, -0.4259, +0.0879, +0.2630,
+ +0.3531, +0.1753, -0.0971, +0.0215, -0.3038, +0.0496, -0.0076,
+ -0.0041, +0.4259, +0.0657, -0.5145, -0.2599, -0.4776, +0.3572,
+ -0.0882, -0.5125, +0.3645, -0.2350, +0.3037, +0.0251, +0.0069,
+ +0.1117, -0.1438, -0.3608, -0.0945, +0.0367, +0.3858, -0.1095,
+ +0.2089, +0.0670, +0.0303, +0.3321, -0.0496, -0.0875, -0.2644,
+ -0.3230, +0.2989, +0.2316, -0.2202, +0.1620, +0.0545, -0.0712,
+ -0.3471, +0.2478, +0.4852, -0.5060, -0.4551, -0.0413, -0.0806,
+ -0.1088, +0.1450, +0.3475, -0.2555, +0.4609, -0.2173, +0.0375,
+ -0.2081, -0.3098, +0.0208, -0.0619, -0.3731, -0.6503, +0.4515,
+ +0.2094, -0.0824
+ ],
+ [
+ -0.5170, +0.1003, -0.2783, -0.6186, +0.2368, -0.0190, -0.1630,
+ -0.1213, +0.1496, +0.0248, -0.1328, +0.0539, -0.0966, -0.0531,
+ -0.2163, -0.1158, -0.2377, +0.0500, +0.1625, +0.1170, -0.0106,
+ -0.3097, -0.4656, -0.4708, -0.0289, +0.0066, -0.3745, -0.6951,
+ +0.1199, -0.5173, +0.0549, +0.1097, -0.2456, +0.1115, +0.0591,
+ +0.0470, +0.1578, -0.1879, -0.0658, +0.0909, -0.2496, -0.2248,
+ +0.4248, -0.1354, -0.1393, -0.8688, +0.0636, -0.4394, +0.2200,
+ +0.1561, -0.4325, +0.4339, -0.0754, -0.0817, -0.0893, -0.1214,
+ -0.1116, +0.2879, -0.0563, -0.2715, -0.4882, +0.2859, -0.2995,
+ -0.1398, -0.2850, -1.0355, -0.3602, -0.0328, +0.1144, +0.0813,
+ +0.1973, -0.1108, -0.2196, +0.2758, +0.1210, +0.0388, +0.3758,
+ -0.0191, -0.0143, -0.1181, -0.0926, -0.1991, +0.1299, +0.3758,
+ -0.2773, -0.0428, -0.0928, +0.0626, -0.1142, -0.7525, -0.2598,
+ +0.2538, +0.0233, +0.1504, +0.1794, -0.3095, +0.0210, -0.0850,
+ -0.0495, -0.4411, +0.1839, +0.0477, -0.0286, +0.0936, -0.6572,
+ +0.1839, +0.4563, -0.2091, +0.0248, +0.1385, +0.3169, +0.0519,
+ -0.0989, -0.1175, -0.3051, +0.0354, -0.0424, +0.1304, +0.1515,
+ -0.0171, +0.1693, -0.0891, -0.2219, -0.4009, -0.0310, +0.1282,
+ +0.1776, -0.0047
+ ],
+ [
+ +0.1380, +0.2142, +0.4673, +0.1246, -0.1066, +0.0043, -0.5221,
+ +0.3742, -0.4602, -0.8135, +0.0083, -0.4086, +0.2676, +0.2790,
+ -0.2260, -0.0560, -0.2715, +0.2882, -0.2880, +0.0254, -0.1774,
+ -0.3830, +0.4338, -0.2213, +0.1391, -0.0732, +0.4147, -0.1880,
+ +0.0527, -0.2910, -0.0809, -0.1841, -0.3322, -0.4953, -0.1521,
+ +0.2495, -0.0054, -0.2932, -0.4878, -0.0038, +0.4161, -0.3234,
+ -0.0314, +0.1115, -0.4632, -0.3006, -0.0798, +0.1703, -0.2143,
+ -0.2859, -0.2375, +0.2771, -0.1369, -0.3072, -0.2897, -0.2418,
+ +0.0962, -0.3550, -0.0244, +0.4272, +0.1292, -0.1235, +0.2004,
+ +0.0508, -0.0173, -0.1179, -0.4618, +0.0211, +0.4627, +0.1255,
+ -0.0642, -0.6615, -0.8088, +0.1172, -0.2285, +0.1128, -0.4433,
+ +0.0289, +0.1877, +0.0257, -0.0601, +0.4759, +0.2316, +0.2525,
+ -0.8702, -0.1753, +0.1574, +0.2693, +0.1138, +0.0027, +0.3658,
+ -0.1321, +0.0335, -0.1231, -0.0159, +0.0725, +0.1244, -0.1485,
+ +0.3185, +0.1363, -0.2805, +0.0108, -0.3196, +0.0761, -0.1414,
+ -0.7086, -0.3851, +0.1082, -0.0947, -0.1132, +0.0128, +0.0426,
+ +0.1525, -0.2935, -0.2190, -0.1058, -0.3318, +0.2028, -0.0869,
+ -0.1759, -0.0099, -0.0156, +0.1404, +0.4959, +0.2544, -0.2563,
+ -0.1863, -0.3104
+ ],
+ [
+ -0.0462, -0.0661, +0.0177, +0.1117, -0.0840, -0.0354, +0.1956,
+ -0.1682, +0.4247, -0.2188, +0.0610, -0.2316, -0.1642, +0.0931,
+ -0.4613, +0.1745, +0.3985, +0.2796, +0.3386, -0.3525, +0.1070,
+ -0.2179, +0.1877, +0.0971, +0.0106, -0.2052, -0.2934, +0.3679,
+ +0.0239, +0.2812, +0.2747, +0.4661, -0.3552, +0.1835, -0.0808,
+ -0.3574, -0.0415, -0.0578, +0.2739, -0.5322, +0.5109, +0.0240,
+ -0.0562, -0.1229, +0.6340, +0.1371, -0.3732, +0.0357, -0.3860,
+ -0.4552, +0.0429, -0.4369, +0.1635, +0.0917, +0.0485, +0.4785,
+ -0.1511, +0.1110, +0.1995, +0.0097, +0.2405, -0.2414, +0.0298,
+ -0.2812, -0.4761, +0.0651, +0.0123, +0.1065, +0.0719, -0.0054,
+ -0.2184, +0.1448, -0.0888, -0.3939, +0.1655, -0.2067, -0.5353,
+ +0.2353, +0.2515, +0.2236, +0.1733, -0.6740, +0.4386, -0.5420,
+ +0.4434, +0.1039, -0.3120, +0.2169, -0.3071, -0.1024, +0.1452,
+ -0.1416, -0.1628, +0.2083, -0.1115, -0.7625, +0.3777, +0.1805,
+ +0.1196, -0.2727, -0.1867, +0.1559, -0.3124, +0.3247, +0.2318,
+ -0.4715, +0.1808, +0.0566, +0.0206, -0.0373, -0.1982, -0.0788,
+ +0.0168, +0.2310, +0.2439, +0.1661, -0.2146, +0.1834, -0.5113,
+ -0.0335, +0.1840, +0.0022, +0.0348, +0.0051, -0.2306, +0.1406,
+ -1.1259, +0.3664
+ ],
+ [
+ +0.0318, -0.2679, -0.2614, -0.1973, +0.2404, +0.1434, +0.3707,
+ +0.2090, +0.4069, -0.2247, -0.3218, -0.3096, +0.1293, -0.0884,
+ -0.3467, -0.4976, +0.0924, +0.1781, -0.1320, +0.0549, -0.5223,
+ -0.1325, +0.0103, -0.2401, -0.2866, +0.1653, +0.1530, +0.0176,
+ -0.2471, -0.0895, +0.0405, -0.1687, -0.0921, -0.1267, -0.1152,
+ -0.1043, -0.1753, +0.0893, -0.2130, -0.4188, -0.4725, -0.4629,
+ +0.1877, -0.3559, +0.1267, -0.3203, +0.0462, -0.4118, -0.1890,
+ +0.1122, -0.3732, -0.1022, +0.2022, -0.1366, +0.0030, -0.1273,
+ -0.1577, +0.0149, -0.4048, -0.0553, -0.3841, -0.0635, -0.0668,
+ -0.0240, -0.2512, -0.0342, +0.1208, +0.1698, +0.0684, +0.2576,
+ -0.4877, +0.0467, -0.1196, +0.0137, -0.0317, -0.1261, -0.1722,
+ +0.1796, +0.0264, -0.0866, +0.2900, -0.1445, -0.2117, -0.2555,
+ +0.0153, -0.0128, -0.1061, +0.2955, +0.0776, -0.1622, +0.1979,
+ -0.5717, -0.2221, -0.5955, +0.0113, -0.0887, +0.1299, +0.0254,
+ -0.3551, +0.1862, -0.2365, -0.1536, +0.3140, -0.2480, +0.0087,
+ -0.0997, +0.0713, -0.2663, -0.0440, +0.0937, +0.2929, +0.1531,
+ +0.0955, -0.1225, -0.0295, -0.4336, -0.5122, +0.1122, -0.8094,
+ -0.4266, +0.1985, +0.0234, -0.0613, +0.0515, +0.3909, -0.0183,
+ +0.1148, -0.1523
+ ],
+ [
+ +0.3359, -0.1869, -0.2533, -0.0985, -0.7635, +0.1533, -0.2820,
+ -0.3471, +0.0897, +0.0203, +0.2535, -0.2971, +0.4527, +0.0458,
+ -0.0874, +0.1152, +0.4554, +0.1142, -0.2699, +0.1179, -0.1985,
+ -0.9075, +0.2464, -0.4019, -0.0910, -0.2593, -0.2856, -0.0436,
+ -0.6527, +0.1452, -0.2960, +0.0344, +0.1343, -0.1048, -0.3936,
+ -0.3032, -0.3788, +0.0353, -0.1878, +0.0576, -0.1689, -0.4045,
+ -0.1461, +0.0830, +0.1182, -0.4652, -0.0953, -0.6720, +0.0945,
+ -0.5396, +0.0898, +0.2677, -0.2913, -0.4229, +0.1202, -0.0904,
+ -0.3550, -0.3097, +0.2230, +0.1057, +0.0718, -0.3367, +0.1662,
+ +0.0343, -0.1256, +0.1963, +0.0176, -0.6387, -0.1989, +0.2022,
+ +0.4656, +0.0942, -0.0056, -0.4187, +0.3404, +0.2211, +0.1169,
+ +0.1007, +0.0997, -0.2284, +0.3446, -0.0014, -0.0285, -0.1841,
+ -0.0327, +0.4128, -0.1193, -0.0727, +0.1012, +0.1710, -0.1450,
+ -0.3435, -0.0115, -0.4703, +0.2966, +0.8223, -0.4463, +0.1917,
+ +0.1166, +0.3306, +0.1405, +0.0708, -0.0131, -0.6147, +0.0924,
+ +0.0075, +0.1126, +0.2569, -0.1908, +0.0480, -0.1231, +0.3264,
+ +0.1711, -0.2605, -0.2647, +0.3721, -0.0645, +0.1503, +0.1291,
+ +0.1172, -0.2780, -0.1826, +0.4557, -0.1936, -0.2885, +0.2577,
+ -0.0979, +0.1202
+ ],
+ [
+ -0.1158, -0.1203, +0.2931, -0.0169, -0.1224, -0.2196, +0.0375,
+ +0.1217, -0.0717, +0.0309, -0.3250, -0.6930, +0.3157, +0.3399,
+ +0.1499, -0.4654, +0.1378, +0.0857, +0.1082, -0.1218, +0.2364,
+ -0.2335, -0.3723, +0.1551, +0.2133, -0.1149, +0.2749, +0.0897,
+ +0.0351, +0.3511, +0.0369, +0.0891, -0.0289, +0.1253, +0.1030,
+ -0.3115, -0.0120, +0.1679, -0.2288, -0.0316, +0.0693, -0.1857,
+ -0.0275, +0.1549, -0.0970, +0.3139, -0.3723, -0.2072, -0.0652,
+ -0.7408, -0.2646, -0.3538, -0.0154, -0.0892, -0.0768, -0.2742,
+ -0.0490, -0.0602, +0.0019, +0.1352, -0.0770, -0.3543, -0.0697,
+ -0.0010, -0.1149, +0.4413, -0.0254, -0.3315, -0.1090, -0.2054,
+ +0.1694, +0.2616, +0.0942, +0.2497, +0.0530, +0.0563, -0.7192,
+ +0.4092, -0.0048, +0.0902, -0.1310, -0.1415, -0.2011, -0.6722,
+ -0.3626, -0.2573, +0.0514, +0.2064, +0.4356, -0.3869, -0.4955,
+ +0.4278, -0.0143, +0.5334, -0.0880, +0.3717, +0.2425, +0.3499,
+ -0.1294, -0.2654, -0.3768, -0.0888, -0.0157, -0.0979, -0.0309,
+ +0.2135, +0.5274, +0.1955, -0.1448, +0.1123, -0.3041, +0.2034,
+ +0.3085, -0.1826, +0.0387, -0.0188, +0.0767, +0.0393, +0.0995,
+ -0.0815, -0.1028, +0.3061, -0.0871, +0.0163, +0.0341, -0.0941,
+ +0.1141, -0.0859
+ ],
+ [
+ +0.1346, -0.2172, +0.0978, -0.6672, -0.1348, -0.0431, -0.2859,
+ +0.2175, -0.0364, -0.0001, +0.1272, -0.0153, +0.1906, +0.0659,
+ +0.0133, -0.1530, +0.0221, +0.1844, -0.1527, +0.2800, -0.1700,
+ +0.1811, -0.0547, -0.1051, +0.0705, +0.4800, +0.3136, +0.3016,
+ +0.1607, -0.2637, -0.0977, +0.3550, -0.8973, -0.0959, +0.1339,
+ -0.0700, +0.0018, +0.2663, -0.0236, +0.2359, +0.1039, +0.1942,
+ +0.0607, -0.3812, -0.5102, +0.0543, +0.0873, +0.3242, -0.2135,
+ -0.2219, -0.1992, +0.2718, -0.1586, +0.3889, +0.1715, -0.2721,
+ -0.2973, -0.3207, -0.0925, +0.1679, +0.0101, +0.1243, -0.0946,
+ +0.4589, +0.0732, +0.2290, +0.1831, -0.2087, +0.0723, -0.3444,
+ +0.0759, +0.0474, +0.1058, +0.0749, +0.3074, +0.0300, -0.0406,
+ -0.0367, -0.2537, -0.0259, +0.2831, +0.2101, -0.2099, +0.1691,
+ -0.1417, +0.3665, -0.2222, +0.0689, -0.5235, -0.4461, +0.0953,
+ +0.0713, -0.0981, +0.1386, -0.2551, -0.1353, -0.2220, +0.0984,
+ +0.1421, -0.2133, +0.3212, +0.0994, +0.2285, -0.1218, -0.1785,
+ -0.3109, +0.1328, -0.0235, -0.1608, +0.4227, +0.0215, +0.0019,
+ +0.0836, +0.1117, -0.0728, -0.2913, -0.1075, +0.1626, -0.3855,
+ +0.0457, +0.3605, +0.2480, -0.2352, -0.1792, -0.3048, +0.0033,
+ -0.2870, -0.2734
+ ],
+ [
+ +0.2825, +0.0253, +0.3434, -0.4158, +0.3016, +0.0192, -0.0418,
+ -0.1255, -0.1076, +0.0548, -0.1023, -0.5851, +0.1909, +0.2882,
+ -0.3090, -0.7278, +0.3460, +0.2750, -0.7070, -0.0496, +0.3945,
+ -0.2519, -0.1225, -0.0607, -0.4056, -0.2111, +0.3660, -0.0585,
+ +0.4245, +0.2649, -0.3773, +0.0827, -0.1903, -0.2281, -0.0650,
+ -0.0638, -0.2845, -0.1337, -0.0783, +0.1342, -0.1489, -0.4966,
+ +0.0118, +0.0197, +0.0057, +0.0949, +0.0621, -0.0338, -0.0991,
+ +0.0066, -0.1481, +0.2726, -0.4469, -0.3302, +0.2692, +0.1707,
+ +0.3707, +0.1253, -0.4246, -0.1088, -0.4577, +0.3361, -0.1334,
+ -0.0922, -0.0685, -0.0547, +0.4337, +0.1579, -0.4863, +0.0767,
+ +0.1318, +0.1400, -0.4470, +0.3186, -0.3718, -0.2955, -0.2746,
+ -0.0406, +0.5112, -0.0238, +0.0284, -0.1063, -0.0117, -0.8589,
+ -0.3694, +0.0320, +0.0189, +0.0331, -0.2141, -0.8608, +0.0327,
+ -0.0556, -0.1770, +0.1723, -0.2761, -0.1774, +0.0713, -0.0250,
+ -0.0596, -0.0625, +0.2231, +0.0175, -0.0983, +0.0422, +0.1555,
+ -0.5649, -0.3524, -0.2454, +0.1824, -0.0103, -0.1012, -0.9742,
+ -0.1553, +0.1821, -0.4459, -0.3179, -0.1515, +0.1620, +0.3267,
+ +0.1404, +0.2546, -0.1374, +0.1050, +0.3883, +0.1537, +0.3372,
+ -0.1049, +0.2927
+ ],
+ [
+ -0.1137, -0.4166, +0.0811, -0.1074, +0.1298, +0.3253, -0.2082,
+ -0.2213, +0.1534, -0.1803, -0.0258, +0.0401, +0.0798, -0.2134,
+ +0.2491, +0.0716, +0.0343, -0.2944, +0.2551, +0.0941, +0.0408,
+ -0.3241, +0.0993, +0.0733, -0.3525, -0.0441, +0.1505, +0.4496,
+ +0.2280, -0.7034, +0.3645, +0.1627, +0.1388, +0.0158, +0.0827,
+ +0.0373, +0.3876, +0.2836, -0.0866, -0.0687, +0.2009, +0.1649,
+ -0.2235, +0.2029, -0.2978, -0.0627, +0.1204, +0.3592, +0.1627,
+ -0.0046, -0.2956, -0.0393, -0.0124, -0.0285, -0.0873, +0.1263,
+ -0.0741, -0.2644, -0.4354, +0.1968, -0.1551, +0.2574, +0.3975,
+ -0.2532, +0.2247, +0.1793, -0.0178, +0.0389, -0.2176, -0.0078,
+ +0.3203, -0.4747, +0.2487, -0.2343, -0.1160, +0.2001, -0.0703,
+ -0.3625, -1.2527, -0.0600, +0.4611, -0.5930, -0.2747, -0.0267,
+ +0.3052, +0.1597, +0.0768, +0.1167, -0.2072, +0.2038, +0.3434,
+ -0.0937, +0.0957, +0.3292, +0.0797, -0.2865, -0.0670, -0.0445,
+ -0.1057, -0.2379, +0.5652, +0.0320, +0.0419, +0.4116, -0.1071,
+ +0.0689, +0.0907, +0.3484, +0.1590, +0.0351, -0.0998, +0.1812,
+ +0.0501, -0.0919, -0.1304, -0.2934, +0.2443, +0.1057, -0.0614,
+ +0.0500, +0.0664, -0.0375, +0.1694, -0.2717, -0.2612, -0.3212,
+ -0.2974, +0.2638
+ ],
+ [
+ -0.5774, +0.3181, -0.3273, -0.1211, +0.0055, -0.4124, +0.0537,
+ -0.2612, +0.2349, -0.4658, -0.0050, -1.0234, -0.3664, -0.1299,
+ -0.1466, -0.0418, -0.2383, -0.3654, +0.3775, +0.1982, -0.1129,
+ -0.1871, +0.2701, +0.4368, +0.0212, +0.1457, +0.0686, -0.2753,
+ +0.1434, -0.0047, +0.1454, +0.0819, -0.3603, +0.1466, +0.1092,
+ -0.3422, -0.4487, -0.0906, -0.3430, -0.2524, +0.1927, +0.1330,
+ -0.1120, +0.1445, +0.2624, +0.1544, -0.0290, -0.3791, -0.7613,
+ +0.2273, +0.5885, +0.0024, -0.3480, +0.1977, -0.0958, -0.6726,
+ +0.3647, +0.2863, +0.1615, -0.3028, +0.1422, +0.0351, -0.2444,
+ +0.4095, -0.1586, -0.2540, -0.2831, +0.1385, -0.1211, +0.0820,
+ +0.0624, -0.3549, +0.5922, +0.0954, -0.2535, -0.0218, -0.0244,
+ +0.3862, -0.1688, -0.3774, +0.3790, +0.2072, -0.0622, -0.2919,
+ +0.0455, +0.3040, -0.3514, -0.0860, +0.0334, -0.1671, +0.2577,
+ -0.5322, +0.0133, +0.1657, -0.3508, -0.2676, +0.3673, -0.0115,
+ -0.0482, -0.0297, -0.0389, +0.1215, -0.1455, +0.0523, -0.0173,
+ -0.6891, -0.0529, +0.0384, +0.0603, -0.0842, +0.2071, -0.3928,
+ -0.4082, -0.3285, +0.1687, -0.0882, +0.3685, +0.6179, -0.1699,
+ +0.1308, +0.3543, -0.3176, +0.3397, +0.3826, +0.3932, -0.2160,
+ +0.0758, -0.5191
+ ],
+ [
+ +0.0368, -0.2841, +0.3212, -0.1046, +0.1066, -0.1692, +0.0441,
+ -0.1738, +0.1288, +0.1462, +0.3217, +0.0865, +0.0390, -0.0192,
+ +0.0404, -0.2603, -0.0536, -0.0572, -0.1969, +0.0769, -0.1008,
+ -0.1035, +0.2273, +0.2291, -0.3269, +0.1858, -0.0050, +0.0674,
+ -0.0107, -0.1338, +0.3698, -0.5048, +0.1857, +0.0551, +0.0661,
+ -0.1068, -0.0948, +0.0117, +0.1151, +0.2025, +0.3121, -0.2408,
+ +0.1965, +0.0487, -0.7906, -0.0334, +0.3236, +0.1644, +0.4166,
+ -0.1055, +0.1932, -0.0195, -0.3465, +0.0443, +0.1194, +0.0125,
+ -0.0827, -0.0962, +0.2962, -0.0488, +0.1598, +0.3571, +0.0897,
+ +0.3379, -0.2544, +0.2126, -0.0753, +0.2236, -0.3288, -0.2804,
+ -0.2382, -0.0673, -0.4725, -0.2956, +0.3931, -0.0577, -0.0484,
+ -0.0825, -0.0234, -0.0012, -0.2582, +0.2310, +0.1934, -0.0328,
+ -0.3296, -0.0377, +0.0144, -0.0493, +0.1883, +0.1098, -0.0826,
+ -0.3920, +0.0428, +0.2089, -0.2060, -0.7064, +0.1179, -0.0451,
+ -0.2583, +0.0018, +0.2450, +0.2332, +0.1510, +0.1215, +0.3939,
+ -0.0024, +0.0365, -0.0031, +0.2525, +0.4259, -0.1204, +0.4661,
+ -0.4353, -0.1290, -0.1438, +0.0636, -0.0102, -0.3655, +0.0300,
+ +0.1916, -0.0599, -0.2007, +0.0524, -0.1662, -0.2424, -0.0274,
+ -0.1569, +0.1000
+ ],
+ [
+ -0.0637, -0.1863, -0.6578, -0.4075, +0.4592, +0.0931, +0.0450,
+ -0.2538, +0.2210, -0.1249, -0.0020, +0.0283, +0.0380, +0.0780,
+ -0.1990, -0.0818, -0.4455, -0.0233, +0.2985, -0.0360, +0.0030,
+ +0.1289, -0.4828, -0.0266, +0.3165, +0.4611, -0.1339, +0.2269,
+ -0.3576, +0.2379, +0.0616, +0.0536, -0.1029, -0.2106, +0.2604,
+ +0.2081, -0.1925, -0.0754, +0.2499, +0.3368, -0.0372, +0.1727,
+ +0.0510, +0.3065, -0.3597, +0.0893, +0.0763, +0.2531, +0.0945,
+ -0.0978, -0.4872, +0.1585, +0.2350, +0.0042, +0.2615, +0.5016,
+ -0.0575, +0.3570, -0.2265, +0.0205, -0.0211, +0.0035, +0.1404,
+ -0.0716, +0.1827, -0.0442, -0.0263, +0.1428, +0.1302, +0.1828,
+ -0.2924, -0.0227, +0.1217, -0.6324, +0.2053, +0.1390, +0.0127,
+ +0.1238, +0.1171, -0.1365, -0.2359, -0.4082, -0.1660, +0.1427,
+ +0.1196, -0.0325, +0.0057, +0.4846, +0.0993, -0.0405, +0.1408,
+ -0.1807, -0.2587, +0.3101, +0.1675, +0.0447, -0.3461, -0.2691,
+ -0.4096, -0.0942, +0.1744, -0.0936, -0.5898, -0.2103, -0.1726,
+ -0.0253, +0.0434, -0.1817, -0.0017, -0.0732, +0.0117, -0.0722,
+ +0.0378, -0.0350, +0.1071, +0.1702, +0.0475, -0.2638, -0.1625,
+ -0.1349, -0.0802, +0.2415, -0.5080, -0.1928, -0.1470, -0.4723,
+ +0.0916, -0.3390
+ ],
+ [
+ -0.0319, -0.2568, -0.3452, -0.8975, +0.0234, +0.0465, -0.2783,
+ -0.0049, +0.2664, +0.1066, +0.1903, -0.1544, +0.1015, +0.0390,
+ +0.2634, +0.1084, +0.4512, -0.0436, -0.1367, +0.0045, -0.1837,
+ +0.1029, -0.1632, -0.1837, +0.6919, -0.0553, +0.0326, -0.1813,
+ -0.0900, +0.1512, -0.4626, -0.1875, -0.4928, -0.0598, +0.1387,
+ -0.2047, +0.2451, +0.0565, -0.1416, -0.3491, -0.3006, -0.1248,
+ +0.0152, -0.2328, +0.2402, -0.0661, +0.0658, +0.1040, +0.3802,
+ -0.0112, +0.0407, -0.1680, +0.0345, +0.1971, +0.3401, +0.2459,
+ -0.0255, +0.1214, +0.2680, -0.3016, -0.2448, -0.1874, -0.2089,
+ -0.1908, -0.1026, -0.0855, -0.4025, -0.3408, -0.2456, +0.5108,
+ +0.3292, +0.3236, +0.0067, -0.2123, -0.3467, -0.4285, +0.3948,
+ -0.1683, +0.1793, +0.0202, +0.1046, -0.1635, +0.0089, +0.1688,
+ -0.2510, -0.3722, -0.2089, -0.1783, -0.0669, +0.0678, -0.5277,
+ -0.0529, +0.1733, +0.0191, -0.0705, +0.0364, +0.1663, -0.1209,
+ +0.1131, +0.1186, +0.2512, -0.0488, +0.0809, -0.1145, -0.1271,
+ -0.0396, -0.1508, +0.1063, +0.0833, -0.0061, +0.0375, +0.0654,
+ -0.3352, -0.2458, -0.2320, -0.3859, -0.0070, +0.1126, -0.1032,
+ -0.2134, -0.0926, +0.0302, +0.1784, -0.0682, -0.0282, -0.7006,
+ +0.1910, -0.3904
+ ],
+ [
+ +0.3192, +0.1111, -0.6012, +0.3225, -0.4535, -0.0085, -0.3111,
+ +0.1855, -0.1676, -0.0738, +0.0822, +0.1434, +0.4061, -0.0507,
+ +0.4361, -0.3297, +0.3959, -0.0188, +0.4148, -0.5738, +0.1457,
+ -0.0489, +0.2778, -0.3531, -0.1397, -0.1520, -0.0287, -0.6212,
+ -0.3127, +0.2671, +0.2058, -0.4405, -0.2342, -0.5902, +0.3898,
+ +0.3465, +0.1755, -0.0220, +0.1983, -0.0664, +0.2772, +0.1739,
+ +0.1469, +0.1508, +0.0469, -0.0437, +0.2568, +0.2491, -0.0083,
+ +0.1356, +0.0938, +0.0837, +0.0836, +0.0214, +0.4250, -0.1934,
+ -0.4020, -0.1029, -0.5578, +0.2044, -0.2170, -0.0228, +0.1993,
+ +0.2275, +0.1241, +0.1742, +0.0646, -0.2667, -0.2929, -0.1490,
+ -0.1064, -0.1058, -0.0915, +0.4289, +0.0903, -0.0145, +0.0636,
+ -0.1609, +0.1068, +0.0953, -0.1067, +0.6037, +0.0392, -0.3197,
+ +0.5477, -0.2598, -0.1731, +0.2520, -0.1743, +0.3163, +0.1029,
+ +0.0826, +0.0984, -0.1887, +0.1584, +0.0799, -0.0282, -0.3150,
+ +0.2303, -0.1113, +0.0595, +0.3788, -0.0392, +0.3025, -0.3878,
+ -0.5151, +0.2330, +0.0285, +0.3161, -0.0239, -0.4795, +0.0254,
+ -0.2269, +0.2386, +0.1402, +0.1470, -0.6547, -0.0564, +0.1567,
+ +0.2744, -0.2991, -0.1626, -0.0430, +0.3150, -0.3246, -0.5712,
+ -0.0055, -0.3797
+ ],
+ [
+ -0.3311, +0.5520, +0.0202, +0.0347, -0.0955, +0.1769, -0.1216,
+ -0.5414, -0.0140, -0.4940, +0.0579, +0.1224, -0.3528, -0.0838,
+ +0.0529, +0.3608, -0.0284, +0.3117, -0.2008, -0.1805, -0.0194,
+ -0.0832, -0.4345, -0.0929, +0.2921, -0.1498, -0.1107, -0.1055,
+ +0.1120, +0.0489, -0.0705, +0.3460, -0.5063, -0.1734, -0.1611,
+ -0.1879, +0.0308, -0.1548, +0.2727, -0.3340, -0.0900, +0.0219,
+ -0.2370, +0.1133, -0.4604, +0.0397, +0.0569, -0.0033, +0.1989,
+ +0.0316, -0.0793, +0.3309, -0.2333, -0.0901, -0.0592, +0.6892,
+ -0.2496, -0.3073, -0.2298, +0.0616, -0.3792, +0.1182, +0.1591,
+ -0.3000, +0.0748, +0.0657, +0.1301, -0.4092, -0.0038, +0.2277,
+ +0.1257, -0.2273, +0.1688, -0.2584, -0.4970, -0.4494, +0.1215,
+ -0.4090, -0.2102, -0.0350, -0.5087, -0.4668, -0.1650, -0.0987,
+ +0.1236, +0.2362, +0.2316, -0.0291, -0.0943, -0.5639, +0.1708,
+ +0.2437, -0.1004, -0.1398, +0.1035, +0.1159, -0.1351, +0.1072,
+ -0.1315, -0.3223, -0.4333, +0.4723, -0.1710, -0.2299, +0.2976,
+ -0.0060, +0.1195, -0.0104, +0.1074, -0.2846, -0.4527, -0.2632,
+ +0.1364, +0.0941, +0.1204, +0.0046, +0.0114, +0.0163, -0.1973,
+ +0.3729, +0.0846, -0.4045, +0.2118, +0.0164, -0.2190, -0.2371,
+ -0.2993, +0.2432
+ ],
+ [
+ -0.1999, +0.2731, -0.5014, +0.0910, -0.0931, +0.1036, -0.1270,
+ -0.0817, -0.0154, -0.0206, -0.0408, +0.4497, +0.2223, +0.2196,
+ -0.7578, +0.2677, +0.0995, -0.2112, -0.0028, +0.2438, +0.1108,
+ +0.2180, -0.1645, +0.1080, -0.0588, -0.3713, +0.2330, +0.0622,
+ +0.0356, -0.1107, +0.2171, +0.3460, +0.1169, -0.0950, +0.0433,
+ +0.2683, +0.3525, +0.0266, -0.0754, -0.5264, +0.2388, -0.6409,
+ -0.0726, +0.0384, -0.1989, -0.0009, -0.4445, -0.1684, +0.1225,
+ -0.1660, +0.4413, -0.1799, +0.2400, -0.3099, +0.0016, -0.0833,
+ -0.7784, +0.4708, -0.6577, +0.3799, +0.6264, -0.1871, -0.3739,
+ -0.4713, -0.1501, -0.4015, -0.1328, +0.0957, +0.1912, +0.0638,
+ -0.0467, -0.4078, +0.1610, -0.0365, -0.3455, -0.2260, -0.3127,
+ -0.1146, +0.0137, +0.5440, -0.0219, +0.2123, -0.0637, -0.2723,
+ -0.2934, +0.1655, -0.2298, -0.2410, -0.5185, -0.2223, -0.0961,
+ +0.0352, +0.2925, +0.3485, -0.1372, -0.4120, +0.1116, -0.1099,
+ +0.0138, +0.0291, -0.0382, -0.7153, -0.2397, +0.2314, +0.1870,
+ -0.0262, -0.3472, -0.1412, +0.1835, +0.1803, -0.3371, +0.1257,
+ -0.0936, -0.0660, -0.0033, -0.1456, +0.1906, -0.0405, -0.0503,
+ +0.0937, -0.2006, -0.3532, +0.0603, +0.2505, +0.3601, -0.0452,
+ -0.0635, -0.6510
+ ],
+ [
+ +0.0801, -0.1152, -0.1023, -0.2728, +0.2922, -0.1832, +0.0599,
+ -0.1848, +0.4450, +0.1490, -0.1221, +0.1036, +0.0132, +0.0810,
+ +0.1268, -0.1337, -0.3961, +0.1085, -0.0716, -0.1921, -0.3443,
+ +0.1464, +0.0135, +0.2471, +0.1164, -0.1025, -0.0783, -0.2663,
+ -0.1993, +0.0015, +0.0044, -0.4095, -0.0273, -0.1155, -0.4331,
+ +0.1066, +0.0919, -0.2454, -0.2628, +0.2389, -0.1057, +0.2725,
+ -0.1989, -0.1479, +0.0510, +0.0092, -0.1120, +0.1414, +0.0799,
+ -0.0754, -0.2215, -0.1256, -0.0623, +0.2077, +0.3035, -0.2214,
+ -0.6918, +0.1394, +0.2235, +0.1078, +0.0306, -0.1905, +0.1945,
+ +0.1752, +0.3299, +0.1567, -0.4560, -0.0486, +0.2782, +0.0370,
+ -0.0034, -0.1706, +0.2711, +0.0758, +0.3491, -0.4888, -0.1950,
+ +0.1386, +0.1543, +0.0083, +0.1213, -0.3797, -0.0387, -0.3016,
+ +0.0131, -0.2130, -0.3180, +0.1819, -0.1755, +0.0802, -0.2931,
+ +0.1786, -0.0149, -0.1051, -0.0315, +0.1551, -0.1358, +0.0589,
+ +0.5969, +0.2370, +0.3050, +0.2023, +0.2449, +0.3847, -0.1073,
+ +0.0952, -0.1834, -0.0657, -0.0297, -0.1044, -0.1129, -0.2891,
+ +0.1358, +0.0482, +0.1766, +0.1571, +0.2808, +0.4726, +0.1341,
+ -0.2285, -0.3607, -0.0398, +0.6096, +0.1937, +0.2873, -0.1861,
+ -0.1185, +0.3545
+ ],
+ [
+ -0.3278, -0.1930, -0.1599, -0.5355, -0.1366, +0.1130, +0.0473,
+ -0.2217, -0.0350, +0.0798, +0.0793, -0.5043, +0.1174, +0.3034,
+ +0.0124, +0.2226, +0.3267, +0.1707, +0.2169, -0.5309, +0.1600,
+ +0.0517, -0.4852, +0.0062, +0.0718, +0.1663, -0.0552, +0.0169,
+ +0.0383, -0.0693, +0.1500, +0.0157, -0.0304, +0.1954, -0.0287,
+ -0.3461, +0.1973, +0.0111, +0.1130, -0.1460, +0.0315, -0.5328,
+ +0.2015, +0.3556, -0.0869, +0.0870, -0.5072, +0.1132, -0.2748,
+ -0.4480, -0.2697, -0.0652, -0.5685, -0.4562, +0.1975, +0.2419,
+ -0.4626, +0.0024, -0.1507, -0.1471, +0.2193, -0.1275, +0.4040,
+ +0.3209, +0.1640, -0.1510, -0.4820, +0.1794, -0.4405, -0.1735,
+ +0.1729, -0.3057, -0.4526, -0.0080, -0.4693, -0.2131, -0.2706,
+ +0.0447, +0.1040, -0.3679, -0.4076, -0.1979, -0.2949, +0.1116,
+ +0.2748, -0.3093, -0.0293, -0.0922, +0.1830, +0.1941, +0.3643,
+ -0.1352, +0.3278, +0.0598, +0.1934, +0.1198, +0.0962, -0.4302,
+ +0.1065, +0.0470, -0.2098, +0.3883, +0.0830, +0.1810, +0.0977,
+ +0.1435, -0.0660, +0.0221, +0.2323, +0.0524, +0.2645, +0.1619,
+ -0.1579, +0.1316, -0.2469, +0.2635, -0.1006, -0.2155, +0.0331,
+ -0.2031, -0.0216, -0.1451, +0.2895, -0.0214, +0.3568, -0.3865,
+ -0.1667, -0.1800
+ ],
+ [
+ -0.3304, -0.2134, +0.3510, -0.5108, -0.2111, -0.1792, -0.0421,
+ +0.4758, +0.2467, -0.5291, -0.0360, +0.3120, -0.0341, -0.3329,
+ +0.0485, +0.0262, -0.0625, +0.2772, +0.0243, +0.0503, -0.3026,
+ +0.1754, +0.1102, -0.1137, +0.2720, -0.2735, +0.2843, +0.0928,
+ +0.3817, -0.1360, +0.3084, +0.2154, +0.0551, +0.0254, -0.2090,
+ -0.2294, +0.3103, +0.2654, +0.1559, -0.5294, +0.0432, +0.3977,
+ -0.4601, +0.1524, -0.1085, -0.4227, -0.4719, +0.2092, +0.1943,
+ +0.1581, +0.0410, +0.4207, +0.0977, -0.3378, +0.1116, -0.0014,
+ -0.4745, +0.6479, +0.0745, +0.5830, +0.1199, -0.1011, -0.1293,
+ -0.0804, +0.0018, +0.2811, -0.2055, +0.3042, +0.0299, -0.1093,
+ -0.1341, -0.5747, -0.1965, -0.0029, -0.4240, -0.0170, -0.0404,
+ +0.2126, -0.4633, +0.2287, +0.2028, -0.3558, -0.1158, +0.4914,
+ +0.3413, +0.1495, -0.0327, -0.4714, -0.7613, +0.1391, +0.0399,
+ +0.2837, -0.2018, -0.3605, -0.2774, -0.1837, -0.0889, +0.1551,
+ +0.0221, +0.4301, +0.3622, +0.1331, +0.6120, +0.4287, -0.0283,
+ -0.6826, -0.0267, -0.0294, +0.0663, -0.0459, -0.2412, -0.5911,
+ -0.1372, +0.2309, +0.1248, +0.1185, +0.2075, +0.2477, -0.1539,
+ +0.1403, +0.3769, -0.2115, +0.1617, -0.0457, +0.0571, -0.2857,
+ +0.6603, +0.4566
+ ],
+ [
+ -0.1823, +0.0784, +0.2491, -0.0658, -0.1253, -0.3280, -0.0786,
+ -0.0834, +0.1769, -0.1943, +0.0284, +0.2453, -0.1602, +0.2141,
+ +0.2370, +0.2935, -0.0225, -0.1074, -0.0917, +0.0168, +0.0555,
+ +0.0727, +0.1091, -0.4227, -0.0792, -0.2282, +0.1589, -0.0921,
+ +0.0707, -0.2317, -0.1100, -0.4094, -0.4553, -0.2184, -0.0116,
+ +0.1466, +0.1430, +0.1080, -0.4107, -0.1796, +0.2525, +0.3216,
+ -0.9063, -0.0929, +0.3810, -0.7382, +0.5492, -0.0668, +0.3180,
+ +0.4302, -0.0739, -0.0155, -0.1496, -0.0550, +0.2669, -0.3280,
+ +0.1120, +0.1728, -0.1383, +0.2225, +0.2539, +0.2513, +0.0321,
+ +0.5312, +0.2007, -0.4269, +0.1030, -0.0593, +0.2921, -0.1206,
+ -0.1005, +0.3027, -0.3273, -0.3401, +0.4240, -0.1429, -0.3607,
+ -0.2518, -0.3908, -0.1625, +0.0287, -0.0235, -0.4878, +0.4316,
+ -0.2891, +0.0565, +0.2353, -0.0641, +0.3064, +0.2112, -0.1420,
+ -0.2177, -0.3821, +0.7271, +0.3713, -0.3661, +0.5337, +0.1600,
+ +0.2798, +0.0060, -0.5892, -0.0844, -0.0186, +0.1678, -0.4085,
+ -0.6148, -0.3494, -0.2869, -0.1150, -0.2749, -0.0230, -0.1066,
+ +0.0143, +0.0127, +0.0161, -0.2056, -0.2318, -0.5619, +0.1652,
+ +0.1019, -0.1633, -0.1833, -0.2370, +0.2717, +0.2952, +0.0667,
+ +0.0990, -0.4266
+ ],
+ [
+ -0.1404, +0.2058, +0.1602, +0.0134, -0.0048, -0.0035, -0.0355,
+ -0.2216, +0.2586, +0.3609, -0.2009, -0.1837, -0.0456, -0.0235,
+ -0.2660, -0.0855, +0.2575, -0.1742, +0.0712, -0.3809, +0.0540,
+ -0.3518, +0.0654, -0.0985, -0.0174, -0.2376, -0.0256, -0.4111,
+ -0.2828, +0.0993, +0.2304, +0.5239, -0.3554, +0.0383, +0.2434,
+ -0.5734, -0.1051, -0.3595, +0.2396, -0.8436, -0.1097, +0.3730,
+ -0.0296, -0.7251, -0.5459, +0.0122, -0.2128, -0.0621, -0.0256,
+ -0.1174, +0.0882, -0.4369, -0.0668, +0.1133, -0.1152, +0.2048,
+ -0.1807, -0.1928, +0.1486, +0.0628, +0.0596, +0.2119, -0.6358,
+ -0.2254, -0.7158, -0.1149, -0.2410, -0.5986, +0.5575, +0.0465,
+ +0.1609, +0.1187, +0.0130, +0.1342, +0.0813, -0.0330, -0.3847,
+ +0.1347, -0.4587, -0.1143, +0.2428, -0.5963, -0.1608, -0.1482,
+ +0.0627, +0.3220, +0.1516, +0.4999, -0.0128, -0.0200, -0.1320,
+ -0.0554, +0.2049, -0.1251, -0.5828, -0.8083, +0.1950, -0.1099,
+ -0.0353, +0.1212, +0.1774, -0.2833, +0.3942, +0.0153, -0.0157,
+ +0.3691, -0.2966, -0.0717, -0.6072, +0.1585, +0.3019, +0.3623,
+ -0.1689, -0.1160, +0.0535, -0.2640, -0.1563, -0.3521, +0.2048,
+ +0.4548, +0.0275, +0.1527, +0.0274, -0.2322, +0.1108, -0.2821,
+ +0.1913, +0.3169
+ ],
+ [
+ +0.1590, -0.1035, -0.2605, +0.0136, -0.3923, +0.0692, -0.7490,
+ -0.2982, -0.0454, +0.0929, -0.2295, -0.3157, -0.0764, -0.5633,
+ +0.0159, -0.3085, +0.1804, -0.0719, -0.3588, -0.7964, -0.6185,
+ -0.3666, -0.0235, -0.0345, -0.3317, +0.1480, -0.4855, +0.1127,
+ -0.5958, +0.1819, -0.0419, -0.1468, +0.1142, +0.1051, -0.2639,
+ +0.0997, +0.3395, -0.3084, -0.3258, -0.1066, -0.2893, -0.0037,
+ +0.0564, -0.1242, +0.0657, -0.0035, +0.0636, +0.4068, -0.1448,
+ -0.3482, -0.2538, +0.3569, +0.2159, -0.0154, -0.6304, -0.4189,
+ -0.0635, -0.3691, -0.2921, +0.0409, +0.1899, -0.3812, +0.2210,
+ -0.6655, +0.3989, -0.1049, +0.1303, -0.0892, -0.5919, -0.3518,
+ -0.1278, -0.1322, +0.4399, +0.1367, -0.7090, -0.6477, +0.6335,
+ -0.0354, +0.0506, -0.9850, -0.2243, -0.0365, -0.2207, -0.0357,
+ +0.0192, -0.3252, +0.4193, -0.4387, -0.0567, -0.1070, +0.0985,
+ +0.0036, +0.3469, -0.3330, +0.1098, +0.2214, +0.2048, -0.0146,
+ -0.0623, -0.5665, +0.2825, -0.0504, -0.5541, -0.1815, +0.0756,
+ -0.0723, -0.2771, +0.2300, +0.0135, -0.1535, +0.3194, +0.0648,
+ -0.4801, -0.3012, -0.0178, -0.4948, +0.0913, -0.0701, -0.0560,
+ +0.1917, +0.0169, +0.2973, -0.2595, -0.4123, -0.2222, +0.2014,
+ -0.0542, -0.3881
+ ],
+ [
+ +0.0190, -0.2289, +0.2122, +0.3353, -0.1944, -0.1196, +0.3250,
+ -0.4051, -0.4948, +0.0590, -0.4226, -0.5429, -0.0153, +0.1209,
+ +0.1909, +0.0308, -0.0752, -0.5306, -0.0138, -0.2742, -0.2818,
+ +0.3312, -0.3404, -0.3811, +0.1262, -0.2478, +0.3360, -0.0831,
+ -0.2199, +0.3797, -0.0050, -0.3790, +0.3728, -0.4673, -0.1201,
+ -0.6100, +0.2481, +0.0763, +0.0353, +0.2943, +0.2041, +0.2258,
+ +0.0065, -0.3684, +0.1407, +0.0883, -0.2261, -0.3986, +0.1192,
+ +0.0393, -0.1829, +0.0456, -0.1700, -0.1890, -0.0255, +0.5810,
+ +0.2534, -0.6135, -0.2221, +0.3232, +0.1238, +0.2076, -0.0528,
+ -0.2240, -0.1124, +0.1144, +0.0085, +0.0646, +0.2492, +0.3381,
+ +0.0875, +0.2317, +0.2245, +0.2454, -0.0249, -0.6176, -0.2258,
+ +0.0930, -0.1846, +0.2402, -0.1385, +0.2153, -0.2008, -0.5581,
+ +0.1088, -0.5005, +0.3305, -0.3271, +0.2312, -0.1030, -0.2210,
+ -0.1379, +0.0190, +0.0899, +0.1926, -0.0067, +0.2582, +0.1681,
+ -0.4289, +0.1044, +0.2660, -0.7339, +0.0163, -0.1567, -0.0121,
+ +0.2644, -0.2077, +0.2582, -0.4713, +0.2558, +0.4078, +0.1073,
+ -0.2123, +0.0709, +0.1464, +0.3106, +0.1395, +0.3353, +0.0492,
+ -0.5039, -0.0581, -0.1024, -0.2474, +0.3306, -0.0213, -0.3695,
+ -0.3309, -0.2358
+ ],
+ [
+ -0.2505, +0.2642, -0.4537, -0.0715, +0.3695, -0.0352, +0.1565,
+ -0.1376, +0.0881, -0.2340, +0.2502, -0.0066, +0.2090, +0.3373,
+ +0.1071, -0.3952, -0.0842, -0.0159, -0.0483, +0.0554, -0.3171,
+ -0.1729, -0.0182, -0.0288, +0.1663, +0.1096, +0.1333, -0.1396,
+ +0.1167, -0.5935, -0.4258, -0.2818, -0.0363, +0.1614, +0.0594,
+ -0.0180, -0.0911, -0.3805, -0.3195, +0.2354, -0.7418, -0.3067,
+ +0.2896, +0.1554, +0.2314, -0.3847, -0.2630, -0.1717, -0.4242,
+ -0.1676, -0.2017, +0.0866, +0.1201, -0.4409, +0.5562, -0.2542,
+ +0.5081, +0.1408, +0.0570, +0.0872, -0.1119, +0.0402, +0.6168,
+ -0.0142, +0.2616, -0.4573, -0.0325, -0.2873, +0.1618, +0.2425,
+ +0.0082, -0.0065, +0.0754, -0.1841, -0.0383, +0.1628, +0.0744,
+ -0.2854, -0.4410, -0.0051, -0.1549, -0.1816, +0.0458, -0.1471,
+ +0.1906, -0.1438, -0.0535, +0.1475, -0.1722, -0.0339, -0.1129,
+ -0.1283, -0.1106, +0.1569, -0.4002, +0.2532, +0.2737, -0.3029,
+ -0.0787, -0.0859, +0.0837, +0.0402, -0.2344, +0.0842, +0.0386,
+ -0.0083, +0.3807, +0.0054, -0.5496, -0.1724, -0.2242, -0.0842,
+ -0.4564, +0.0385, -0.2174, +0.3352, -0.3090, -0.1349, -0.0586,
+ -0.1559, +0.1631, +0.2784, +0.0279, +0.4398, +0.4739, -0.0570,
+ +0.0061, -0.2062
+ ],
+ [
+ +0.1434, -0.0120, +0.3951, -0.0323, -0.2571, +0.0301, +0.0365,
+ -0.0118, -0.0874, +0.1590, -0.2019, -0.0344, +0.0095, -0.1811,
+ +0.2940, +0.3832, -0.0999, -0.3384, +0.0198, -0.0699, +0.3587,
+ -0.0567, -0.0724, -0.3066, +0.2375, -0.2321, -0.3101, +0.0757,
+ +0.3101, +0.1344, +0.3533, -0.5987, +0.3279, -0.1368, +0.1387,
+ +0.4028, -0.0494, +0.2006, +0.0743, -0.8107, -0.2589, +0.2490,
+ +0.1449, +0.0505, -0.5133, +0.1138, +0.0307, -0.3560, +0.3254,
+ +0.1286, -0.2014, +0.3468, +0.3491, -0.0319, -0.0878, +0.1543,
+ +0.2314, -0.2761, -0.1381, -0.0057, -0.5610, -0.1594, -0.0920,
+ +0.4453, -0.1576, -0.2773, +0.1801, -0.1316, +0.0393, -0.1425,
+ +0.4727, -0.1651, +0.1977, +0.0339, -0.6448, -0.3207, -0.4467,
+ +0.1506, +0.0784, +0.0261, -0.1625, +0.1947, +0.1033, -0.0283,
+ -0.3328, +0.2162, +0.7168, +0.0928, +0.2083, +0.2409, +0.0455,
+ -0.1177, +0.4082, +0.0083, +0.0361, +0.4231, +0.5370, -0.0506,
+ -0.1792, -0.3001, -0.0351, +0.1178, +0.0498, +0.4208, -0.4401,
+ +0.1326, -0.0392, +0.1412, +0.0806, +0.3868, +0.8497, +0.1497,
+ +0.0860, +0.0240, -0.0507, +0.3800, -0.0406, +0.0583, -0.6224,
+ -0.1246, -0.0229, -0.1372, -0.3068, +0.0459, -0.0281, +0.2181,
+ +0.1075, -0.4332
+ ],
+ [
+ -0.4636, -0.1112, +0.0763, +0.4141, +0.0402, -0.5420, +0.2227,
+ -0.6480, -0.3164, -0.4396, -0.4744, +0.0671, -0.2261, -0.0518,
+ +0.0014, +0.3857, +0.1624, +0.0687, +0.2872, -0.2497, -0.0027,
+ -0.3947, -0.1018, +0.2272, -0.2266, -0.0169, -0.1020, +0.3085,
+ -0.1820, +0.0355, +0.0255, -0.3090, +0.2653, -0.1058, -0.3634,
+ -0.0307, +0.0202, -0.2707, -0.0831, -0.0681, -0.0213, -0.1671,
+ +0.2558, +0.1859, -0.2014, -0.1705, +0.0005, -0.0036, +0.1420,
+ -0.2307, +0.1531, -0.0214, -0.3054, -0.1012, +0.2385, +0.1473,
+ +0.2885, -0.2721, -0.3078, -0.4205, -0.2689, +0.2199, -0.2707,
+ +0.1737, +0.1931, +0.1001, -0.1801, -0.2993, -0.2526, +0.3641,
+ +0.2463, -0.4613, -0.0852, -0.0683, -0.4316, +0.4021, +0.2350,
+ -0.2239, -0.4374, +0.3698, +0.1811, -0.0643, -0.1829, -0.0204,
+ +0.0173, +0.2112, +0.1542, -0.0099, +0.3586, -0.9393, +0.0668,
+ -0.0593, -0.0195, -0.2426, +0.1660, +0.0517, -0.0871, -0.0915,
+ -0.1157, +0.2283, -0.0123, -0.5005, -0.2247, -0.2321, +0.2065,
+ -0.2147, +0.0276, +0.4313, +0.3968, -0.0005, +0.3617, +0.4281,
+ -0.3239, -0.0066, +0.2102, -0.1717, +0.0734, +0.0493, -0.0372,
+ -0.0340, +0.4729, +0.0822, +0.0106, -0.1141, +0.0119, +0.1059,
+ +0.5751, +0.0668
+ ],
+ [
+ -0.1552, +0.1920, +0.1906, -0.4119, +0.1690, -0.0936, -0.0005,
+ -0.3644, +0.7333, +0.1379, +0.2201, -0.2639, +0.4613, -0.2908,
+ +0.2669, -1.1749, -0.3588, +0.2477, -0.5366, -0.0223, -0.1503,
+ +0.3160, +0.0281, +0.3906, -0.5610, +0.1908, -0.1706, -0.2998,
+ +0.0783, +0.1982, +0.0441, -0.2543, +0.2529, +0.1253, +0.0761,
+ +0.1273, -0.1639, +0.3318, +0.1196, -0.6859, -0.0741, -0.1769,
+ -0.0100, +0.4201, -0.3729, -0.0130, +0.2054, +0.1697, -0.1171,
+ -0.1656, -0.2938, -0.3180, +0.2930, +0.0248, -0.0721, +0.1678,
+ +0.4060, +0.0378, +0.1610, +0.3815, -0.0424, +0.0788, +0.0789,
+ -0.3713, -0.0217, +0.0841, -0.3375, +0.3190, +0.0918, +0.4838,
+ +0.2233, +0.3977, +0.2742, -0.4574, -0.0468, -0.1012, +0.1981,
+ -0.0430, +0.1140, +0.0615, +0.0295, -0.0799, -0.0695, -0.2327,
+ -0.6654, +0.2112, -0.1571, -0.4852, -0.3658, -0.3385, -0.0080,
+ +0.2630, -0.1378, -0.2598, -0.1100, +0.3519, +0.4706, -0.0383,
+ -0.0452, +0.1254, -0.3156, -0.2174, +0.0628, -0.3415, +0.3510,
+ -0.2029, -0.0020, +0.0680, -0.2272, -0.8619, -0.2280, +0.1946,
+ +0.3584, -0.1512, -0.3592, +0.2931, +0.0253, -0.3035, +0.1828,
+ -0.2700, -0.3571, -0.4811, -0.6953, -0.0204, -0.3862, -0.6288,
+ -0.0145, -0.0406
+ ],
+ [
+ +0.1678, -0.1390, +0.2876, -0.0368, -0.2344, -0.1094, +0.0984,
+ -0.1800, -0.2036, +0.0680, +0.1698, -0.1941, -0.5914, +0.4885,
+ +0.1021, -0.3722, +0.3561, -0.1853, +0.1896, -0.2605, -0.1587,
+ -0.0873, +0.0486, -0.3496, +0.2293, -0.1008, +0.1305, +0.3650,
+ -0.1152, -0.2546, -0.0588, -0.4204, -0.0234, +0.0420, -0.1034,
+ +0.1464, -0.2898, +0.0839, -0.3266, -0.1044, -0.5746, -0.0885,
+ +0.1007, +0.2220, -1.0912, -0.0480, +0.1591, -0.0165, +0.1192,
+ +0.1978, +0.0232, -0.1556, -0.5672, -0.1858, +0.1479, -0.2103,
+ -0.2111, -0.0703, -0.2522, +0.2085, -0.2553, +0.0499, -0.2740,
+ -0.1353, -0.2710, -0.0528, +0.4056, -0.2755, +0.1720, -0.0192,
+ +0.0148, -0.1274, -0.1029, -0.2500, +0.1273, +0.2180, +0.3116,
+ -0.0436, -0.0094, -0.2959, +0.0379, -0.0557, +0.0774, +0.0563,
+ +0.1035, -0.3976, -0.1366, +0.0774, -0.0490, -0.5567, -0.1338,
+ -0.3588, -0.2579, -0.5681, +0.2617, -0.0666, +0.0752, +0.1150,
+ -0.1603, +0.1110, +0.0370, -0.1144, -0.3738, -0.1971, -0.1416,
+ +0.0396, +0.4996, +0.1288, +0.0554, +0.0123, +0.0905, -0.4663,
+ +0.0454, -0.0723, +0.0772, -0.6927, +0.4248, -0.3354, +0.2230,
+ -0.1773, +0.1688, +0.3252, -0.1065, -0.1715, -0.3558, -0.0626,
+ +0.1096, +0.1991
+ ],
+ [
+ +0.5921, -0.0539, -0.2375, -0.1628, -0.1813, -0.2862, +0.0293,
+ -0.2155, -0.2371, +0.3062, -0.0559, -0.3696, -0.4438, +0.0744,
+ -0.0515, -0.1233, +0.3211, +0.0144, +0.0047, +0.1096, -0.1194,
+ +0.6654, +0.0189, -0.0285, +0.5427, +0.2019, -0.2679, -0.0657,
+ -0.2132, -0.3312, +0.3644, -0.1502, -0.3224, +0.4975, +0.1831,
+ -0.1414, +0.0861, +0.1378, -0.2480, -0.3489, +0.1228, -0.0426,
+ -0.1649, -0.1352, +0.5559, -0.2245, -0.1738, +0.2697, -0.0013,
+ +0.0406, +0.1814, +0.3375, -0.3825, -0.0905, -0.3900, +0.0475,
+ -0.0292, +0.1905, -0.6014, +0.2037, -0.2561, -0.0093, -0.1547,
+ -0.1622, -0.1100, -0.1235, -0.1932, -0.4019, -0.4531, +0.2393,
+ +0.2683, -0.0960, -0.1682, +0.2321, +0.2489, -0.2497, +0.3791,
+ -0.0741, +0.3354, -0.0953, +0.1158, -0.0730, +0.3047, +0.3713,
+ -0.2526, -0.5759, -0.0975, +0.1361, -0.3150, +0.0852, +0.0006,
+ -0.1836, +0.2002, +0.3521, +0.1334, -0.0675, +0.3020, +0.0340,
+ +0.2560, +0.2306, -0.2568, +0.1243, +0.3763, -0.2964, +0.1928,
+ +0.1165, -0.3346, -0.0858, -0.0298, -0.1786, -0.2049, -0.3626,
+ +0.2401, -0.1222, +0.3287, -0.5254, +0.0560, -0.3043, +0.2072,
+ -0.0904, -0.2016, -0.0695, +0.4787, -0.3004, +0.0996, +0.1439,
+ -0.3243, -0.1055
+ ],
+ [
+ +0.1111, -0.1740, +0.1508, -0.1986, +0.2262, -0.3348, -0.0585,
+ +0.0075, +0.0359, +0.0449, -0.4827, -0.0655, +0.1545, -0.0082,
+ -0.2903, -0.2934, +0.1367, -0.2222, -0.4653, -0.0171, +0.1057,
+ -0.1496, -0.0883, -0.3486, +0.1808, +0.2586, +0.0096, -0.0701,
+ +0.2976, +0.3417, -0.0200, +0.0370, -0.1724, -0.1279, +0.1512,
+ +0.0398, -0.0496, +0.3608, -0.0239, +0.2864, +0.1176, +0.1120,
+ +0.2264, -0.3415, +0.0121, -0.3474, -0.3206, +0.0721, -0.0702,
+ -0.3024, +0.0170, -0.0474, +0.2562, +0.4340, +0.0519, +0.1430,
+ +0.1811, -0.0179, -0.1797, +0.6682, -0.4247, +0.0873, -0.1702,
+ +0.0747, +0.0966, +0.1486, -0.0962, -0.6584, +0.2975, -0.0368,
+ +0.2390, +0.1650, -0.1969, +0.0966, -0.3846, -0.0257, -0.0487,
+ -0.0734, -0.0613, -0.0289, +0.1590, -0.0105, -0.1821, +0.0777,
+ -0.1220, -0.6621, +0.1552, -0.2265, +0.2804, +0.5431, +0.0168,
+ +0.3805, +0.2050, -0.1815, -0.2352, +0.0362, -0.1197, -0.1010,
+ +0.2668, -0.4902, +0.0595, +0.0568, +0.1720, +0.1513, -0.5935,
+ -0.2029, -0.6192, +0.0444, +0.2029, +0.3536, -0.5571, -0.3656,
+ -0.2919, -0.1727, -0.4999, -0.1579, +0.2853, +0.5241, -0.2430,
+ +0.3972, -0.4621, +0.2171, -0.0693, +0.2835, +0.1048, +0.3082,
+ +0.0935, +0.0725
+ ],
+ [
+ -0.1637, -0.0871, +0.1658, -0.2654, -0.0754, -0.1575, +0.2605,
+ -0.3529, +0.0581, -0.2371, +0.0493, +0.0024, +0.0636, +0.1201,
+ -0.0833, +0.1548, -0.0617, +0.1090, +0.1521, -0.1700, +0.1232,
+ +0.0961, -0.3606, -0.7468, -0.3476, -0.2093, -0.1083, +0.1433,
+ +0.2611, -0.3620, +0.1350, -0.1761, -0.0702, -0.2724, +0.1582,
+ -0.3202, -0.0834, -0.0354, -0.4836, -0.1879, -0.2959, -0.2197,
+ +0.1708, +0.3084, -0.4935, +0.0483, -0.0412, -0.3479, -0.1102,
+ -0.0092, -0.0574, +0.0554, -0.2258, +0.2767, +0.2602, -0.4930,
+ -0.2602, -0.4295, -0.0097, -0.1366, +0.0042, -0.1456, -0.2534,
+ -0.0490, -0.2300, -0.1938, +0.0845, -0.2032, +0.0032, -0.2577,
+ -0.1209, +0.0597, -0.0013, -0.2991, +0.3123, -0.2665, -0.3323,
+ +0.1128, -0.6301, +0.1209, +0.0201, -0.0950, -0.1123, +0.0299,
+ -0.4154, -0.0366, +0.0223, -0.0708, -0.7754, +0.1047, -0.4431,
+ +0.2150, -0.0731, +0.1860, -0.2326, +0.0030, -0.2935, -0.3126,
+ +0.2240, +0.4270, +0.2995, -0.0847, -0.1550, +0.0892, +0.1713,
+ -0.0596, -0.0584, +0.1644, +0.0519, -0.5139, -0.2303, -0.6931,
+ -0.2711, -0.0971, -0.3829, -0.3374, +0.0538, +0.2356, -0.3548,
+ +0.3561, +0.0897, -0.0909, -0.1119, -0.2261, -0.0979, -0.0202,
+ -0.8850, +0.2295
+ ],
+ [
+ -0.1634, -0.2828, -0.1941, -0.2810, +0.0986, +0.0981, -0.2612,
+ -0.2277, +0.0979, -0.0239, +0.2944, -0.1705, +0.2270, -0.0299,
+ +0.0262, +0.1895, -0.0745, -0.1899, +0.0421, -0.7681, +0.0562,
+ -0.4968, -0.3613, +0.0405, -0.1105, -0.3492, -0.1548, -0.2436,
+ +0.0937, +0.4257, -0.3796, +0.1241, -0.3825, +0.5613, +0.1613,
+ -0.4511, -0.2494, +0.3871, +0.3589, -0.0450, +0.2856, +0.1787,
+ -0.0970, -0.2310, -0.1176, -0.1352, -0.6234, -0.0065, +0.1151,
+ -0.0174, +0.0149, -0.0273, +0.1629, +0.1581, +0.3120, +0.5614,
+ +0.0688, +0.2278, +0.1334, +0.2673, -0.1221, -0.3665, +0.0668,
+ -0.4807, -0.0818, -0.1851, +0.3883, +0.1152, +0.4085, -0.1056,
+ +0.0702, -0.1919, -0.1840, -0.3105, +0.1887, +0.1173, -0.1200,
+ +0.3380, -0.0967, +0.3400, -0.0601, +0.1227, +0.0433, +0.3186,
+ +0.2203, +0.1091, -0.4412, -0.2574, +0.3692, +0.1454, -0.2175,
+ -0.0362, +0.2412, -0.0417, +0.4794, -0.2736, +0.2893, -0.2836,
+ -0.1868, -0.0621, +0.0612, +0.4949, +0.0728, -0.3448, +0.0081,
+ +0.1892, -0.4146, -0.2561, -0.0357, +0.1077, -0.0580, +0.1262,
+ -0.1692, -0.0372, -0.1210, -0.4731, +0.4645, -0.2352, -0.3995,
+ +0.2874, +0.0848, +0.2734, -0.1254, +0.4217, -0.2578, +0.2693,
+ -0.2673, +0.0498
+ ],
+ [
+ -0.0628, +0.0296, -0.2983, -0.3481, -0.1473, +0.1786, -0.5650,
+ +0.0384, +0.0395, -0.1228, -0.0090, +0.6397, +0.0374, -0.6429,
+ -0.3989, -0.1724, +0.4038, +0.1364, +0.2632, +0.0267, -0.1227,
+ +0.3067, +0.3173, +0.2586, +0.0388, +0.1178, -0.1741, -0.1198,
+ -0.3351, -0.2439, -0.5281, -0.3739, +0.0095, -0.1192, +0.1664,
+ -0.3714, -0.0687, -0.3244, -0.2592, -0.1771, +0.0574, -0.0862,
+ -0.1435, +0.1585, -0.2317, -0.4128, -0.5971, -0.2712, +0.1453,
+ -0.0166, -0.2195, +0.0543, +0.1135, +0.0443, -0.0980, -0.0873,
+ +0.1613, +0.3857, -0.2544, -0.5476, -0.1106, -0.4170, +0.1687,
+ -0.1565, +0.2169, -0.2409, +0.0623, +0.1636, -0.2886, +0.0399,
+ +0.2059, +0.2386, -0.3149, -0.1199, +0.0318, +0.3464, +0.1410,
+ -0.0834, -0.8710, +0.1241, +0.2162, -0.1006, -0.7545, -0.0171,
+ -0.3134, -0.2252, -0.2220, -0.0807, -0.0750, +0.1127, +0.3198,
+ -0.3802, -0.3772, -0.0536, +0.0959, -0.0257, -0.1361, -0.5826,
+ +0.2504, -0.1742, -0.2791, -0.4393, -0.4317, +0.0342, -0.1934,
+ -0.3139, -0.2882, +0.0038, -0.0628, -0.3115, +0.2009, +0.5177,
+ +0.2402, -0.1266, +0.2183, -0.1377, -0.1591, -0.0679, +0.3299,
+ -0.1463, -0.3163, +0.0590, +0.0126, +0.3101, +0.0180, +0.0617,
+ -0.0267, -0.0517
+ ],
+ [
+ -0.1878, +0.4202, -0.2018, -0.2199, -0.1093, +0.0883, +0.3946,
+ -0.1421, +0.0568, +0.1144, +0.1511, -0.2157, +0.1200, -0.1398,
+ +0.5402, -0.1717, +0.2102, -0.7088, +0.0888, -0.2136, +0.0865,
+ +0.0689, -0.3463, +0.1241, +0.0271, -0.1606, +0.1215, +0.2254,
+ +0.0182, -0.2754, -0.1091, +0.3262, +0.0484, +0.0632, +0.1665,
+ +0.0405, +0.2157, -0.6539, +0.0117, -0.0504, -0.0204, -0.2643,
+ +0.3264, +0.2175, +0.3935, -0.1287, -0.3278, -0.1537, +0.0975,
+ -0.0697, +0.4259, +0.1344, +0.3404, -0.3377, -0.1828, +0.1118,
+ -0.5460, +0.1486, -0.1924, -0.2064, -0.1048, +0.2057, -0.0103,
+ +0.1334, -0.0832, -0.2903, -0.1947, -0.1323, -0.3305, -0.1156,
+ +0.1135, +0.1272, +0.3634, -0.0064, -0.8530, -0.3437, -0.2028,
+ -0.1464, +0.0134, +0.1799, -0.1531, -0.0605, +0.1737, -0.3357,
+ -0.0260, +0.0243, +0.0821, -0.4290, -0.2971, +0.0604, -0.3610,
+ -0.9631, +0.0909, -0.1828, -0.0168, -0.2583, -0.0384, +0.0965,
+ -0.1840, -0.0546, -0.6720, -0.5470, +0.0744, -0.2020, -0.2608,
+ -0.0065, +0.1288, -0.1573, +0.1691, -0.2865, -0.2280, +0.1725,
+ +0.5208, -0.2204, -0.2221, -0.1635, -0.2530, -0.1879, -0.1018,
+ -0.3523, +0.5690, +0.0229, +0.5258, +0.0883, +0.1659, +0.1884,
+ +0.1938, -0.3107
+ ],
+ [
+ -0.1181, +0.0420, +0.1144, +0.1611, -0.1838, +0.2476, -0.0909,
+ -0.1870, +0.1146, +0.1150, +0.0946, -0.0853, +0.2211, +0.0397,
+ -0.2939, -0.2748, -0.0733, -0.4318, +0.0864, +0.2981, -0.2610,
+ +0.0152, +0.4888, +0.0618, -0.1510, -0.1448, -0.4673, +0.2183,
+ -0.1130, -0.0786, -0.3847, +0.1379, +0.1242, +0.0200, -0.0700,
+ +0.1541, -0.2642, +0.1701, +0.0021, +0.3278, -0.1615, +0.2148,
+ -0.0260, -0.0893, -0.4782, +0.0654, +0.6166, +0.0800, +0.1462,
+ -0.2415, +0.0865, -0.7428, -0.6088, +0.5626, -0.0687, -0.4575,
+ +0.3253, -0.0043, +0.2689, -0.3320, -0.0873, +0.2519, -0.2260,
+ -0.0534, -0.4402, -0.0939, -0.5351, -0.0932, +0.1957, +0.0074,
+ -0.1433, +0.0204, -0.4745, +0.0286, -0.0910, +0.4747, -0.6399,
+ -0.0882, +0.0181, +0.2373, -0.0368, -0.0419, +0.4141, +0.0785,
+ -0.2220, +0.3220, +0.0220, +0.1948, +0.0091, +0.3534, +0.4111,
+ +0.2544, +0.2341, -0.1570, -0.1050, +0.0645, -0.2550, -0.0280,
+ -0.1230, +0.3032, +0.1779, +0.1246, -0.1200, -0.1179, -0.2386,
+ -0.7218, +0.1017, +0.0982, -0.1698, +0.2219, -0.1897, -0.3570,
+ +0.0490, -0.0444, +0.0950, -0.2295, +0.0222, +0.1401, +0.0871,
+ -0.3157, +0.0077, -0.2118, +0.1846, +0.2797, -0.2519, +0.5200,
+ -0.1003, -0.3801
+ ],
+ [
+ -0.0374, +0.0125, -0.1276, -0.0663, -0.0598, +0.0254, -0.1572,
+ +0.0380, +0.1068, -0.6109, +0.3036, -0.1031, +0.2926, +0.7185,
+ +0.1928, +0.1294, -0.1074, +0.0822, -0.2497, -0.0638, -0.2045,
+ -0.0279, -0.4689, +0.1881, -0.2892, -0.1539, -0.1233, +0.4763,
+ -0.0517, -0.4180, -0.2516, -0.1770, -0.0086, -0.2397, +0.1959,
+ -0.3844, -0.0017, -0.0121, -0.0297, +0.1524, +0.0519, -0.1683,
+ -0.0179, -0.1571, -0.2795, -0.1275, -0.0718, -0.3185, +0.1964,
+ +0.4256, +0.2213, -0.0376, -0.0930, -0.2075, -0.1796, +0.2767,
+ +0.1493, +0.1180, -0.0987, -0.0247, +0.2443, -0.5713, +0.1010,
+ -0.3878, +0.2381, -0.5685, -0.0383, -0.5102, -0.2925, -0.5523,
+ -0.0822, +0.1612, +0.3682, +0.3328, -0.4877, +0.0733, -0.1662,
+ +0.5293, -0.0499, -0.1371, +0.0455, +0.2431, -0.0888, +0.3100,
+ +0.1143, -0.5558, -0.1580, -0.0643, +0.4244, +0.4820, +0.1560,
+ -0.4581, +0.0270, +0.0924, +0.3386, +0.0239, -0.0115, -0.5032,
+ -0.0458, +0.4652, +0.1183, +0.1134, -0.0802, -0.2699, -0.5722,
+ +0.2359, +0.2058, -0.0863, -0.3910, -0.0556, +0.1493, -0.0604,
+ +0.1420, -0.2824, +0.2240, +0.0645, -0.0183, -0.0387, +0.5395,
+ -0.0833, +0.1167, -0.0518, -0.0461, +0.0443, +0.0494, +0.1201,
+ +0.0229, -0.1096
+ ],
+ [
+ +0.4898, +0.4718, -0.0682, -0.0311, +0.1615, -0.1496, -0.1432,
+ +0.1643, -0.2215, +0.1757, +0.4375, +0.4404, -0.0622, -0.5233,
+ -0.1271, +0.2250, -0.2745, +0.2733, +0.1107, -0.3827, +0.1241,
+ +0.3758, +0.2248, -0.2225, +0.1124, -0.1181, -0.0423, -0.5795,
+ -0.4674, +0.3522, +0.0859, -0.0276, -0.2329, +0.3446, -0.1834,
+ -0.0068, -0.1553, -0.1485, +0.0824, -0.2299, +0.2591, -0.3897,
+ +0.0787, +0.3867, -0.2286, +0.1480, -0.2998, -0.3949, -0.2774,
+ +0.1865, -0.4783, +0.6124, -0.3644, -0.3829, -0.0067, -0.0521,
+ -0.2011, +0.0770, +0.0012, +0.0381, +0.0878, -0.0414, -0.2545,
+ -0.5219, -0.0408, +0.3443, +0.0090, -0.0228, +0.0870, +0.3942,
+ -0.0491, +0.1444, +0.0063, -0.0771, -0.0745, -0.2912, +0.0112,
+ +0.2357, +0.3547, +0.0734, -0.0780, -0.0617, +0.3603, -0.6174,
+ -0.2102, -0.0907, -0.1515, -0.1293, -0.4516, +0.2042, +0.1366,
+ +0.4122, -0.0986, +0.3063, -0.8169, -0.4886, -0.0303, +0.2678,
+ -0.2087, +0.1952, -0.1536, +0.0337, +0.5130, -0.3060, +0.0524,
+ +0.0624, -0.0559, +0.0889, +0.2813, +0.1058, +0.1298, -0.3953,
+ -0.0201, -0.1515, +0.3005, +0.5508, +0.0059, +0.0024, -0.0398,
+ -0.0980, -0.0488, -0.4250, +0.3168, -0.1026, -0.1809, -0.3030,
+ -0.1698, -0.0848
+ ],
+ [
+ +0.3695, +0.3071, +0.2333, +0.0139, -0.3983, -0.0711, -0.2194,
+ -0.6272, -0.2138, +0.0617, -0.0111, -0.6236, +0.2183, +0.0222,
+ +0.0592, +0.4917, -0.2183, +0.0121, -0.1354, -0.0017, +0.2402,
+ +0.1886, -0.2910, -0.7567, -0.1246, -0.2037, -0.5099, -0.1605,
+ -0.2461, +0.0206, +0.4707, -0.5077, +0.1170, +0.2024, -0.2554,
+ +0.0730, +0.0879, +0.0928, -0.4353, -0.0598, +0.2081, +0.0372,
+ -0.1332, -0.3373, +0.2284, -0.0599, +0.4024, +0.0604, +0.1383,
+ -0.0774, -0.1523, +0.6480, +0.0155, +0.1066, -0.1377, -0.3421,
+ +0.1621, -0.2353, -0.1816, -0.4314, +0.0973, +0.4458, +0.1650,
+ -0.0560, +0.0744, +0.2842, +0.0021, +0.0804, -0.0905, -0.0140,
+ -0.2298, -0.1811, -0.2960, -0.1459, +0.0368, +0.1198, +0.2527,
+ +0.0157, +0.1724, -0.0734, -0.0688, +0.0016, +0.0925, -0.4295,
+ -0.1006, -0.0191, +0.0594, +0.0157, -0.3886, -0.2070, -0.1863,
+ +0.4119, +0.2145, +0.1962, +0.3108, -0.0909, -0.0882, -0.1576,
+ +0.0135, -0.1729, +0.0140, +0.0432, +0.1751, -0.1687, -0.1999,
+ -0.1014, -0.5196, -0.2550, -0.0893, -0.1267, +0.0980, +0.5148,
+ +0.0603, -0.1135, +0.1299, +0.1265, +0.2391, -0.0833, -0.3704,
+ +0.3892, +0.0321, +0.1687, -0.1774, +0.1666, +0.0407, -0.0665,
+ +0.4508, -0.0340
+ ],
+ [
+ +0.1389, -0.2080, +0.3438, +0.4899, -0.2797, -0.1417, +0.2512,
+ +0.1198, -0.2197, +0.2436, +0.4070, +0.3478, -0.1127, +0.3079,
+ -0.0048, -0.1004, -0.1047, +0.3478, +0.1476, +0.1566, -0.0925,
+ +0.3851, -0.1324, -0.2224, -0.1426, -0.2631, -0.1746, -0.3112,
+ +0.2770, +0.0137, -0.4146, -0.1265, +0.1451, -0.1700, -0.0411,
+ +0.2917, -0.1317, -0.4289, -0.0707, +0.0520, -0.2571, +0.0517,
+ -0.2700, -0.2443, -0.2731, -0.1958, +0.1699, +0.0438, -0.2558,
+ -0.1989, +0.1992, +0.2155, -0.3511, -0.0328, +0.1605, -0.3222,
+ -0.1463, -0.3556, +0.0530, +0.3442, -0.1352, +0.1355, +0.2699,
+ +0.3785, +0.0217, -0.3072, +0.1845, -0.3802, +0.3923, +0.2325,
+ -0.1082, -0.3326, -0.1154, -0.1105, +0.0031, -0.1160, +0.1205,
+ +0.2553, -0.1605, -0.4819, -0.2491, -0.0375, +0.0202, +0.1819,
+ -0.2861, -0.0136, -0.2221, -0.2957, -0.1213, +0.1185, +0.1611,
+ -0.2615, -0.3213, +0.5138, +0.2730, +0.2119, +0.1809, -0.0294,
+ -0.1709, +0.0105, -0.1378, -0.1316, +0.0682, +0.2159, +0.4921,
+ -0.0666, +0.0769, +0.1773, -0.2154, -0.2371, -0.0556, -0.3074,
+ +0.1083, -0.3648, +0.1665, -0.4355, -0.3632, -0.2370, -0.2437,
+ -0.0211, +0.2440, -0.1843, -0.1545, -0.2505, +0.1790, -0.1286,
+ -0.1876, +0.0066
+ ],
+ [
+ +0.1689, +0.2206, -0.0781, -0.1455, +0.0397, +0.0219, -0.2993,
+ +0.0903, -0.2283, +0.1591, +0.2444, -0.2100, -0.1380, -0.1889,
+ +0.2269, -0.4279, -0.0857, +0.2944, +0.2988, +0.3288, +0.3567,
+ -0.0988, -0.1966, -0.1906, +0.0061, -0.1165, +0.1244, +0.0469,
+ +0.1843, -0.5449, +0.3939, -0.5508, -0.0447, -0.3135, -0.0453,
+ -0.0627, +0.1362, -0.1780, +0.1294, -0.3741, -0.2563, +0.0990,
+ -0.0449, +0.3342, +0.2931, +0.1074, -0.1005, -0.1918, -0.2936,
+ +0.1220, +0.0024, +0.0063, +0.1774, +0.2586, -0.0011, +0.0033,
+ -0.4226, -0.3821, +0.1809, -0.0285, +0.0375, -0.1220, +0.0390,
+ +0.0580, +0.0155, +0.0621, -0.2021, +0.1297, -0.2579, -0.1164,
+ +0.3854, +0.3059, -0.6227, +0.4577, -0.2496, +0.2659, +0.1491,
+ -0.0004, +0.3749, -0.2097, -0.0885, +0.3152, -0.1971, -0.0840,
+ -0.1774, -0.5290, -0.1122, +0.0411, -0.1771, -0.2706, +0.2021,
+ +0.2337, -0.2176, +0.0079, -0.0904, +0.1092, +0.1135, +0.1338,
+ -0.1462, +0.0274, +0.3584, -0.1800, +0.4639, -0.1490, -0.3155,
+ -0.0412, +0.1629, -0.4656, -0.0496, +0.0748, -0.0045, +0.1361,
+ +0.1575, +0.1444, +0.0315, +0.1265, +0.0749, +0.0722, +0.2141,
+ -0.3132, -0.2626, +0.1807, +0.3173, -0.0458, -0.0529, -0.4732,
+ -0.0423, +0.2795
+ ],
+ [
+ +0.1614, -0.3846, +0.3338, -0.0183, +0.0286, +0.0085, -0.0646,
+ -0.0875, +0.0821, +0.1362, -0.4212, -0.1688, +0.1994, -0.0489,
+ -0.1341, -0.0673, -0.0943, +0.3059, -0.1284, -0.2643, +0.1213,
+ +0.0141, -0.3665, +0.1340, -0.0951, -0.1020, +0.1972, -0.2862,
+ +0.4121, -0.3036, +0.2082, +0.2528, -0.1514, +0.4938, -0.2471,
+ -0.4203, -0.0928, +0.3780, +0.0119, -0.0783, -0.1615, +0.1439,
+ +0.3527, -0.1908, +0.2838, +0.0668, -0.0234, -0.3280, -0.1800,
+ -0.0103, -0.6500, -0.2414, +0.1170, -0.0475, -0.4425, +0.3974,
+ -0.1808, -0.2993, -0.0731, +0.2598, -0.0778, +0.0570, +0.4062,
+ +0.3539, +0.0569, +0.0185, +0.0098, +0.0246, +0.2126, -0.1912,
+ +0.0584, -0.1487, +0.2746, +0.0755, +0.2073, +0.2170, -0.2629,
+ +0.0391, +0.1679, +0.0640, -0.5268, +0.1509, -0.1113, -0.0692,
+ -0.5873, +0.0353, +0.0339, +0.1475, +0.1000, -0.0805, -0.5734,
+ -0.1932, -0.0914, +0.1323, -0.2580, +0.3211, -0.0493, -0.7405,
+ -0.1821, -0.0603, -0.3156, +0.4612, -0.2098, +0.2076, -0.0475,
+ -0.0307, +0.4645, +0.0965, -0.2655, +0.0462, -0.1490, +0.4663,
+ +0.1683, -0.1155, -0.1533, +0.3838, +0.0265, -0.0092, -0.2440,
+ +0.1372, -0.1355, -0.1840, -0.8211, +0.0373, -0.3227, -0.2345,
+ +0.3017, -0.5007
+ ],
+ [
+ -0.7194, +0.1233, -0.0451, +0.4639, +0.2358, -0.1510, +0.1254,
+ +0.2313, -0.1787, +0.1401, +0.2545, -0.3689, -0.2419, -0.0821,
+ -0.0639, +0.2946, -0.5942, +0.2970, +0.5321, +0.4658, -0.0104,
+ -0.1767, -0.3440, +0.0767, +0.1729, -0.5545, +0.5259, +0.2951,
+ -1.0173, +0.1334, +0.1770, -0.3246, +0.0155, -0.1276, +0.0960,
+ -0.0504, +0.0450, +0.1771, -0.1464, -0.0822, +0.2322, +0.1848,
+ -0.1134, -0.2567, -0.4594, -0.0382, -0.6554, -0.1064, -0.2206,
+ -0.0739, +0.3366, +0.1127, -0.0090, +0.3358, -0.0705, -0.0750,
+ -0.6799, +0.2498, +0.1230, +0.1456, +0.1680, +0.1652, +0.1617,
+ -0.0904, +0.5898, -0.0638, +0.1600, +0.0301, +0.4253, +0.2886,
+ +0.0156, +0.2199, -0.2753, -0.1821, -0.2855, +0.0326, -0.0055,
+ +0.0443, +0.5850, +0.3302, -0.1953, -0.2251, -0.4092, +0.1372,
+ -0.3366, +0.0798, +0.0072, +0.3039, +0.1618, -0.4104, -0.3004,
+ -0.1219, -0.3149, -0.0726, -0.2950, -0.0165, -0.9270, -0.2799,
+ -0.1752, -0.0162, -0.0462, +0.0538, -0.1469, +0.1161, +0.0670,
+ -0.0248, +0.0987, -0.1501, -0.2436, +0.0872, +0.4334, -0.5042,
+ +0.0042, -0.2367, +0.6838, +0.3448, +0.0355, +0.0805, +0.1266,
+ +0.0622, +0.3305, -0.0711, -0.0195, -0.0055, -0.0946, -0.0947,
+ -0.0616, +0.3404
+ ],
+ [
+ +0.3272, -0.2307, -0.4980, -0.3687, +0.2682, -0.0280, -0.1263,
+ +0.2620, -0.1047, -0.2322, -0.4030, +0.0904, +0.2516, -0.6150,
+ -0.0529, +0.0397, +0.1731, +0.1377, +0.1052, +0.2936, -0.2730,
+ +0.0615, -0.1997, +0.1070, +0.2508, +0.1554, +0.2048, +0.5632,
+ +0.0154, +0.2170, -0.3470, -0.5387, -0.1137, +0.0830, +0.0412,
+ -0.3426, +0.1562, -0.1541, -0.3798, +0.2924, -0.4815, +0.0288,
+ +0.0003, +0.0698, -0.1956, -0.6329, +0.0033, -0.1108, +0.1074,
+ -0.1663, +0.0352, -0.2713, +0.0867, -0.3850, +0.2340, -0.1578,
+ +0.1721, -0.7906, -0.3210, +0.0378, -0.2736, -0.2421, -0.2189,
+ -0.2970, -0.0288, -0.2068, +0.2631, -0.1496, +0.3061, +0.1604,
+ +0.4461, +0.1724, -0.2270, -0.2402, -0.1807, -0.0693, +0.1151,
+ -0.0305, -0.0112, +0.0159, -0.0346, +0.0245, +0.1452, +0.1488,
+ -0.0366, -0.0898, -0.0973, -0.4954, +0.3385, -0.1914, -0.2531,
+ -0.0537, +0.0391, -0.3276, -0.0391, -0.4617, +0.1141, +0.1026,
+ -0.0772, -0.4487, -0.2116, -0.1719, -0.6509, -0.3549, -0.0131,
+ -0.3162, -0.1257, +0.1993, +0.3512, +0.1550, -0.0918, +0.0812,
+ +0.0252, -0.0723, -0.2245, -0.0305, +0.0530, -0.0849, +0.1550,
+ -0.3906, -0.0536, +0.0028, -0.0251, +0.0676, +0.3088, -0.2304,
+ -0.3914, -0.1776
+ ],
+ [
+ +0.0754, -0.0331, -0.1040, +0.0217, +0.0386, +0.0777, +0.0818,
+ -0.2514, -0.4614, +0.2256, -0.0788, -0.1833, +0.3704, +0.2216,
+ -0.3747, -0.1590, -0.6929, +0.0802, -0.1232, +0.4860, +0.2148,
+ -0.0651, +0.3254, -0.2056, +0.1625, +0.2458, -0.4113, -0.4391,
+ -0.3837, +0.2540, +0.0527, -0.2951, +0.1566, +0.0967, +0.1662,
+ +0.6384, +0.0095, -0.3455, +0.1615, -0.2592, -0.0434, -0.0727,
+ -0.0382, -0.4776, -0.4566, -0.3037, -0.1459, -0.4048, +0.2599,
+ -0.0861, -0.0116, -0.1129, -0.0676, -0.0800, -0.1187, -0.3390,
+ +0.1063, +0.2348, -0.1164, +0.1153, -0.1498, +0.0402, -0.4802,
+ -0.1661, -0.1160, +0.1173, -0.0176, +0.2695, +0.0772, +0.0372,
+ +0.0242, +0.0225, +0.1049, -0.7242, +0.0126, -0.0755, +0.1022,
+ -0.2108, -0.1998, +0.2239, +0.0868, +0.1431, -0.0998, -0.0364,
+ -0.0655, -0.3919, -0.1501, +0.0311, -0.2907, -0.4067, +0.0829,
+ +0.0872, +0.0864, -0.1518, -0.3844, -0.3313, -0.0999, +0.1984,
+ +0.0486, +0.0816, -0.4610, -0.3460, -0.1629, +0.0140, -0.0830,
+ -0.2701, +0.4440, -0.3354, +0.0757, -0.1434, +0.0249, -0.3367,
+ -0.0574, +0.2688, -0.2757, -0.0715, -0.4653, -0.0473, -0.1148,
+ +0.1354, -0.0367, -0.4103, +0.2259, -0.6937, -0.2013, -0.0564,
+ +0.2864, -0.2999
+ ],
+ [
+ -0.1390, +0.3005, -0.0987, -0.4789, +0.0332, +0.1438, +0.1070,
+ +0.1519, -0.6019, +0.4098, +0.4004, -0.1516, -0.1093, -0.2201,
+ +0.2699, +0.1977, +0.4157, -0.1772, -0.0797, +0.0854, -0.7648,
+ -0.4394, -0.0438, -0.4718, +0.3928, -0.5257, -0.0439, +0.1315,
+ -0.1150, -0.1163, +0.1980, +0.3534, +0.1772, -0.7586, +0.1434,
+ +0.2689, -0.2058, +0.0350, -0.1247, -0.3290, +0.3909, +0.0623,
+ -0.0877, -0.2343, -0.2182, +0.6083, -0.9525, +0.1864, -0.3507,
+ +0.1482, -0.0038, -0.7236, -0.0294, -0.1077, +0.0192, +0.0980,
+ -0.2851, -0.0462, +0.0435, +0.1113, -0.1022, +0.3637, +0.2610,
+ +0.1618, +0.0215, -0.0779, -0.0163, +0.0879, -0.4159, -0.4511,
+ -0.1508, +0.2072, -0.0557, -0.2555, -0.4352, -0.0096, +0.1234,
+ -0.3254, -0.2381, +0.3456, -0.2058, +0.3037, -0.0526, -0.0977,
+ -0.2569, +0.5950, +0.4026, +0.3997, -0.0944, -0.3276, -0.1265,
+ +0.1403, -0.0443, +0.2053, +0.0302, +0.0350, +0.3422, -0.0679,
+ -0.2907, +0.0528, -0.1514, +0.2496, +0.1636, +0.1756, -0.1530,
+ +0.1945, +0.3399, -0.3761, -0.5962, -0.1480, +0.0239, -0.3460,
+ +0.3300, -0.3923, +0.0366, +0.2525, +0.3290, -0.0804, -0.0721,
+ -0.0075, +0.1203, -0.1507, -0.0603, -0.0650, +0.2470, +0.0277,
+ +0.1761, +0.1118
+ ],
+ [
+ -0.1023, +0.1811, +0.1096, +0.0398, -0.0287, -0.0113, +0.1133,
+ -0.1833, +0.1573, -0.2773, +0.2050, -0.1728, -0.2022, -0.1899,
+ -0.2964, -0.0777, -0.4232, -0.2348, +0.0104, -0.3079, +0.0108,
+ -0.0532, -0.6523, -0.1098, +0.1428, +0.0241, -0.1377, -0.1040,
+ -0.0198, -0.1276, -0.1225, +0.1877, +0.1434, -0.1603, +0.0083,
+ +0.3261, -0.0649, +0.2380, +0.1431, +0.1992, +0.2852, +0.0863,
+ +0.1383, +0.0683, -0.0237, -0.1648, -0.3055, +0.0780, -0.2690,
+ -0.1308, +0.0550, -0.2885, -0.0357, +0.3337, +0.3640, +0.2330,
+ -0.4088, -0.0555, +0.2426, -0.0360, -0.0471, +0.0268, +0.0698,
+ -0.3097, +0.4724, +0.0377, +0.1186, -0.3599, -0.1465, -0.0735,
+ +0.1470, +0.1003, +0.0560, +0.2386, -0.7249, +0.3320, -0.1094,
+ -0.1790, -0.3375, -0.1804, +0.3751, +0.1747, -0.1219, -0.4064,
+ +0.2044, -0.1771, -0.2139, +0.2752, -0.2412, +0.3879, -0.0443,
+ -0.4725, +0.0672, +0.1978, +0.0040, +0.0679, -0.1308, -0.1091,
+ -0.3235, -0.0660, -1.2227, -0.2144, +0.0729, +0.2776, +0.0983,
+ +0.3612, +0.1038, -0.1449, -0.2453, -0.0479, +0.2660, +0.0042,
+ +0.0880, +0.1908, -0.1619, +0.2752, -0.0579, +0.0556, -0.1338,
+ +0.1464, -0.0785, +0.2846, +0.4422, +0.2484, -0.6025, -0.2763,
+ +0.1162, -0.3478
+ ],
+ [
+ -0.5782, +0.1906, +0.1734, +0.1883, -0.0293, -0.0389, +0.0819,
+ +0.0158, +0.1459, -0.0329, +0.1881, +0.3707, +0.0956, -0.2496,
+ -0.1015, +0.3248, +0.1064, -0.2893, +0.3955, +0.1916, +0.2692,
+ +0.0676, +0.0055, -0.6039, -0.1335, -0.2131, +0.1014, -0.0254,
+ -0.0912, -0.2667, +0.0564, -0.2423, +0.0568, +0.2143, -0.1274,
+ +0.0890, -0.1465, +0.3149, -0.1007, +0.5162, +0.3685, +0.0812,
+ -0.1759, -0.2218, +0.4711, -0.1292, -0.0327, -0.0697, +0.0674,
+ -0.0355, -1.6970, -0.5040, +0.3186, +0.0522, +0.2239, +0.0747,
+ +0.4768, -0.4289, -0.1898, +0.0650, +0.3639, +0.1651, +0.2521,
+ -0.1041, -0.1097, -0.1902, -0.3308, -0.0783, +0.0330, +0.0435,
+ -0.2222, -0.3439, +0.1648, +0.3389, -0.1015, +0.0497, -0.0452,
+ +0.0318, +0.0559, -0.3934, +0.1315, +0.2891, -0.0126, -0.0007,
+ +0.0235, -0.0232, -0.0145, -0.1985, -0.2792, -0.1734, -0.3868,
+ +0.4253, -0.1242, -0.1719, -0.1692, -0.5732, +0.1520, +0.7987,
+ +0.1763, -0.3345, -0.2268, -0.0233, -0.2024, -0.0249, +0.1214,
+ -0.0592, -0.2435, +0.2254, -0.3216, +0.2705, -0.0196, +0.0999,
+ +0.3110, -0.1762, -0.2190, -0.4913, -0.0483, +0.4600, -0.5647,
+ +0.0644, -0.0517, -0.6167, -0.1300, -0.1070, -0.1628, -0.0141,
+ -0.1285, +0.3464
+ ],
+ [
+ +0.2531, -0.4246, -0.1124, -0.1414, +0.3469, +0.0590, +0.0769,
+ +0.1326, -0.0672, -0.5040, +0.4048, -0.1567, +0.0505, -0.3964,
+ +0.1137, +0.0952, +0.3906, +0.1974, -0.5820, -0.4967, +0.0089,
+ -0.9033, +0.2035, +0.3123, -0.0154, -0.0289, -0.2539, -0.3530,
+ +0.0047, +0.1289, -0.0604, +0.1756, -0.1851, -0.3747, -0.2330,
+ +0.0155, -0.2719, +0.3565, -0.8995, -0.3202, -0.0988, -0.4006,
+ -0.0811, -0.0058, +0.3941, -0.2473, -0.0218, -0.0270, -0.3174,
+ -0.3637, -0.5382, +0.0212, -0.3645, -0.0166, +0.3558, -0.3776,
+ -0.2406, -0.1041, -0.2648, +0.0408, +0.0477, -0.3856, +0.3001,
+ -0.2375, +0.0915, -0.0683, +0.0510, +0.1140, +0.3605, +0.0479,
+ -0.0216, +0.0533, +0.1311, +0.0990, -0.2098, +0.4808, -0.0483,
+ -0.6076, -0.0011, -0.3198, -0.3740, +0.3489, -0.1652, -0.1550,
+ -0.0346, -0.1286, -0.0016, -0.0003, -0.4651, -0.1696, -0.5290,
+ +0.1247, -0.0264, -0.4317, -0.2631, -0.3566, -0.0829, +0.4125,
+ +0.3511, +0.3472, +0.3246, -0.2954, +0.0431, +0.0219, +0.1410,
+ +0.1440, +0.2573, -0.1697, -0.0990, -0.1925, -0.3016, -0.5556,
+ -0.0015, -0.1362, +0.0310, -0.6040, -0.1562, -0.2446, -0.2332,
+ +0.1920, +0.1550, +0.1036, -0.4364, -0.1748, -0.1564, -0.2098,
+ -0.4382, +0.3966
+ ],
+ [
+ +0.1260, +0.0490, +0.3787, -0.0375, -0.2074, +0.1874, +0.0317,
+ -0.0706, -0.0983, +0.3232, -0.1024, +0.0829, +0.2997, -0.6455,
+ +0.1067, -0.0603, -0.5746, -0.0119, +0.1894, +0.1563, -0.1189,
+ -0.0454, +0.5147, +0.0360, -0.1992, -0.0254, +0.3549, +0.1757,
+ -0.4647, -0.0077, -0.2720, -0.1760, -0.2262, -0.4833, -0.2636,
+ +0.3875, +0.0347, +0.0979, +0.0910, -0.1617, +0.2177, -0.2526,
+ -0.2857, +0.2492, -0.4129, +0.5601, -0.5158, +0.6762, -0.0035,
+ -0.2667, -0.1909, -0.4599, +0.4615, -0.4111, +0.1033, +0.0490,
+ -0.1589, +0.0755, -0.1904, +0.1806, +0.0493, -0.1964, -0.1795,
+ +0.1061, +0.1791, +0.4933, -0.1962, -0.1606, -0.5060, +0.0979,
+ +0.1747, +0.2053, +0.0114, -0.1039, +0.2534, -0.0638, -0.3248,
+ +0.2861, -0.2703, +0.0699, -0.6233, -0.2882, +0.4067, -0.3037,
+ -0.4889, -0.2084, +0.0349, -0.0843, +0.0359, -0.1602, -0.2522,
+ -0.0374, +0.2539, -0.0456, +0.0193, -0.1338, +0.0877, +0.0100,
+ -0.2885, -0.5033, -0.1374, +0.2941, -0.1094, -0.3068, +0.3346,
+ -0.1147, -0.2984, +0.2426, -0.0239, -0.0587, -0.3346, -0.1018,
+ +0.1709, -0.2609, +0.0585, -0.3472, -0.1020, -0.2216, +0.2505,
+ +0.0018, -0.2663, +0.3529, +0.2675, +0.1840, -0.7017, -0.0175,
+ +0.2269, -0.2479
+ ],
+ [
+ +0.3040, +0.2737, -0.5742, -0.0408, +0.0635, -0.0384, -0.3790,
+ -0.2584, -0.4556, +0.0124, -0.1558, -0.2336, -0.1191, -0.2965,
+ -0.0478, -0.2460, -0.1696, -0.2144, -0.1847, -0.0240, -0.2321,
+ +0.1156, +0.0593, -0.5346, -0.2271, +0.1473, +0.1119, -0.2017,
+ +0.0852, -0.6201, +0.2337, +0.1348, +0.2248, -0.4217, +0.1638,
+ -0.1542, +0.2474, +0.1655, -0.2747, -0.3630, -0.1479, +0.1020,
+ +0.0481, +0.0818, -0.0606, -0.5730, -0.0580, +0.2307, +0.0102,
+ +0.3657, -0.0025, +0.1403, +0.5203, -0.3502, -0.0716, -0.0956,
+ +0.2056, +0.3511, -0.0761, -0.3415, -0.4086, -0.1799, +0.1528,
+ -0.2285, +0.4164, -0.4004, +0.4581, +0.0228, +0.3447, -0.0499,
+ +0.1209, +0.3148, +0.1120, +0.0279, -0.0009, -0.0518, -0.2637,
+ +0.0562, -0.0797, -0.3466, -0.1235, +0.2356, -0.4437, -0.2633,
+ -0.5231, +0.3174, +0.5079, -0.0572, -0.2430, +0.2296, +0.0292,
+ +0.0220, +0.1550, -0.0500, -0.1876, -0.0993, -0.4246, +0.0450,
+ -0.2272, +0.0427, -0.3256, +0.4864, +0.3597, +0.4831, +0.0694,
+ +0.0089, +0.2025, -0.3835, +0.3883, +0.1819, -0.5876, +0.2974,
+ -0.3375, -0.3222, +0.0057, -0.2190, -0.0620, +0.0231, -0.1838,
+ -0.0152, +0.2449, -0.1569, -0.1453, -0.2986, -0.1157, -0.0309,
+ +0.1738, -0.1929
+ ],
+ [
+ +0.1540, +0.0907, +0.0518, -0.3168, +0.2437, -0.1048, +0.1006,
+ -0.0696, -0.2625, -0.2643, -0.2835, -0.3560, +0.3865, +0.1339,
+ -0.0532, -0.4447, -0.0998, -0.1350, -0.0618, -0.0229, +0.1311,
+ -0.4932, +0.0372, -0.4844, -0.4117, +0.3505, +0.1197, +0.0140,
+ +0.2804, -0.2457, +0.3772, -0.3713, +0.0690, -0.3633, +0.2494,
+ +0.2031, +0.1649, -0.4295, +0.4660, -0.2606, -0.5435, -0.2758,
+ -0.1259, -0.2487, +0.0974, +0.0217, -0.0250, +0.2417, +0.0858,
+ +0.1764, +0.0492, +0.0453, +0.1658, -0.2055, +0.3024, +0.3197,
+ -0.6662, +0.0136, -0.1004, -0.0527, -0.0925, +0.0632, -0.4504,
+ -0.8565, +0.0316, -0.3916, +0.1335, -0.0838, -0.0710, -0.0795,
+ -0.5285, +0.4056, +0.2705, +0.2677, +0.1918, -0.1448, -0.4974,
+ -0.4795, -0.5206, -0.2320, +0.0128, +0.4737, +0.0136, +0.0774,
+ +0.3074, +0.0766, -0.2378, +0.0485, +0.3838, -0.2468, -0.1098,
+ -0.2152, +0.0587, -0.2543, +0.3835, -0.1868, +0.4615, -0.4107,
+ +0.2520, +0.0725, +0.3860, +0.1150, -0.3168, +0.0991, +0.1227,
+ +0.0676, -0.0073, +0.0185, +0.0667, -0.4643, +0.2600, -0.0383,
+ -0.2920, +0.0836, -0.3683, +0.2688, +0.2978, -0.1071, -0.2877,
+ -0.0936, -0.0374, +0.0552, -0.2354, -0.0068, -0.5642, -0.0270,
+ +0.3623, -0.6247
+ ],
+ [
+ -0.1794, -0.6469, -0.2005, -0.0931, +0.1129, +0.0514, -0.0467,
+ +0.3075, -0.0633, -0.1825, +0.2719, -0.3011, +0.2022, +0.4541,
+ +0.1091, +0.1069, -0.2843, -0.0083, -0.1186, +0.1789, +0.1923,
+ +0.2096, +0.2436, +0.2531, -0.2846, +0.1484, +0.5951, -0.2624,
+ +0.2010, +0.0453, -0.1421, +0.1439, +0.0311, +0.1574, -0.1362,
+ +0.2092, -0.1079, +0.0097, +0.0032, -0.2158, -0.2078, -0.2905,
+ +0.1767, -0.5548, +0.0682, +0.0185, -0.1438, -0.3615, +0.0546,
+ +0.0569, -0.0391, -0.7231, -0.1122, -0.0317, +0.2239, +0.1588,
+ +0.1139, +0.0698, -0.1196, -0.5234, -0.4367, -0.1172, +0.1110,
+ -0.0475, -0.1380, +0.1305, -0.2057, -0.7198, +0.0661, -0.1014,
+ +0.0224, +0.0770, -0.5482, +0.2791, +0.2226, -0.2000, -0.0676,
+ -0.4551, +0.0832, -0.0944, +0.0012, -0.0266, +0.3025, +0.0629,
+ -0.0212, +0.3119, -0.3967, -0.0072, +0.0522, -0.1675, +0.2270,
+ -0.5319, +0.1066, -0.4644, +0.2507, -0.7823, +0.3102, +0.0146,
+ +0.1905, -0.2320, +0.0155, -0.3714, -0.3955, +0.1832, -0.0578,
+ -0.4893, +0.0741, -0.1344, -0.2543, +0.0362, -0.5893, -0.5407,
+ -0.0138, -0.3061, -0.1880, -0.7254, +0.1985, +0.1975, +0.3145,
+ +0.0314, -0.2741, +0.4982, -0.0651, +0.3584, +0.0948, +0.0382,
+ -0.1478, -0.6292
+ ],
+ [
+ +0.0108, +0.1363, -0.4603, -0.6946, +0.1555, -0.4470, -0.0054,
+ -0.0728, +0.2475, -0.2475, +0.2982, -0.1344, +0.2278, +0.2052,
+ -0.6269, -0.3164, -0.3965, -0.0100, +0.5359, -0.4468, +0.1302,
+ -0.4960, -0.4109, +0.2271, -0.4049, +0.2888, +0.0563, +0.2683,
+ -0.1955, +0.3281, -0.3322, -0.0276, +0.1287, +0.5680, +0.0449,
+ +0.0856, +0.1424, +0.1702, -0.1806, +0.5474, +0.1719, -0.1926,
+ -0.0079, -0.1671, +0.0840, -0.0674, -0.2571, -0.0109, -0.2267,
+ +0.2417, +0.3584, +0.3720, -0.0394, -0.0459, -0.0924, -0.3447,
+ +0.0089, -0.9740, +0.0036, -0.3574, -0.1076, -0.4138, +0.1189,
+ -0.1872, +0.1986, +0.1237, +0.1391, +0.4177, -0.0582, -0.2411,
+ -0.1025, -0.3558, +0.4156, -0.1450, +0.0069, -0.2615, +0.3515,
+ -0.2806, +0.0704, -0.3630, +0.2234, -0.1900, -0.3181, -0.1556,
+ +0.2019, -0.0437, -0.2472, -0.4759, -0.2476, -0.4334, +0.3947,
+ +0.2041, +0.0127, +0.2119, -0.3167, +0.2268, -0.1841, +0.3159,
+ -0.4010, -0.2133, -0.0276, -0.4166, -0.0255, -0.0258, -0.2008,
+ -0.5324, -0.3827, -0.8062, +0.5195, -0.2211, +0.2540, +0.0670,
+ +0.1731, +0.1564, +0.2965, -0.2518, +0.1688, +0.4063, +0.1802,
+ +0.2394, -0.2798, -0.2258, +0.0013, +0.0755, +0.0758, +0.0380,
+ -0.0515, +0.0203
+ ],
+ [
+ +0.0682, +0.0607, -0.4312, -0.0837, -0.0390, -0.0473, +0.2011,
+ +0.2264, +0.0435, +0.1802, +0.2948, +0.4862, -0.2232, +0.2120,
+ +0.2287, +0.3143, +0.0856, -0.1173, +0.3023, -0.5732, -0.2188,
+ -0.1307, -0.1044, +0.0311, +0.1745, -0.0431, -0.1285, +0.0134,
+ -0.6088, -0.3926, +0.0858, -0.2324, +0.0178, -0.2543, +0.1034,
+ -0.2823, +0.0999, -0.1172, +0.2767, +0.4904, -0.3913, +0.2075,
+ +0.1072, +0.0606, -0.0847, +0.4113, +0.1683, +0.1330, +0.0234,
+ -0.2255, -0.0991, +0.2487, -0.0258, +0.0851, -0.4635, -0.1941,
+ +0.0976, +0.0097, +0.3667, -0.5655, +0.3308, +0.0844, -0.2296,
+ +0.5016, +0.0795, +0.0289, -0.4559, +0.4661, -0.1285, +0.1738,
+ -0.3641, +0.2920, +0.1332, +0.1255, +0.1899, +0.0596, +0.0581,
+ +0.3625, +0.2658, +0.1000, -0.0309, +0.4054, -0.1588, -0.0548,
+ -0.0737, -0.2622, +0.1349, +0.0257, -0.1382, -0.2838, +0.3152,
+ +0.0558, +0.3262, -0.1312, -0.2371, -0.1248, +0.4027, +0.0974,
+ -0.3818, -0.4092, -0.0118, -0.2306, +0.0839, -0.0772, +0.1386,
+ +0.0937, -0.2221, +0.0781, +0.3098, +0.0550, +0.1964, -0.6213,
+ +0.1870, +0.0641, +0.1922, +0.0954, -0.0066, +0.0672, +0.0384,
+ -0.1116, -0.0447, -0.0057, +0.0436, -0.2353, +0.1362, +0.0894,
+ -0.0830, +0.0130
+ ],
+ [
+ +0.2553, +0.2339, +0.0967, +0.7129, -0.2857, -0.1087, +0.2100,
+ -0.2756, -0.2708, -0.1745, +0.2868, -0.3398, -0.0809, -0.0359,
+ +0.1840, -0.6609, +0.0503, -0.0303, -0.5335, +0.4147, +0.3857,
+ +0.2817, -0.2322, +0.2738, -0.1197, -0.0957, +0.0977, +0.2833,
+ -0.1044, +0.1534, +0.3056, -0.0947, -0.0552, -0.0028, -0.2728,
+ -0.1350, +0.4430, +0.1648, -0.4715, +0.1161, -0.1061, +0.0075,
+ -0.3901, -0.1448, -0.0034, +0.0361, +0.3333, +0.2831, +0.0583,
+ -0.0816, -0.2184, +0.2277, +0.2847, -0.0651, -0.0631, -0.1300,
+ -0.7026, +0.0612, +0.3413, +0.0853, -0.0591, -0.2359, -0.0052,
+ +0.0620, +0.0290, +0.0936, -0.3844, -0.2343, -0.0891, +0.1331,
+ +0.0239, +0.3608, -0.0228, +0.5134, +0.5165, -0.3740, -0.0318,
+ +0.2402, -0.0454, +0.1330, -0.2295, -0.2050, +0.1477, -0.4862,
+ -0.3914, +0.0083, -0.0326, -0.1580, +0.5535, +0.2553, -0.3117,
+ -0.3831, -0.0202, +0.1943, -0.4166, +0.0539, -0.3034, -0.4123,
+ +0.2323, +0.5206, -0.1463, +0.2259, -0.4273, +0.0657, -0.0571,
+ +0.0722, -0.1226, -0.0538, -0.0069, -0.2261, -0.1497, -0.2016,
+ +0.3124, -0.7570, +0.0104, +0.2903, +0.0640, +0.0830, -0.2558,
+ -0.2965, +0.1475, +0.2381, -0.0430, +0.7055, +0.0051, -0.2930,
+ +0.0725, +0.1653
+ ],
+ [
+ +0.1017, -0.0169, +0.3433, -0.0247, +0.3333, +0.4303, -0.0808,
+ +0.0873, -0.1596, +0.3726, -0.1868, +0.0866, -0.1615, +0.0522,
+ +0.1393, -0.5026, +0.2647, -0.2591, -0.3463, +0.0496, +0.3718,
+ -0.3523, -0.0447, +0.4346, -0.1340, +0.0819, -0.6307, -0.3348,
+ -0.4477, +0.1867, -0.0589, +0.1986, +0.1826, +0.0722, +0.1900,
+ -0.0628, -0.1909, -0.1866, +0.0619, +0.1771, -0.5174, +0.2349,
+ +0.0508, -0.0999, +0.0179, -0.0232, +0.3815, -0.0653, +0.0794,
+ +0.4170, -0.6661, +0.2416, -0.3119, +0.0735, -0.1154, -0.5300,
+ -0.4085, -0.0628, -0.2777, +0.3121, +0.3427, +0.2223, -0.2194,
+ +0.0163, +0.1581, -0.2255, +0.1695, +0.0007, -0.5535, -0.4634,
+ -0.0713, +0.2734, +0.0629, +0.0570, +0.1100, -0.1807, -0.4638,
+ +0.0892, -0.2699, -0.2704, +0.3017, +0.0141, -0.6492, +0.0556,
+ +0.2206, -0.2548, +0.5063, +0.3248, +0.5339, +0.1342, -0.3769,
+ -0.2276, +0.1179, -0.0696, -0.4020, +0.1742, -0.7131, -0.1189,
+ +0.1510, +0.0971, +0.0307, -0.1883, +0.1087, +0.0189, +0.2568,
+ -0.0677, +0.0837, +0.3688, -0.1358, -0.0299, +0.0662, -0.1572,
+ -0.4141, -0.4710, +0.1579, +0.1420, +0.3501, -0.3492, -0.2122,
+ +0.0453, -0.1907, +0.1908, +0.1346, -0.1349, -0.2534, +0.1119,
+ +0.2728, -0.2293
+ ],
+ [
+ +0.2693, -0.1020, -0.3455, +0.0030, -0.3548, +0.1798, +0.4188,
+ +0.0925, -0.0413, +0.4003, +0.1355, +0.1477, +0.2107, +0.1396,
+ +0.0675, -0.1143, +0.2218, +0.1212, +0.1667, +0.5631, -0.1789,
+ +0.2033, -0.0790, -0.1211, +0.2683, +0.1936, +0.0309, +0.0716,
+ -0.0439, +0.1382, +0.2220, -0.3047, -0.0533, +0.0854, +0.0078,
+ +0.2174, +0.6549, +0.2140, -0.0696, +0.1489, +0.1232, +0.0858,
+ -0.6816, -0.1291, -0.5285, +0.3526, +0.0384, +0.2509, +0.2088,
+ -0.2426, +0.1777, +0.1761, +0.1864, -0.0985, +0.2616, -0.1704,
+ -0.0899, +0.0956, +0.3256, -0.1290, +0.0407, +0.1948, -0.2022,
+ +0.2970, +0.1606, +0.3364, +0.2783, +0.5472, -0.2109, +0.1295,
+ -0.0814, -0.1079, +0.1947, -0.2231, -0.1824, +0.2293, -0.1339,
+ -0.3247, +0.1065, +0.1698, -0.3407, +0.3650, +0.1766, -0.2943,
+ -0.4004, +0.0150, +0.1015, -0.0351, -0.0017, +0.0853, -0.0862,
+ +0.2807, +0.1220, +0.4419, -0.0513, +0.1721, +0.1401, +0.4210,
+ -0.1857, -0.0636, +0.0270, -0.2352, +0.0363, -0.0249, -0.0597,
+ +0.2238, -0.3294, +0.0218, -0.0032, -0.0701, -0.1210, +0.1158,
+ -0.0764, +0.0413, +0.0088, +0.1163, -0.0208, -0.0476, -0.0188,
+ +0.1646, -0.2721, -0.3308, -0.1978, +0.0704, -0.0254, -0.5013,
+ -0.2004, +0.1996
+ ],
+ [
+ +0.2633, -0.1499, +0.0166, -0.5333, +0.1778, +0.4300, +0.1187,
+ +0.0878, +0.4357, -0.1351, -0.2278, +0.2826, +0.4363, +0.1333,
+ -0.0353, -0.3369, -0.1327, +0.3520, -0.2643, -0.1522, -0.2161,
+ +0.1890, -0.2408, +0.2558, -0.1769, +0.1612, +0.2292, +0.1531,
+ -0.2258, +0.2110, -0.4630, -0.0362, -0.1990, -0.1168, +0.0159,
+ -0.4588, -0.0290, +0.1523, -0.1201, -0.0006, +0.1122, +0.0192,
+ +0.4572, +0.0165, -0.4139, +0.2357, +0.2230, +0.0980, -0.0781,
+ +0.1679, -0.2461, +0.2794, +0.2259, -0.2183, +0.0412, -0.1722,
+ -0.2792, +0.2898, +0.2379, -0.0363, -0.2130, -0.1842, +0.1052,
+ -0.0095, -0.2856, +0.0777, +0.0496, +0.0280, -0.2245, -0.0076,
+ -0.0632, -0.0875, -0.0481, -0.5607, +0.0340, -0.1438, -0.0158,
+ -0.1934, +0.2243, -0.2398, -0.0403, -0.6139, -0.4362, -0.0030,
+ -0.2919, -0.0780, -0.3351, -0.0650, -0.0780, -0.2431, -0.3703,
+ -0.4119, +0.1445, +0.0133, +0.0393, -0.3822, +0.1098, +0.1970,
+ +0.0569, -0.5413, -0.1958, +0.1032, +0.0823, +0.1366, -0.0495,
+ -0.1210, -0.1508, -0.2696, -0.0934, +0.0480, +0.2404, -0.1181,
+ +0.0223, -0.4104, -0.4513, +0.0789, +0.1213, -0.0352, -0.1675,
+ -0.2540, -0.0869, +0.0362, -0.2360, -0.0736, +0.3257, +0.0739,
+ -0.0038, +0.0745
+ ],
+ [
+ -0.1152, +0.2965, -0.3136, -0.1767, +0.0926, -0.5773, +0.0044,
+ +0.1510, -0.1418, -0.2058, +0.0223, -0.3192, -0.2464, -0.3721,
+ +0.0900, +0.0702, -0.0699, +0.0563, -0.5249, -0.1389, -0.0329,
+ -0.1351, +0.0523, +0.3451, -0.0718, -0.3792, +0.0844, +0.0541,
+ -0.4429, -0.2259, -0.2771, +0.0803, +0.1938, -0.0576, +0.2719,
+ -0.3080, +0.1831, -0.1929, +0.0382, -0.0297, +0.0554, -0.0088,
+ +0.0183, -0.0070, -0.0396, -0.5188, +0.0332, +0.0408, -0.2020,
+ -0.0902, -0.1569, +0.3531, +0.1486, +0.1994, -0.2587, +0.3177,
+ +0.2230, +0.3852, +0.0526, +0.0521, +0.2908, -0.4346, +0.1264,
+ -0.3982, +0.0842, -0.6006, +0.6465, -0.3693, -0.1780, -0.1894,
+ +0.3467, -0.0559, +0.0476, -0.0536, +0.5247, -0.0387, -0.4233,
+ +0.4379, -0.5253, -0.1410, -0.1401, -0.2706, -0.0231, -0.0002,
+ +0.3057, -0.1973, +0.2027, +0.1584, +0.1657, +0.2245, +0.1908,
+ -0.2495, -0.0467, +0.3324, -0.0309, +0.2062, +0.1451, +0.1661,
+ -0.7140, +0.5208, -0.1006, +0.1176, -0.0063, +0.0877, -0.1852,
+ +0.2412, +0.2701, +0.2423, -0.0322, +0.0373, +0.2032, -0.0462,
+ +0.1739, -0.2051, +0.4769, +0.2840, +0.0295, -0.1836, +0.1977,
+ +0.1941, +0.0022, -0.1481, -0.0497, -0.0241, +0.4881, +0.1507,
+ +0.0563, +0.5255
+ ],
+ [
+ +0.1783, -0.1203, -0.2837, -0.0693, -0.0784, -0.5550, -0.2614,
+ +0.0294, -0.2250, -0.6219, +0.0918, -0.1786, +0.0339, +0.1697,
+ +0.4793, -0.1741, +0.2219, -0.1546, -0.1324, -0.1727, -0.4113,
+ -0.1253, -0.1133, +0.2454, -0.1448, +0.1979, -0.3952, +0.1347,
+ -0.1608, -0.2029, -0.2363, +0.0604, -0.1048, +0.1909, +0.4279,
+ -0.5313, -0.5097, +0.1291, -0.1537, +0.2515, +0.0301, -0.1484,
+ +0.2159, +0.0742, -0.0764, +0.3921, -0.5697, -0.0334, +0.0640,
+ +0.1345, -0.0446, -0.2890, -0.3501, +0.3603, -0.4679, +0.1560,
+ -0.4771, -0.1902, -0.2499, -0.7031, +0.2479, +0.2047, +0.1851,
+ -0.2436, -0.1453, -0.0497, +0.0418, -0.4254, +0.4114, +0.2546,
+ +0.5168, +0.6939, -0.2599, -0.3046, -0.4814, +0.1555, -0.1132,
+ -0.0019, -0.1333, +0.3497, -0.4754, +0.0764, -0.0157, +0.2168,
+ -0.1795, -0.5074, +0.3335, +0.1166, +0.4986, +0.3988, +0.1274,
+ -0.5790, -0.2656, -0.5017, +0.2233, +0.0550, +0.0143, -0.2615,
+ -0.4955, +0.1764, -0.2795, -0.4044, +0.2753, +0.2312, +0.1464,
+ -0.0805, +0.5014, -0.1711, -0.6885, -0.5679, +0.3286, -0.2191,
+ -0.0982, +0.3592, +0.2221, +0.0310, -0.0824, -0.3813, -0.0662,
+ -0.7379, -0.2829, -0.0762, -0.2882, -0.4549, -0.1073, -0.1336,
+ -0.1835, -0.1327
+ ],
+ [
+ +0.4517, +0.0658, -0.3340, +0.2966, -0.1853, -0.0043, -0.3360,
+ +0.0280, -0.2086, -0.0996, +0.0273, -0.2293, -0.0638, -0.2680,
+ -0.1610, +0.3207, +0.0587, +0.1650, -0.1426, -0.2957, +0.3290,
+ -0.1567, -0.5362, +0.1573, -0.0615, -0.4283, -0.2864, -0.0530,
+ +0.0971, -0.0878, -0.0782, -0.0000, +0.1582, +0.6758, +0.3259,
+ +0.1928, -0.0288, -0.1770, +0.0926, -0.0870, +0.0457, -0.3155,
+ -0.1675, -0.4340, +0.1712, +0.0053, +0.0989, +0.1947, -0.0384,
+ -0.0906, -0.2912, +0.1230, -0.3258, -0.2202, -0.4676, +0.1021,
+ +0.0618, -0.0397, +0.0854, -0.1780, +0.1357, +0.0466, +0.0795,
+ -0.2550, -0.2503, +0.1017, -0.1647, -0.2143, -0.1276, +0.0739,
+ +0.1593, -0.1818, +0.1127, -0.0927, -0.8645, +0.0464, +0.2128,
+ -0.1659, +0.0030, -0.0731, +0.0294, +0.0992, -0.0481, +0.0158,
+ -0.3424, -0.2776, +0.2169, -0.1007, +0.0535, +0.0958, +0.1272,
+ -0.3455, +0.0960, +0.2129, +0.1420, +0.1840, +0.3833, -0.4782,
+ -0.0468, +0.1290, -0.1255, -0.2247, -0.0768, -0.0179, +0.0375,
+ -0.0087, -0.0451, +0.1420, -0.0974, -0.0792, +0.0055, +0.3840,
+ -0.2168, +0.0080, +0.4134, +0.2009, -0.3005, +0.3029, -0.1305,
+ -0.2074, -0.1235, +0.1048, +0.3730, +0.0040, -0.1392, -0.2744,
+ +0.0893, +0.0640
+ ],
+ [
+ -0.2067, +0.2301, -0.1646, -0.2645, +0.2361, +0.1113, +0.0502,
+ -0.0047, +0.0101, -0.3107, -0.2395, -0.4054, -0.3047, -0.1105,
+ +0.0458, -0.6247, +0.2991, +0.1149, +0.2152, +0.0058, -0.1267,
+ -0.1580, +0.2562, -0.1681, -0.4301, -0.5288, +0.1117, +0.1572,
+ -0.0636, -0.0258, +0.0505, -0.6769, -0.4278, -0.1437, -0.1065,
+ -0.0424, +0.2820, -0.1881, +0.0922, +0.2906, +0.1197, +0.1735,
+ +0.2757, -0.0850, -0.5826, +0.0295, -0.2369, -0.0866, -0.0146,
+ -0.1379, -0.1154, +0.2802, +0.1067, -0.2483, +0.0971, +0.0321,
+ +0.0438, -0.0545, +0.1608, -0.6518, +0.0127, -0.0457, -0.2670,
+ +0.2368, +0.0150, +0.2014, -0.3092, +0.0049, -0.0913, -0.0520,
+ +0.0037, -0.0204, -0.2846, -0.0804, +0.3840, +0.3022, +0.3030,
+ -0.0264, +0.3104, -0.2525, -0.4555, +0.0665, -0.5402, +0.1549,
+ -0.2790, -0.3014, +0.1059, -0.0015, +0.0155, -0.6908, +0.3992,
+ +0.1417, -0.2429, +0.0394, +0.1702, -0.0042, -0.3149, +0.3281,
+ +0.0022, +0.2559, -0.0678, +0.7093, -0.5322, -0.0675, -0.3888,
+ -0.3135, -0.0432, +0.5027, +0.0406, -0.0088, +0.3937, +0.3382,
+ -0.1515, +0.1129, -0.2990, +0.0603, +0.0857, +0.0208, -0.5491,
+ +0.0658, -0.3145, +0.1052, +0.2350, -0.1393, -0.0873, +0.1726,
+ -0.0157, -0.0962
+ ],
+ [
+ -0.3887, -0.3419, -0.2082, -0.3848, -0.1498, +0.2693, -0.1537,
+ +0.2435, +0.0828, +0.3029, -0.3123, +0.1239, +0.2061, -0.2443,
+ -0.0488, -0.0663, -0.2655, -0.0834, -0.2414, -0.0122, +0.0514,
+ -0.7199, -0.4183, +0.2118, +0.3534, -0.2131, -0.3576, -0.1144,
+ -0.0576, +0.0392, -0.1840, +0.2215, -0.5385, -0.2425, -0.0777,
+ +0.0208, -0.1796, +0.1108, +0.1878, +0.1009, +0.1568, -0.1247,
+ -0.1476, +0.1501, -0.2837, -0.0996, +0.2396, -0.0442, +0.1063,
+ +0.2721, -0.1514, +0.2922, -0.1659, -0.3875, +0.0173, +0.3768,
+ -0.0494, -0.3885, +0.1457, -0.2002, +0.3482, -0.5610, +0.1872,
+ +0.0486, +0.3783, -0.1147, -0.0878, -0.0411, -0.0771, -0.0347,
+ +0.0312, +0.0703, -0.3597, -0.2080, +0.1644, -0.0097, +0.4533,
+ -0.0798, +0.1823, +0.0052, -0.0697, -0.3489, +0.1621, -0.0199,
+ -0.2716, -0.1253, +0.0369, +0.0719, -0.0387, -0.1067, +0.0970,
+ +0.0786, -0.5694, +0.2189, +0.0160, +0.1855, -0.0319, -0.1075,
+ -0.0951, +0.1119, -0.2590, +0.3577, -0.1265, -0.2266, +0.1194,
+ +0.2802, +0.2770, +0.0235, +0.2434, +0.3130, +0.1270, -0.4183,
+ +0.1559, +0.2719, -0.3041, -0.2625, +0.0789, +0.0228, -0.3127,
+ +0.2764, -0.0512, +0.1628, -0.0959, +0.1506, -0.1898, +0.1287,
+ +0.1856, -0.0313
+ ],
+ [
+ +0.2018, +0.2554, -0.0049, -0.3112, -0.2239, -0.3388, +0.3906,
+ +0.1859, -0.1265, +0.3720, -0.1896, +0.0098, +0.0376, +0.2438,
+ +0.1950, +0.0796, -0.0422, -0.0262, -0.2366, +0.1564, +0.2580,
+ +0.1235, -0.3529, -0.5791, -0.0359, -0.3110, -0.2399, +0.4439,
+ +0.0040, +0.1688, +0.1939, -0.2981, +0.0870, +0.4176, -0.3759,
+ -0.2486, +0.1234, +0.1051, +0.0157, -0.4434, -0.0287, +0.4169,
+ +0.0161, -0.2643, +0.4733, -0.1172, +0.0843, -0.2524, -0.0453,
+ -0.0913, -0.1426, -0.3986, -0.0733, +0.0797, +0.1183, -0.1853,
+ -0.2104, +0.0994, -0.3430, +0.2793, -0.6255, +0.3737, +0.2317,
+ -0.1720, +0.1032, +0.1511, -0.2115, +0.5591, -0.0244, -0.0046,
+ -0.1598, -0.1281, -0.0300, +0.2074, -0.0218, +0.1136, +0.0940,
+ +0.0987, -0.5553, -0.0394, -0.0461, -0.1228, +0.1672, +0.0195,
+ +0.3806, +0.2578, -0.4602, +0.0679, +0.0663, +0.0252, -0.0842,
+ -0.0321, -0.2086, +0.0606, -0.2867, -0.1604, -0.2171, +0.4462,
+ -0.3729, -0.7239, +0.1828, -0.0708, +0.0649, -0.3095, +0.4024,
+ +0.0170, -0.0434, -0.1998, +0.2228, +0.5068, -0.0601, -0.3232,
+ -0.1708, -0.3354, -0.1161, -0.4872, +0.0997, +0.3460, -0.0601,
+ -0.3048, +0.1425, -0.3348, -0.4696, +0.0979, +0.0794, +0.1274,
+ +0.2205, +0.1029
+ ],
+ [
+ +0.2202, -0.0473, -0.0483, +0.0908, +0.2507, +0.1783, -0.0428,
+ -0.0113, -0.0889, -0.2476, +0.1438, -0.2904, +0.1929, -0.5124,
+ -0.1411, +0.0491, +0.2510, +0.5334, -0.0648, +0.3099, +0.0367,
+ +0.2053, -0.0321, +0.0069, +0.3099, -0.0422, -0.7279, +0.3423,
+ -0.1532, +0.0617, -0.1533, -0.0856, +0.0292, +0.0060, -0.1155,
+ -0.3122, -0.3182, +0.0682, +0.1417, +0.3202, +0.2111, +0.4028,
+ +0.0776, -0.1851, +0.0884, +0.1650, +0.0792, -0.5007, +0.4097,
+ -0.0505, -0.5315, -0.8284, +0.2097, +0.3150, -0.0899, +0.5223,
+ +0.3590, +0.1334, -0.2466, -0.4766, +0.1727, -0.0124, -0.1536,
+ -0.3359, -0.2406, -0.2959, +0.3427, -0.2860, +0.0579, -0.1943,
+ +0.1129, -0.2535, -0.1982, -0.0823, -0.3116, +0.0267, -0.0368,
+ -0.8230, -0.0157, -0.0027, -0.2506, +0.0386, -0.1757, +0.1732,
+ +0.1558, -0.4040, +0.2373, -0.0159, -0.0559, -0.4249, +0.1963,
+ +0.0035, +0.2762, +0.1329, -0.0338, -0.3528, +0.4236, +0.3524,
+ +0.3066, -0.1558, +0.4670, +0.0273, +0.0020, -0.1610, +0.0273,
+ +0.2771, -0.1472, -0.1650, +0.1146, -0.0556, +0.4777, +0.2354,
+ -0.0608, -0.0926, -0.3920, +0.1041, +0.2493, -0.4355, -0.0731,
+ +0.2479, -0.7999, -0.1610, +0.2666, +0.2134, +0.1338, +0.0135,
+ -0.6830, -0.1893
+ ],
+ [
+ -0.1152, +0.1442, -0.0220, -0.7058, -0.3012, -0.0015, -0.2417,
+ -0.3607, -0.1625, +0.0061, -0.0695, -0.2861, -0.0088, +0.0729,
+ +0.3041, +0.3543, +0.2796, +0.0359, +0.0541, -0.5513, +0.0041,
+ -0.0687, -0.2319, +0.4381, -0.2315, -0.4676, -0.3778, +0.2826,
+ -0.2813, -0.5964, +0.5921, -0.0691, -0.0296, +0.4393, +0.1530,
+ +0.2270, -0.0868, -0.5361, -0.0368, +0.3822, +0.1015, +0.3149,
+ -0.2556, +0.0701, +0.1325, +0.1867, -0.1930, +0.2955, +0.1443,
+ +0.0907, -0.7181, -0.1485, -0.9969, +0.2466, -0.0384, +0.1874,
+ +0.1444, -0.3377, +0.0616, +0.2895, -0.1200, +0.0314, +0.4350,
+ +0.0230, +0.1443, -0.3053, -0.0222, -0.0372, +0.2736, +0.1352,
+ -0.0322, +0.2443, +0.2799, -0.1980, +0.1430, -0.4997, +0.5547,
+ +0.0101, -0.4364, +0.1719, +0.2264, +0.2338, -0.1936, -0.3765,
+ -0.4489, -0.4625, -0.3184, -0.0327, -0.1858, -0.1664, -0.0074,
+ +0.2940, +0.0657, +0.0209, -0.3291, -0.0707, -0.1251, -0.0179,
+ -1.4153, +0.2057, -0.1318, -0.0649, -0.0746, +0.1426, -0.0178,
+ -0.3179, +0.0938, -0.1089, -0.1703, -0.0076, +0.1258, -0.3994,
+ -0.3611, +0.1069, +0.4496, +0.2736, -0.0324, +0.0022, -0.5305,
+ +0.0004, -0.3541, -0.2936, -0.4940, +0.3456, +0.2212, -0.0787,
+ -0.4951, +0.1607
+ ],
+ [
+ +0.1808, +0.1338, +0.2585, -0.4397, +0.0622, -0.1769, -0.0225,
+ -0.0177, +0.0734, +0.0638, -0.1966, -0.5875, -0.3866, +0.3552,
+ +0.0917, -0.2711, +0.0791, -0.0989, -0.0565, -0.1037, +0.4928,
+ -0.3035, -0.0973, +0.0508, +0.3004, -0.1029, -0.4030, +0.0268,
+ +0.0685, +0.1040, -0.4739, -0.0076, -0.5081, +0.1892, -0.2594,
+ +0.6059, -0.2552, -0.1620, -0.0864, +0.1521, +0.1867, +0.3853,
+ +0.3173, +0.0243, -0.2726, -0.3549, -0.1538, +0.1737, +0.1056,
+ +0.3319, -0.1266, +0.1966, -0.3478, +0.1736, -0.6014, -0.2518,
+ +0.4000, +0.3501, +0.4711, +0.3372, +0.1510, +0.4035, +0.1676,
+ -0.3453, -0.0087, -0.2413, +0.5548, -0.6989, -0.3707, +0.0316,
+ +0.1842, -0.0989, -0.3163, -0.1315, +0.4837, -0.2424, +0.2195,
+ -0.0846, +0.0250, -0.3628, -0.0584, -0.5256, -0.0596, +0.3859,
+ +0.1934, -0.0144, +0.1942, -0.1791, +0.3130, +0.7044, +0.1126,
+ -0.3029, +0.2233, -0.0153, -0.0767, -0.2393, +0.0245, +0.1158,
+ +0.0386, +0.5383, -0.0311, +0.0613, +0.2475, +0.1752, +0.0003,
+ -0.1864, +0.1285, +0.2277, -0.2469, -0.1582, -0.2115, +0.2388,
+ +0.0677, -0.0029, -0.0497, +0.3063, -0.1699, +0.3031, -0.3998,
+ -0.0385, -0.0300, -0.0523, +0.4780, +0.2601, +0.5331, -0.0449,
+ +0.1596, -0.1041
+ ],
+ [
+ +0.2238, +0.1284, -0.1701, +0.1403, -0.0135, +0.2474, +0.0308,
+ +0.2728, -0.1048, +0.1523, -0.0382, +0.4176, -0.3344, +0.2705,
+ +0.3271, +0.7143, -0.4450, +0.4092, +0.1036, -0.4947, +0.2866,
+ -0.5911, -0.1048, +0.0398, +0.2436, +0.1804, -0.2068, +0.1557,
+ -0.4103, -0.0793, +0.2855, -0.0640, -0.1582, -0.1056, -0.2873,
+ +0.7593, -0.4392, -0.2479, +0.1564, -0.2532, -0.6649, -0.2479,
+ -0.7535, -0.0447, -0.2502, -0.2208, -0.0584, -0.5366, -0.2103,
+ +0.0147, +0.0866, +0.6192, -0.1458, +0.0391, -0.0438, -0.2746,
+ +0.2588, -0.1434, +0.3173, -0.0749, -0.5273, +0.1983, -0.1958,
+ -0.2106, +0.0725, +0.1267, -0.4564, +0.0371, +0.2196, -0.0905,
+ +0.0582, -0.0972, -0.1200, +0.0785, +0.0373, +0.1558, -0.1794,
+ -0.0782, +0.0833, -0.2928, +0.2547, -0.3066, +0.3207, -0.0713,
+ +0.1041, +0.0323, -0.3902, +0.1083, -0.1922, +0.0627, +0.2882,
+ +0.1281, -0.6859, +0.3662, -0.3920, -0.0183, -0.5185, -0.3081,
+ -0.3686, +0.0500, +0.0318, -0.1623, -0.2901, +0.1586, +0.0187,
+ -0.4677, -0.2002, -0.3237, -0.0840, +0.1040, +0.0714, +0.2835,
+ -0.1764, -0.1995, +0.2796, -0.0560, +0.0650, -0.3539, +0.1896,
+ +0.3324, -0.3503, -0.2889, -0.0343, +0.3707, -0.0376, +0.2383,
+ -0.3181, +0.3099
+ ],
+ [
+ -0.1127, -0.3128, +0.0028, +0.1006, -0.1284, -0.0052, +0.3716,
+ +0.0876, +0.3156, -0.0414, -0.0690, -0.0513, +0.1852, +0.0597,
+ -0.0213, +0.0427, -0.5044, +0.2126, -0.2119, -0.1303, -0.4426,
+ +0.3006, +0.3830, +0.1086, -0.1569, -0.1747, -0.3161, -0.2888,
+ +0.2725, +0.2182, -0.4447, -0.6314, +0.0895, -0.0459, -0.4898,
+ -0.0969, -0.0063, +0.5000, +0.0557, -0.0516, -0.1925, -0.0804,
+ +0.2792, -0.0105, -0.1772, +0.2723, -0.2916, -0.1807, -0.0976,
+ +0.3596, -0.5005, +0.0279, +0.2975, -0.3719, +0.1297, -0.3601,
+ +0.0749, -0.0975, +0.4026, -0.2229, -0.0846, +0.2353, -0.1063,
+ +0.0776, -0.1897, -0.0136, -0.1587, -0.3237, -0.2042, +0.2351,
+ +0.0336, -0.1441, -0.0715, +0.1958, -0.0658, +0.1386, +0.1308,
+ +0.1369, +0.0607, -0.1522, +0.0956, -0.0699, +0.3380, -0.4043,
+ -0.0375, +0.1118, -0.6505, -0.1881, -0.3635, +0.3707, +0.2681,
+ -0.0927, -0.2507, +0.0609, +0.0271, +0.1656, +0.0221, -0.5332,
+ +0.0420, +0.0947, +0.0090, -0.1108, +0.1345, +0.2935, -0.2839,
+ +0.2581, +0.2247, -0.1338, -0.0634, +0.1884, -0.1076, -0.0599,
+ -0.0024, -0.1269, +0.1119, -0.3119, -0.1935, -0.2787, -0.0870,
+ -0.5573, -0.1073, -0.0517, -0.1105, -0.3601, +0.4294, +0.1922,
+ -0.5099, +0.1859
+ ],
+ [
+ +0.4151, +0.0486, -0.2621, -0.1066, -0.4595, +0.2190, +0.0539,
+ +0.2084, +0.0236, -0.0017, -0.0462, -0.1106, -0.6621, -0.4632,
+ -0.1909, -0.1931, -0.2267, -0.1587, -0.2585, +0.1337, +0.2305,
+ +0.5494, +0.3112, -0.2645, -0.0419, -0.5014, +0.0660, -0.4007,
+ -0.0919, +0.1091, +0.0193, +0.4635, -0.2758, +0.1595, -0.1809,
+ -0.2396, +0.2757, -0.0915, -0.3786, -0.2914, -0.0223, -0.1506,
+ +0.3220, -0.4689, +0.0942, +0.1772, +0.2289, +0.0095, -0.1261,
+ +0.0043, +0.2686, +0.3630, -0.5158, +0.2660, +0.2270, -0.1899,
+ -0.3355, +0.1850, -0.0454, -0.1173, -0.4624, +0.2398, -0.0933,
+ +0.2974, +0.3400, +0.0097, +0.0780, -0.0762, -0.0705, -0.3773,
+ -0.3827, -0.1402, +0.2830, +0.0033, +0.0435, -0.1584, -0.0909,
+ -0.2032, -0.5186, +0.3478, +0.1443, +0.1681, -0.1531, +0.5813,
+ -0.1559, -0.3443, -0.1627, -0.0723, -0.0982, +0.0982, +0.1497,
+ -0.1783, +0.1030, -0.1996, -0.0243, -0.0758, -0.6743, +0.3288,
+ -0.1346, +0.0569, +0.0086, -0.5111, -0.0393, +0.1989, +0.1777,
+ -0.0203, +0.0408, +0.1340, -0.2372, -0.1229, +0.3350, +0.1631,
+ +0.2887, +0.1170, -0.2061, -0.4772, +0.1707, -0.1617, +0.1395,
+ -0.2869, -0.0917, +0.0842, +0.2473, -0.0274, +0.1507, -0.1940,
+ +0.0308, +0.2831
+ ],
+ [
+ +0.0270, +0.2691, -0.3350, -0.1182, +0.0450, +0.3980, -0.1312,
+ +0.1354, -0.1923, +0.2128, +0.5420, -0.2478, +0.0921, +0.1335,
+ +0.4008, -0.0317, -0.4794, +0.0225, -0.2191, -0.0190, +0.0188,
+ -0.5584, +0.3829, +0.2571, +0.0469, +0.2138, -0.2720, +0.4466,
+ -0.0466, -0.1490, +0.2479, -0.3620, -0.5180, -0.1234, -0.1863,
+ -0.1151, -0.1035, +0.2302, -0.0834, +0.1094, -0.3245, +0.3910,
+ -0.0073, +0.2668, -0.3793, -0.2312, +0.3521, -0.1891, -0.0857,
+ +0.2789, -0.3569, +0.0599, +0.0285, +0.4213, +0.1397, +0.1513,
+ -0.2065, -0.0173, -0.0085, +0.1375, +0.0513, -0.1107, -0.3131,
+ +0.0857, -0.5247, -0.1168, -0.1839, +0.4625, -0.1646, -0.4847,
+ +0.0265, +0.0781, -0.1780, +0.8386, -0.0829, +0.0929, -0.2670,
+ -0.0063, -0.0791, -0.6327, -0.7086, -0.1977, -0.1171, -0.0106,
+ +0.6187, -0.2497, +0.0773, +0.2595, +0.1312, +0.1604, +0.0626,
+ -0.2817, +0.3393, -0.1228, -0.1665, -0.0861, +0.1366, -0.1221,
+ -0.1432, -0.5733, +0.2195, -0.0654, -0.0690, -0.0420, -0.2693,
+ +0.1086, +0.1585, -0.5603, +0.1529, -0.2381, +0.1962, -0.1147,
+ +0.0971, +0.1910, +0.1819, +0.2031, +0.0518, -0.0561, +0.6765,
+ -0.2260, +0.1227, +0.2146, +0.2084, -0.0776, +0.0527, +0.0995,
+ -0.2007, -0.1233
+ ],
+ [
+ -0.2873, -0.1797, +0.0470, +0.1901, +0.1030, +0.0715, -0.0712,
+ -0.0926, +0.0925, -0.3459, -0.3944, -0.2083, -0.0272, -0.2135,
+ +0.0001, -0.4917, -0.1781, +0.1894, -0.2399, -0.0392, +0.5503,
+ +0.0293, +0.1843, +0.0312, -0.2312, -0.3056, +0.1651, +0.2846,
+ +0.1764, -0.0142, -0.3850, -0.5774, -0.0760, -0.0523, -0.6263,
+ +0.3228, +0.4584, +0.1473, +0.5229, -0.3264, -0.0887, +0.3426,
+ -0.1249, +0.1273, +0.0110, +0.0840, +0.0106, -0.1928, -0.0661,
+ -0.0125, -0.1421, -0.2616, -0.2185, +0.0325, -0.2325, +0.1996,
+ +0.1432, -0.6655, -0.3260, -0.8642, -0.1621, -0.5049, +0.5077,
+ -0.8273, +0.4845, -0.1448, +0.0955, -0.3162, +0.1370, +0.2197,
+ +0.0644, +0.1087, -0.4276, -0.3397, -0.0150, -0.1073, -0.9972,
+ +0.3535, -0.6538, -0.1315, +0.1838, -0.2415, -0.3531, -0.3833,
+ +0.2568, -0.3342, +0.0648, +0.0233, -0.3272, +0.2680, +0.3175,
+ +0.1118, +0.3420, +0.1392, +0.4184, +0.0296, -0.4763, -0.0176,
+ -0.0144, -0.5814, -0.3503, +0.3994, +0.2795, +0.3018, +0.0602,
+ -0.0197, -0.2284, +0.0503, -0.5084, +0.3896, -0.0316, -0.2142,
+ -0.1859, +0.5103, -0.0580, -0.4366, -0.3467, +0.2605, -0.1273,
+ -0.2157, -0.1276, +0.0491, -0.0039, -0.0419, -0.3699, +0.4374,
+ +0.1162, -0.6341
+ ],
+ [
+ +0.0881, -0.0428, -0.3523, +0.2652, -0.5092, -0.1459, +0.0844,
+ -0.0671, -0.2616, +0.1079, +0.0182, -0.0213, -0.1061, +0.2430,
+ +0.1738, +0.1872, -0.1859, +0.0672, -0.3635, -0.3092, +0.0467,
+ -0.1636, +0.0847, -0.4381, -0.1506, -0.1320, -0.0478, -0.1204,
+ +0.0794, -0.0013, +0.0643, +0.4463, -0.5180, +0.2987, +0.2615,
+ +0.2146, -0.1057, +0.0422, +0.2968, +0.1310, -0.2525, -0.1665,
+ +0.2121, -0.4593, +0.4054, +0.1538, -0.0042, +0.0514, -0.2158,
+ +0.0907, +0.1021, -0.4739, +0.0356, +0.0105, -0.0032, -0.6401,
+ +0.1607, -0.5373, -0.5146, +0.1560, -0.1215, +0.0354, +0.4660,
+ -0.3790, +0.2760, +0.0380, -0.2825, +0.3231, -0.1135, -0.2536,
+ +0.0494, +0.1541, -0.0165, +0.1671, -0.0775, +0.5874, -0.1627,
+ -0.1555, +0.4098, -0.1272, -0.1850, +0.1632, +0.0497, -0.0743,
+ -0.0829, -0.1529, -0.1856, -0.4889, -0.0907, -0.0640, +0.2289,
+ +0.5469, +0.0572, -0.0645, +0.1524, +0.3242, -0.2129, -0.1097,
+ +0.1131, -0.1921, -0.2634, -0.2343, -0.0592, +0.1269, -0.1817,
+ +0.3688, +0.0245, -0.3743, +0.1940, +0.1823, -0.2238, -0.0054,
+ +0.0251, +0.0565, +0.3600, -0.1530, +0.2105, +0.3182, -0.2694,
+ -0.1781, -0.1540, +0.0377, -0.2013, +0.1521, -0.3718, +0.2454,
+ -0.0135, -0.0690
+ ],
+ [
+ -0.0353, +0.1273, +0.1086, +0.3101, -0.5079, -0.4920, +0.3528,
+ -1.0276, -0.1074, -0.0415, -0.0216, +0.2085, +0.3988, -0.1835,
+ -0.5477, -0.1663, -0.2457, +0.1004, +0.0504, +0.3388, -0.1777,
+ +0.1018, +0.0198, -0.0650, +0.0922, -0.0420, -0.1174, -0.2334,
+ +0.2075, -0.0436, -0.0588, +0.2837, +0.2075, -0.0769, -0.0617,
+ -0.0373, -0.1305, -0.2308, -0.0265, +0.4699, +0.5611, -0.2701,
+ +0.2300, +0.1910, +0.2018, +0.1750, -0.4274, +0.3083, +0.2516,
+ -0.3755, +0.6978, +0.4048, -0.0261, +0.2413, +0.2155, +0.2323,
+ +0.1521, -0.0571, +0.2908, +0.3256, +0.1790, +0.3086, -0.2499,
+ -0.1769, +0.2698, +0.1223, +0.0859, +0.2772, +0.0137, -0.3890,
+ +0.0773, -0.2195, +0.0124, +0.0221, -0.6253, +0.2795, +0.1522,
+ +0.1918, -0.4858, +0.6520, -0.0586, -0.3499, +0.0054, -0.2153,
+ +0.2401, +0.2565, -0.0043, -0.0296, -0.2459, +0.3949, +0.2121,
+ +0.1500, -0.2814, -0.2656, +0.1898, +0.3232, -0.1631, -0.0039,
+ -0.3462, +0.0166, +0.1790, -0.0065, -0.0522, -0.1100, +0.1022,
+ -0.1440, +0.2267, +0.0971, +0.3084, -0.4332, +0.2683, +0.0773,
+ +0.0125, -0.1468, -0.1822, -0.4774, -0.2671, -0.1772, +0.0039,
+ +0.0833, -0.1179, +0.0099, +0.0683, +0.0194, -0.5451, +0.0219,
+ -0.0482, +0.0236
+ ],
+ [
+ -0.0090, +0.0548, +0.0090, +0.3092, +0.0976, -0.0626, +0.0472,
+ +0.1432, -0.0912, +0.1453, +0.0198, -0.0755, -0.0584, +0.2909,
+ -0.1208, -0.3472, +0.1000, -0.1955, -0.4332, +0.1317, -0.2439,
+ -0.1974, +0.0393, -0.1747, -0.0932, -0.2908, -0.4298, -0.6810,
+ +0.1605, -0.0770, -0.0548, -0.1976, +0.3308, -0.1112, +0.2167,
+ -0.8931, +0.2516, -0.0820, +0.2553, +0.1484, -0.4512, -0.3038,
+ -0.1564, -0.1418, -0.2413, -0.2708, +0.1223, +0.4261, +0.1597,
+ +0.2612, +0.0826, -0.1703, -0.1501, +0.1301, +0.1994, +0.0556,
+ +0.3606, -0.4255, -0.2676, +0.4226, +0.0928, -0.0036, -0.3854,
+ +0.0639, +0.3991, -0.0069, -0.1642, +0.1054, +0.3349, +0.0114,
+ +0.2166, +0.1949, -0.2591, +0.1421, -0.0570, -0.1126, +0.4689,
+ -0.0098, +0.0989, -0.2056, +0.0760, +0.1136, -0.1069, +0.0169,
+ +0.2328, -0.1154, -0.3517, -0.2529, -0.0477, -0.1290, +0.0745,
+ +0.2672, +0.0654, +0.0687, +0.0551, +0.1848, +0.0550, -0.4109,
+ +0.2507, -0.1512, +0.1814, -0.0178, +0.0753, -0.0270, +0.4997,
+ -0.2452, +0.3953, +0.1132, -0.0255, -0.0010, +0.0948, -0.1982,
+ -0.1473, -0.4566, -0.1062, +0.2412, +0.0324, +0.0770, +0.2883,
+ -0.1728, +0.1389, -0.4306, -0.4021, +0.2307, -0.3570, -0.4037,
+ +0.1354, -0.0002
+ ],
+ [
+ +0.1589, -0.1895, -0.3689, -0.5727, -0.2003, +0.1168, +0.1060,
+ -0.2306, -0.4607, -0.0903, -0.0011, +0.3110, -0.0802, +0.1225,
+ -0.4624, -0.3856, -0.3799, +0.6809, -0.4660, +0.1443, +0.0860,
+ +0.2358, +0.3056, -0.0617, -0.0484, -0.0795, -0.3600, +0.4075,
+ +0.0335, +0.1461, -0.7056, -0.1246, -0.1867, -0.2580, +0.0790,
+ -0.2452, +0.1160, +0.2423, -0.2178, +0.4376, -0.3230, -0.0658,
+ +0.1403, -0.1059, -0.0664, -0.0812, -0.3583, -0.0568, -0.0803,
+ +0.1634, -0.5470, +0.1477, +0.1001, +0.3944, -0.0091, +0.1279,
+ +0.1031, -0.0828, +0.0511, +0.2370, -0.1112, +0.1076, -0.2241,
+ -0.1850, -0.1509, +0.1283, -0.0812, -0.2306, -0.1560, -0.0871,
+ +0.0507, +0.2300, -0.1790, -0.0950, -0.4634, -0.0224, -0.2822,
+ -0.0187, +0.3859, +0.3795, -0.1656, +0.5539, -0.3940, +0.2439,
+ -0.3326, +0.0786, +0.2440, -0.2166, -0.2951, -0.0167, -0.1098,
+ -0.2217, +0.3969, -0.3522, +0.4583, +0.1530, +0.0412, +0.1156,
+ +0.0537, -0.1116, +0.2062, -0.9592, -0.2470, +0.1359, +0.0993,
+ +0.1294, +0.2242, -0.9313, +0.0561, -0.1260, -0.0798, +0.0884,
+ -0.2110, -0.7277, -0.3866, -0.1434, +0.0363, -0.2238, -0.0164,
+ -0.0179, +0.1237, -0.0881, -0.4443, +0.1300, -0.0737, -0.2013,
+ +0.4890, -0.2268
+ ],
+ [
+ -0.1106, +0.2496, +0.1603, -0.4358, -0.0318, +0.4562, +0.0668,
+ +0.0913, +0.0326, -0.3287, -0.0950, -0.0000, -0.1749, +0.0147,
+ +0.1572, +0.1337, +0.3227, +0.0310, -0.1516, +0.0094, +0.0951,
+ -0.3136, -0.0813, -0.2938, -0.1727, -0.0615, +0.4927, +0.0826,
+ +0.2202, +0.0253, -0.6977, +0.1356, +0.3201, -0.3092, -0.2199,
+ +0.1048, -0.0584, -0.5777, -0.0738, -0.1789, -0.2877, +0.3229,
+ +0.0150, +0.0197, -0.2914, -0.2028, -0.1299, +0.0008, +0.2346,
+ -0.1959, +0.1455, -0.2369, -0.3370, -0.0204, -0.0299, -0.0892,
+ -0.3299, -0.1583, +0.0046, -0.1719, -0.2365, +0.2064, -0.2505,
+ -0.1913, -0.0303, -0.2115, -0.2317, +0.0057, +0.1364, +0.2279,
+ +0.1970, -0.1972, +0.3322, +0.3355, +0.0605, +0.0261, +0.0419,
+ -0.2607, -0.2405, +0.1252, -0.0398, +0.2787, -0.1420, -0.1658,
+ +0.1677, -0.2601, -0.0801, -0.1050, +0.1703, +0.3236, +0.0146,
+ -0.2126, +0.2793, -0.3282, +0.3748, -0.2006, -0.1309, +0.4723,
+ +0.2652, -0.4449, +0.0144, -0.3682, -0.0513, -0.1969, +0.2342,
+ -0.2195, +0.0066, +0.0730, -0.1386, +0.2343, -0.1026, -0.0102,
+ +0.1281, -0.2790, +0.0387, +0.1683, +0.2041, +0.1323, +0.0995,
+ -0.0678, -0.2548, +0.3116, +0.0275, -0.4052, +0.1195, -0.0628,
+ -0.1240, +0.5709
+ ],
+ [
+ +0.1611, +0.1684, +0.1180, -0.0337, -0.0164, +0.2005, -0.4611,
+ -0.1769, +0.2780, -0.1636, -0.3267, -0.7983, +0.0632, -0.2480,
+ +0.1168, -0.0431, -0.2038, -0.0721, +0.1671, -0.1710, +0.0372,
+ +0.1101, -0.3353, +0.1319, -0.0475, -0.0662, +0.0418, -0.9465,
+ +0.3207, +0.1905, -0.1956, +0.2353, -0.1500, -0.1944, -0.1521,
+ -0.1222, +0.2512, +0.3976, +0.0530, -0.2475, -0.4579, -0.2476,
+ -0.1615, -0.1236, -0.5453, +0.2712, -0.1133, +0.0285, -0.0988,
+ -0.0021, -0.2373, +0.0719, +0.0631, +0.1569, +0.0420, +0.2127,
+ -0.2636, -0.1228, +0.1000, -0.3128, -0.2440, +0.1935, +0.2123,
+ +0.2302, -0.3028, +0.1696, -0.1394, +0.3321, -0.0264, -0.0710,
+ +0.2143, -0.1402, +0.1902, -0.0156, +0.2402, +0.1609, -0.2699,
+ +0.2212, -0.2134, -0.0889, +0.0275, -0.1004, -0.0181, +0.2129,
+ -0.1209, +0.0828, -0.3149, +0.1096, +0.1476, -0.0693, +0.1365,
+ -0.1460, -0.0319, -0.1213, +0.1037, -0.0795, -0.1108, +0.4878,
+ +0.1358, -0.0006, +0.0897, -0.0319, -0.0744, +0.2202, +0.0410,
+ +0.1397, +0.0272, -0.1102, +0.0604, -0.0668, -0.6511, +0.1980,
+ -0.1455, +0.4493, -0.1050, +0.0986, -0.2703, -0.1455, +0.0464,
+ +0.1289, +0.1522, +0.1892, -0.0211, +0.1349, +0.0311, +0.2558,
+ -0.0779, +0.3977
+ ],
+ [
+ +0.1549, -0.3957, -0.0942, -0.6545, -0.1147, +0.0885, +0.0263,
+ +0.3899, -0.0039, +0.1578, +0.1178, +0.0588, -0.3606, +0.3915,
+ -0.0311, -0.0269, +0.1901, +0.2721, +0.0042, +0.0927, +0.1884,
+ -0.1861, +0.0426, -0.4855, -0.1304, +0.2175, -0.2916, +0.1244,
+ +0.4870, -0.2349, -0.2040, -0.0040, -0.2405, -0.2903, +0.0529,
+ +0.3191, +0.4127, +0.1782, -0.1870, -0.4273, -0.0206, -0.2915,
+ -0.1524, -0.4046, -0.0423, -0.1181, -0.1054, -0.5696, -0.1597,
+ -0.2354, -0.0163, -0.9035, +0.3200, +0.1112, -0.2512, +0.2378,
+ +0.2037, +0.5013, -0.3021, +0.2650, +0.1290, -0.1847, +0.4552,
+ -0.9110, +0.2156, -0.1397, +0.0881, +0.1174, -0.0092, -0.3658,
+ -0.5517, +0.1533, +0.4847, -0.0725, +0.3432, -0.4701, -0.6041,
+ +0.3269, +0.2537, +0.4220, +0.2289, +0.0101, -0.2262, -0.1981,
+ -0.0431, -0.2085, +0.5592, -0.7000, -0.0529, +0.1269, -0.4089,
+ +0.1060, -0.3534, +0.1786, -0.0607, -0.2296, -0.4937, -0.0940,
+ +0.4213, +0.1533, -0.3961, +0.1725, -0.8912, +0.0248, +0.0092,
+ -0.4522, -0.0179, -0.2877, +0.1628, -0.1096, -0.2574, -0.0872,
+ -0.2096, -0.0405, +0.1788, -0.2012, -0.0524, +0.0632, -0.5398,
+ +0.1414, -0.5686, +0.1372, -0.3937, -0.4191, -0.0216, -0.0568,
+ +0.0698, +0.2414
+ ],
+ [
+ +0.1718, -0.0079, -0.1722, +0.3320, +0.0736, +0.2562, +0.0251,
+ -0.2438, +0.2509, -0.3281, +0.3477, -0.0962, -0.1747, +0.6608,
+ -0.1284, -0.0620, +0.2505, +0.0576, +0.1825, +0.0376, +0.2137,
+ +0.1334, -0.0137, -0.1572, +0.2251, +0.1485, -0.0870, -0.4884,
+ +0.1099, -0.4984, +0.0576, -0.3160, -0.0971, +0.0686, -0.2857,
+ -0.1786, -0.0665, -0.0147, +0.2700, -0.0514, +0.1172, +0.0407,
+ -0.0610, -0.0642, +0.0641, -0.0284, -0.1473, -0.1814, +0.2611,
+ -0.0045, +0.1158, +0.1137, +0.2471, +0.1978, -0.1271, +0.2265,
+ -0.6208, -0.5634, +0.3271, +0.2243, -0.2667, +0.1716, -0.3122,
+ +0.1045, +0.3088, -0.0122, -0.1800, -0.0375, -0.2735, -0.2114,
+ +0.2025, -0.0350, -0.2953, -0.5958, -0.4832, -0.6282, -0.0991,
+ +0.2455, -0.1095, +0.1874, -0.0986, +0.3314, +0.0481, -0.0645,
+ +0.4166, -0.1145, -0.2953, +0.1156, +0.1745, +0.2837, +0.4273,
+ -0.0217, +0.0088, +0.1717, +0.3309, +0.1483, -0.1668, -0.1604,
+ -0.4858, -0.3747, +0.1971, -0.5613, +0.1759, -0.1036, +0.3260,
+ -0.3445, +0.2426, -0.2171, +0.1091, -0.2270, +0.1575, -0.0349,
+ -0.0231, -0.3729, -0.4534, -0.5497, +0.2144, -0.1105, +0.0400,
+ +0.1656, -0.3746, +0.3577, +0.3003, +0.2348, -0.0513, +0.2820,
+ +0.0473, +0.2366
+ ],
+ [
+ -0.1913, +0.1249, -0.1732, -0.2680, +0.0227, -0.2906, -0.0469,
+ +0.2907, -0.2876, -0.0223, +0.2126, +0.0124, -0.1818, -0.0529,
+ +0.2163, +0.5855, -0.4238, +0.1553, -0.3659, +0.1536, +0.2847,
+ -0.1533, +0.0937, -0.0114, -0.3242, -0.3720, -0.0967, +0.0381,
+ +0.1980, -0.2949, +0.5866, -0.7887, +0.4248, -0.8988, -0.2377,
+ +0.0433, +0.0411, +0.3731, -0.0635, -0.2109, -0.2147, -0.6306,
+ -0.3525, -0.4667, -0.0714, -0.0446, +0.1229, +0.1204, -0.0778,
+ +0.3604, +0.3999, -0.2006, +0.1629, +0.2834, +0.1890, +0.0876,
+ -0.2733, +0.4668, +0.1295, +0.6109, +0.6013, +0.1212, +0.1495,
+ -0.1013, -0.0258, +0.0329, +0.0146, -0.2249, -0.1254, +0.0451,
+ -0.1161, +0.0509, +0.0342, +0.4697, -0.2697, -0.8005, -0.0243,
+ +0.0727, -0.5215, +0.0011, +0.1684, -0.2429, +0.0306, +0.2113,
+ +0.3269, +0.2809, -0.3176, -0.1760, +0.0876, +0.0676, -0.3935,
+ -0.0752, -0.0276, +0.2095, -0.0323, -0.2302, +0.4134, +0.2879,
+ -0.2407, +0.3646, +0.2311, +0.2115, +0.0899, -0.2074, +0.0238,
+ -0.3053, +0.0006, -0.2911, +0.0807, +0.0398, -0.0187, +0.2942,
+ +0.0755, -0.4258, -0.0959, -0.3400, +0.0590, -0.0067, -0.2461,
+ -0.5850, -0.6598, +0.4854, -0.1813, -0.1474, +0.7169, +0.1375,
+ +0.1376, +0.0359
+ ],
+ [
+ +0.4524, +0.0223, +0.0119, +0.4184, +0.3407, -0.4284, -0.0053,
+ -0.0177, +0.0914, -0.1727, +0.3593, -0.1639, -0.0031, +0.0938,
+ +0.3939, -0.5016, +0.3695, +0.0559, -0.0370, +0.0097, -0.3375,
+ +0.2016, +0.3032, -0.2097, -0.2397, -0.6238, +0.2770, +0.3377,
+ +0.2961, -0.2426, -0.3826, -0.2628, -0.3084, -0.0764, -0.2180,
+ +0.2903, -0.3832, -0.2275, +0.3650, +0.0053, +0.2570, -0.0952,
+ -0.0308, -0.0060, +0.1119, -0.0977, +0.0164, +0.1121, -0.2184,
+ -0.1349, -0.2883, -0.0804, +0.2702, -0.2342, +0.2967, +0.3763,
+ -0.0868, +0.2934, -0.2347, +0.3500, +0.1751, -0.4036, -0.1235,
+ +0.3100, +0.0484, -0.4195, -0.2837, -0.3306, -0.3631, +0.0059,
+ +0.2298, +0.0809, +0.3639, -0.0795, -0.3863, +0.1088, +0.1869,
+ -0.1940, +0.4728, -0.0070, +0.1099, -0.1665, +0.2909, +0.3550,
+ -0.2971, +0.2387, -0.4757, +0.0819, +0.1032, -0.3366, +0.1963,
+ -0.1535, -0.2657, -0.0605, +0.1982, +0.2318, -0.1578, -0.1356,
+ -0.3610, -0.2701, -0.7643, +0.0454, -0.5442, -0.0430, -0.0145,
+ -0.3589, +0.4091, -0.2258, +0.0022, +0.1099, -0.5204, +0.0504,
+ -0.0081, -0.3179, -0.1154, +0.0752, -0.3016, +0.2487, -0.5536,
+ -0.0588, -0.0644, +0.3218, +0.0549, +0.0735, -0.2451, -0.8390,
+ -0.3746, -0.2682
+ ],
+ [
+ -0.0016, -0.0452, +0.1532, -0.7650, +0.0169, +0.1665, -0.1787,
+ +0.1150, -0.0360, +0.0130, -0.1275, -0.2408, +0.3302, -0.4338,
+ +0.0053, +0.4180, +0.1073, +0.1265, -0.1695, -0.0095, +0.3174,
+ -0.1767, -0.1039, +0.1327, +0.2633, -0.2024, -0.1561, +0.0774,
+ -0.0627, +0.1923, +0.1428, -0.1714, +0.1412, -0.7353, -0.2745,
+ +0.5773, -0.1019, -0.1372, -0.2105, -0.2976, +0.2121, -0.2573,
+ +0.2477, +0.0023, +0.1221, -0.1968, +0.5837, +0.1092, +0.1521,
+ +0.0283, -0.1028, -0.4350, +0.6186, +0.2715, -0.2510, +0.2805,
+ -0.3659, +0.1554, -0.5880, -0.1447, -0.3310, -0.1246, +0.0657,
+ +0.0716, -0.3006, -0.1052, +0.3839, +0.1904, +0.4279, -0.0166,
+ -0.0742, +0.1262, -0.4340, +0.4478, +0.0889, +0.5178, -0.1752,
+ -0.2383, +0.0182, -0.4434, +0.2788, -0.4208, +0.0039, +0.5008,
+ +0.1493, +0.0291, +0.0577, -0.2342, +0.1468, -0.4043, +0.0001,
+ +0.2849, +0.3798, -0.1892, +0.0185, -0.4745, +0.3082, +0.0759,
+ +0.0991, +0.2442, +0.2099, -0.1283, -0.2924, -0.2373, -0.6365,
+ +0.5487, +0.1724, -0.1166, -0.0525, -0.2684, -0.1275, -0.1771,
+ -0.1892, +0.3937, -0.0792, -0.6260, +0.0029, +0.1770, +0.2306,
+ +0.2485, +0.0466, -0.0944, +0.0566, +0.1276, +0.1477, +0.0082,
+ +0.2286, -0.1510
+ ],
+ [
+ -0.1199, +0.3643, +0.2857, -0.2871, +0.2386, +0.0583, -0.1731,
+ +0.0074, -0.0773, -0.1434, +0.3898, -0.5540, +0.0593, -0.3754,
+ -0.2622, +0.3060, -0.1933, -0.0526, -0.1061, -0.0014, -0.6364,
+ -0.2215, -0.3393, +0.2105, +0.1445, -0.2767, +0.0421, -0.2355,
+ -0.1554, +0.3102, -0.1943, +0.0001, -0.3861, +0.0041, -0.0981,
+ +0.4100, +0.0132, +0.1019, -0.0265, +0.2601, -0.5624, -0.2934,
+ +0.3179, +0.5419, -0.0551, +0.0878, -0.7451, +0.3718, +0.0703,
+ -0.0895, +0.0483, -0.0379, -0.0465, +0.0353, -0.1371, -0.3223,
+ +0.2306, -0.2298, +0.0244, +0.2445, -0.3638, +0.0880, +0.1780,
+ +0.0115, +0.2871, +0.0781, -0.2232, -0.0586, +0.0061, +0.5511,
+ -0.0018, +0.0148, -0.0773, -0.0519, +0.0476, +0.2574, -0.5450,
+ -0.1663, +0.2035, -0.0355, +0.2185, +0.0480, +0.1931, +0.0432,
+ +0.2283, -0.2709, +0.2036, +0.1182, -0.0344, +0.2057, +0.3461,
+ +0.0326, +0.2119, +0.1630, +0.1640, -0.3767, +0.0827, +0.3805,
+ -0.1525, +0.1811, +0.0695, -0.2068, +0.2242, -0.0237, +0.2619,
+ +0.0086, +0.3502, +0.1682, +0.1652, +0.1989, -0.4398, -0.2614,
+ +0.0829, -0.0355, +0.1752, -0.1772, -0.0422, -0.4577, -0.1499,
+ -0.3355, +0.0394, +0.2369, +0.1219, +0.2975, -0.4451, -0.3666,
+ -0.0082, +0.1522
+ ],
+ [
+ +0.1437, +0.1224, -0.3918, -0.0514, +0.0086, -0.7202, -0.1270,
+ +0.1309, +0.1368, -0.9251, -0.1310, -0.1672, -0.0649, +0.2541,
+ +0.3051, +0.2231, +0.0904, -0.4305, -0.2895, +0.2720, -0.0440,
+ -0.0308, +0.1066, +0.0813, -0.1520, +0.0280, -0.1259, -0.0510,
+ -0.6828, +0.0160, +0.1415, +0.1845, +0.3022, -0.4259, +0.0890,
+ -0.3119, -0.4578, -0.1781, -0.0130, -0.0715, -0.1318, -0.1111,
+ +0.2490, +0.0330, +0.0753, -0.2763, -0.0104, -0.2097, -0.0717,
+ +0.0752, +0.0167, +0.1028, +0.0059, -0.1039, -0.3831, +0.2080,
+ -0.1394, -0.1861, -0.5240, -0.1540, -0.0547, +0.1486, +0.0644,
+ -0.7054, +0.0501, -0.1106, +0.2911, -0.4076, +0.0784, +0.2586,
+ -0.5799, -0.0241, +0.1035, +0.4729, -0.2316, +0.0955, +0.1980,
+ +0.2074, +0.1257, +0.1966, -0.0541, -0.5537, +0.1174, +0.0074,
+ +0.4825, +0.2543, -0.2226, +0.3017, -0.6206, +0.1855, -0.1653,
+ +0.1181, -0.2842, -0.1470, -0.1760, -0.0710, +0.1804, -0.0457,
+ -0.8516, +0.2589, +0.2182, +0.4728, -0.1165, -0.4510, +0.2497,
+ -0.2057, +0.2234, -0.0425, +0.4023, +0.0146, +0.1678, -0.0695,
+ +0.2158, -0.0381, -0.1743, +0.1496, -0.1089, -0.0381, -0.1673,
+ +0.4718, -0.2082, -0.6251, -0.2411, +0.3403, -0.2797, -0.0130,
+ -0.3459, -0.1456
+ ],
+ [
+ +0.0733, -0.0360, +0.1024, +0.0427, -0.3455, -0.0165, +0.2678,
+ -0.3823, -0.0074, -0.2066, -0.0813, +0.1675, +0.0614, -0.0818,
+ -0.0098, -0.3373, -0.0009, -0.1579, +0.2214, +0.3661, -0.3002,
+ -0.1751, +0.0850, +0.0664, -0.7089, -0.0570, -0.6223, -0.0760,
+ -0.2579, +0.1160, -0.4883, -0.3417, +0.1093, -0.3465, -0.1029,
+ +0.0323, -0.0124, +0.1743, +0.2238, +0.2200, +0.2838, +0.0199,
+ +0.1371, +0.2527, -0.1738, -0.0343, -0.0504, +0.1290, -0.2154,
+ +0.3672, -0.0281, +0.4991, +0.5160, -0.0292, +0.2712, -0.0429,
+ +0.0020, +0.3000, +0.1499, +0.3555, -0.3632, +0.5845, +0.1193,
+ +0.0651, -0.3064, -0.2260, +0.0438, -0.3252, -0.2209, +0.0876,
+ -0.2948, -0.3681, -0.0442, +0.1585, +0.4002, -0.1729, -0.0857,
+ +0.0738, +0.1218, -0.2164, +0.1597, +0.0583, -0.3370, +0.4479,
+ -0.0440, +0.2751, -0.1229, -0.5297, +0.0170, +0.1326, -0.1707,
+ -0.1165, +0.0453, +0.0743, -0.1221, -0.0458, +0.0028, +0.0599,
+ -0.5900, +0.0896, -0.4746, -0.2719, +0.0281, +0.0356, +0.2661,
+ -0.0380, +0.1702, -0.0690, -0.1933, +0.0336, +0.0947, +0.0578,
+ -0.6923, -0.1154, -0.4010, +0.0136, +0.1166, +0.0909, -0.2182,
+ -0.1437, +0.2823, +0.0751, -0.4068, +0.0748, -0.0749, +0.2066,
+ -0.0593, +0.0359
+ ],
+ [
+ +0.1265, -0.0627, +0.2708, -0.2773, +0.1730, +0.0656, -0.4082,
+ -0.1399, -0.0302, -0.0061, -0.2213, -0.7247, -0.3789, +0.1175,
+ +0.1405, +0.0403, +0.0540, -0.4520, -0.1542, +0.1201, +0.3539,
+ -0.3941, -0.3645, +0.3899, -0.1617, +0.3308, -0.0598, +0.0362,
+ +0.2295, +0.0053, +0.3446, -0.4717, -0.2345, -0.4764, +0.1418,
+ -0.2275, -0.3499, -0.0334, -0.0724, +0.0027, -0.2637, +0.2906,
+ +0.2269, +0.2278, +0.0008, -0.3168, -0.2358, +0.1961, -0.1241,
+ -0.0219, -0.2630, -0.5756, -0.1580, -0.0458, -0.0436, -0.0687,
+ +0.1328, +0.0779, -0.2274, -0.2464, -0.4239, +0.2344, -0.2781,
+ -0.0248, -0.1314, -0.0011, +0.1282, -0.2285, -0.0377, +0.4072,
+ -0.0057, +0.1904, +0.2026, -0.0776, -0.2365, +0.0172, +0.3016,
+ -0.2762, +0.1806, -0.3418, -0.4736, -0.1129, -0.0965, +0.0512,
+ -0.1640, -0.5656, +0.3251, -0.0625, +0.2431, -0.7916, +0.4731,
+ +0.1314, +0.3754, +0.2090, -0.0308, -0.6271, +0.1037, -0.0316,
+ +0.5101, +0.2145, -0.0424, -0.0907, -0.2650, +0.0871, -0.5630,
+ +0.3257, -0.2033, +0.0002, +0.0630, -0.1801, +0.1567, +0.0362,
+ -0.2026, -0.1676, +0.2884, +0.0877, +0.3338, +0.1547, +0.1157,
+ -0.1227, +0.0091, -0.2324, -0.2646, +0.1589, +0.1033, +0.2009,
+ +0.1363, +0.2472
+ ],
+ [
+ +0.3672, -0.0901, +0.1674, +0.1741, -0.2490, +0.0575, +0.3177,
+ -0.5621, +0.0752, -0.4964, +0.0001, -0.1637, -0.2243, -0.4065,
+ +0.0050, -0.7852, -0.0936, -0.2096, +0.0598, +0.2685, +0.4182,
+ -0.3412, +0.3916, +0.0203, +0.1744, +0.0933, +0.3562, -0.3311,
+ +0.0469, -0.2780, -0.3809, -0.5812, -0.4755, +0.3753, -0.0527,
+ -0.5474, -0.3383, +0.2383, -0.1474, -0.2493, +0.2020, +0.1638,
+ +0.0508, +0.2289, +0.0218, -0.2402, -0.0091, -0.1547, +0.3674,
+ +0.4758, +0.2179, -0.1136, -0.2481, -0.3880, -0.1108, -0.0173,
+ -0.0563, +0.0266, -0.3333, +0.0366, +0.1629, +0.0646, +0.1936,
+ +0.1930, +0.1110, +0.2076, -0.1780, -0.1180, +0.1521, -0.0950,
+ -0.0727, -0.0017, +0.3475, -0.0342, -0.0499, -0.5500, -0.0339,
+ +0.1342, +0.3349, -0.1089, +0.5189, +0.0124, +0.0046, -0.4442,
+ -0.1642, +0.2013, -0.0279, +0.0108, +0.1346, +0.4585, +0.1802,
+ +0.3017, -0.2408, -0.0645, +0.4384, +0.0099, +0.4344, +0.4860,
+ +0.1790, -0.2444, -0.3877, -0.0284, -0.0566, +0.1372, -0.3824,
+ -0.6377, -0.0628, -0.0398, +0.1073, +0.3323, -0.0827, +0.0376,
+ -0.0416, +0.1855, -0.2737, -0.2940, -0.4861, +0.1553, +0.2175,
+ -0.1099, -0.2827, +0.0182, +0.0924, -0.0093, -0.6144, +0.1743,
+ +0.0977, +0.1084
+ ],
+ [
+ -0.3080, +0.0907, -0.1649, +0.3318, +0.2758, +0.0320, -0.2480,
+ +0.0117, -0.3531, -0.0572, -0.2509, +0.0474, +0.3281, -0.1668,
+ +0.0472, +0.2543, -0.0862, +0.0207, +0.1018, +0.2401, +0.2810,
+ +0.4449, -0.2407, -0.4852, -0.1038, -0.0502, +0.4901, +0.1284,
+ -0.3240, -0.6291, +0.3866, +0.0484, +0.3418, -0.0835, +0.3512,
+ +0.2007, +0.3187, +0.2226, -0.2257, +0.3427, -0.2731, -0.4103,
+ -0.2178, -0.4763, +0.0986, +0.2132, -0.2027, -0.0528, +0.1876,
+ +0.1881, -0.0998, -0.0737, +0.1540, +0.0492, -0.0989, +0.1285,
+ +0.0750, -0.4498, +0.0803, -0.3685, -0.0318, -0.0641, -0.2312,
+ -0.0639, +0.0131, -0.2716, -0.0166, +0.0095, -0.0550, +0.2155,
+ -0.1151, +0.0280, -0.5577, +0.2472, -0.1704, -0.4050, -0.5706,
+ +0.1635, -0.3534, +0.2263, +0.1519, -0.2761, -0.2593, +0.3671,
+ -0.3879, +0.1204, +0.2487, +0.4244, +0.1836, -0.2578, -0.0479,
+ -0.1153, +0.1945, -0.0349, -0.2565, -0.3167, -0.2075, -0.3321,
+ -0.0222, +0.2474, -0.4006, -0.0428, +0.0766, -0.0910, +0.1290,
+ -0.1410, -0.2871, +0.1620, -0.2337, -0.0841, -0.4411, -0.0992,
+ -0.0288, +0.1999, +0.0152, +0.1243, +0.0414, +0.3242, -0.4499,
+ -0.0982, -0.1245, -0.5705, -0.1811, -0.2595, +0.1088, -0.1888,
+ -0.2619, +0.2435
+ ],
+ [
+ +0.2564, -0.5431, -0.5082, +0.3797, -0.1371, -0.1407, +0.2606,
+ -0.3532, +0.1148, +0.0348, -0.6669, +0.5390, -0.0679, -0.6189,
+ -0.1997, +0.1223, -0.3101, +0.0410, -0.0733, -0.1994, -0.2091,
+ +0.3170, -0.8236, -0.2025, -0.3470, -0.0958, +0.1701, +0.0633,
+ +0.4095, -0.2781, +0.0751, -0.1107, +0.0279, -0.3456, -0.3023,
+ -0.1047, +0.4750, +0.1992, +0.0064, -0.3119, -0.0697, +0.0908,
+ -0.0153, +0.3006, +0.1023, +0.0865, -0.3193, -0.2363, -0.0379,
+ -0.0737, -0.1497, -0.1821, -0.4256, +0.1869, -0.0092, -0.5244,
+ +0.2473, -0.0994, -0.4700, +0.0160, +0.0074, +0.1139, +0.2407,
+ +0.0043, -0.2212, +0.1343, -0.0217, +0.2449, +0.0947, +0.3478,
+ -0.0248, -0.0637, +0.1599, +0.1110, +0.3378, +0.1366, -0.0477,
+ -0.1392, -0.0558, -0.0633, +0.1529, -0.0403, +0.1934, -0.3078,
+ +0.0564, +0.0266, +0.2551, -0.4909, -0.1975, -0.0311, -0.1966,
+ +0.0851, -0.0700, +0.3483, -0.3742, -0.0266, -0.0608, +0.3700,
+ -0.0319, -0.3136, -0.0212, +0.4177, -0.1627, -0.1911, -0.0261,
+ +0.0379, -0.7147, -0.1136, +0.0332, +0.2362, +0.2517, +0.0570,
+ +0.1935, -0.0097, +0.3102, +0.3422, -0.1285, +0.2687, +0.1173,
+ -0.1157, +0.2377, -0.2715, -0.1053, +0.1276, +0.5240, -0.3129,
+ +0.0906, +0.2394
+ ],
+ [
+ +0.0182, -0.1299, -0.0132, -0.0445, +0.0434, -0.1050, +0.2383,
+ -0.0531, -0.0667, +0.0269, -0.1853, +0.1164, +0.0166, -0.0413,
+ -0.0896, -0.0977, +0.1889, +0.3095, +0.0361, -0.2056, +0.3806,
+ -0.0326, -0.5333, +0.1189, +0.1859, -0.1565, +0.0555, -0.3661,
+ -0.8639, -0.2448, -0.0557, -0.0534, +0.0042, -0.5713, +0.5114,
+ +0.4660, +0.0137, -0.1421, +0.0979, -0.2005, +0.2329, +0.2130,
+ +0.1805, -0.1600, +0.2769, +0.2827, -0.1460, +0.1061, +0.0854,
+ -0.0310, +0.1183, +0.2273, +0.0824, +0.2282, +0.0108, -0.2525,
+ +0.0771, -0.1526, -0.0139, +0.0269, -0.5221, -0.3769, -0.2342,
+ -0.0453, +0.2171, +0.2046, +0.4883, +0.0497, +0.2218, +0.2181,
+ +0.1806, +0.0522, +0.1161, -0.1453, +0.3688, -0.2118, -0.4573,
+ +0.1621, +0.0019, +0.0855, +0.0834, -0.1672, -0.3092, +0.0172,
+ +0.0616, -0.3783, +0.1639, -0.1543, -0.1446, -0.5286, +0.1300,
+ -0.0023, +0.3224, +0.4647, +0.0172, +0.2039, -0.2361, +0.1141,
+ -0.1565, +0.2557, +0.2248, +0.2834, +0.1647, +0.1474, +0.0831,
+ -0.1383, +0.3499, +0.0644, -0.0408, +0.0691, -0.1987, -0.1009,
+ +0.1492, -0.7122, +0.2109, -0.2153, -0.1362, +0.3380, +0.3956,
+ -0.3061, -0.0537, -0.1554, +0.0221, -0.0772, +0.2158, -0.1286,
+ -0.0206, -0.7828
+ ],
+ [
+ -0.4612, -0.7768, -0.1705, -0.1334, +0.1252, +0.2581, -0.0253,
+ +0.3918, -0.0171, -0.2106, -0.0601, +0.0502, +0.2695, -0.4787,
+ +0.1919, +0.1659, -0.5232, -0.4664, +0.5166, -0.0030, +0.2659,
+ +0.0514, +0.2924, +0.1007, +0.2972, +0.1873, +0.2086, -0.1280,
+ +0.3712, +0.3357, +0.0716, +0.2718, -0.4366, +0.0580, +0.0064,
+ -0.0801, +0.1128, +0.3085, +0.6918, +0.0245, -0.2338, +0.0123,
+ -0.4176, -0.2340, +0.0233, -0.2649, -0.0671, +0.0879, +0.1039,
+ -0.0559, +0.0625, -0.0018, +0.1866, -0.1498, -0.1005, +0.3043,
+ -0.4272, -0.2103, -0.2707, +0.3701, +0.0207, -0.1693, +0.1511,
+ +0.0725, -0.1867, -0.6037, +0.0822, +0.2406, -0.2614, -0.0230,
+ -0.2334, -0.3113, -0.1930, -0.1664, -0.2398, -0.3514, -0.2636,
+ -0.1754, +0.1389, +0.0401, +0.0478, +0.0277, -0.0695, -0.0086,
+ -0.1618, +0.2286, -0.1440, +0.1581, -0.0142, +0.2421, -0.0396,
+ -0.3297, +0.1494, -0.3490, +0.0522, +0.1803, +0.2010, -0.0700,
+ -0.1020, +0.0126, +0.0985, +0.4564, -0.9869, +0.4354, +0.1019,
+ -0.2100, +0.0896, -0.0418, -0.1470, -0.6701, -0.1253, -0.0466,
+ -0.5191, +0.0922, -0.1019, +0.1983, -0.1689, +0.0613, +0.1169,
+ -0.0128, -0.4549, +0.2831, +0.1717, +0.1657, +0.6473, -0.0489,
+ +0.4133, +0.1272
+ ],
+ [
+ -0.1649, +0.3595, -0.1018, -0.2451, -0.1059, -0.2183, +0.0321,
+ +0.2026, +0.3835, -0.4291, -0.1033, +0.0628, -0.0075, +0.3700,
+ -0.0673, -0.3885, -0.2072, +0.0783, +0.0155, -0.1216, +0.1363,
+ +0.2228, -0.4028, -0.3663, +0.2848, -0.2209, -0.1416, -0.3134,
+ -0.0327, -0.0167, -0.0050, +0.1597, -0.0961, -0.2168, -0.1929,
+ -0.4492, -0.0239, -0.0554, +0.3182, -0.2570, -0.0276, -0.2450,
+ +0.1675, -0.1146, +0.0406, +0.0083, +0.3763, +0.3331, -0.1138,
+ -0.0384, -0.1075, -0.1307, +0.7358, -0.0440, +0.0448, -0.8095,
+ +0.1581, -0.2983, -0.2206, +0.1737, +0.0761, +0.1185, +0.3687,
+ +0.0213, -0.7444, -0.2477, -0.0400, -0.1679, -0.1437, -0.1774,
+ +0.0707, -0.3777, -0.0090, -0.2117, +0.2812, +0.1159, -0.1425,
+ -0.4042, -0.0190, -0.4525, +0.0406, +0.0125, -0.0717, -0.0850,
+ +0.5492, -0.2095, -0.2514, -0.0894, -0.1617, +0.1320, +0.5583,
+ +0.0113, +0.1968, -0.7115, -0.1437, -0.1520, -0.4391, +0.2490,
+ -0.0100, -0.2297, +0.0209, +0.1460, -0.3519, -0.0173, -0.0711,
+ -0.1591, -0.3104, +0.1723, +0.0971, +0.0788, +0.3080, -0.2091,
+ -0.0183, +0.4434, +0.1019, +0.0348, -0.2908, +0.2420, +0.5102,
+ +0.2919, -0.0464, +0.0460, +0.0233, +0.1660, -0.1202, -0.2951,
+ +0.1735, -0.0185
+ ],
+ [
+ +0.1634, -0.3169, -0.1324, +0.0502, -0.6239, +0.0555, +0.0211,
+ +0.0921, -0.0013, -0.1419, +0.0632, +0.2059, +0.1216, -0.0172,
+ +0.3665, -0.0805, -0.0796, +0.2272, +0.0931, +0.2847, +0.2629,
+ -0.2724, -0.4270, -0.3100, +0.2210, +0.4631, +0.3028, -0.2282,
+ +0.1676, -0.6001, +0.0974, +0.1097, -0.0096, +0.2315, +0.0054,
+ +0.1062, +0.1074, +0.3050, -0.5204, -0.2651, -0.6917, +0.1531,
+ -0.0189, +0.0602, +0.0373, +0.3394, +0.1720, +0.1038, +0.1990,
+ -0.0107, +0.3361, +0.2242, +0.2207, -0.1006, -0.1221, -0.4280,
+ -0.0186, -0.7557, -0.0749, -0.2288, -0.0474, +0.0275, +0.0316,
+ -0.1601, +0.0462, +0.0927, -0.3655, -0.1558, -0.3117, +0.0820,
+ -0.0712, -0.7471, +0.4260, +0.2970, -0.2324, +0.1872, -0.2711,
+ -0.4186, +0.2332, -0.4264, +0.2156, -0.4412, +0.1897, +0.0445,
+ -0.2522, +0.0740, -0.3054, -0.1679, +0.0561, +0.0893, +0.1132,
+ +0.3704, -0.0683, +0.1545, -0.1077, -0.0547, +0.0933, +0.1020,
+ +0.2662, -0.6865, +0.0276, -0.2674, +0.0357, -0.3108, -0.4783,
+ +0.2114, -0.1678, -0.1909, +0.1531, +0.0703, -0.4706, +0.1802,
+ -0.0411, -0.2016, +0.0814, +0.1414, -0.3811, +0.0172, -0.1926,
+ +0.0396, +0.0064, +0.0637, +0.4441, -0.2017, +0.2727, +0.0266,
+ -0.6768, -0.1469
+ ],
+ [
+ -0.4334, +0.4022, +0.3103, -0.0775, +0.3432, +0.2280, +0.2167,
+ +0.0161, -0.0377, +0.3427, +0.1773, -0.0010, +0.0084, -0.3900,
+ +0.0397, -0.2535, -0.3968, +0.0300, -0.0638, -0.3266, +0.0582,
+ -0.3348, +0.3936, -0.2502, -0.0383, -0.2508, -0.1750, +0.1348,
+ +0.3072, -0.0949, +0.0587, -0.4842, -0.2063, +0.3357, -0.3240,
+ +0.4859, +0.2623, +0.2962, -0.2773, -0.0593, +0.1301, +0.2364,
+ +0.3923, +0.0414, -0.4935, -0.0941, -0.3768, +0.3842, -0.0718,
+ +0.0742, -0.0573, -0.4293, +0.0743, -0.2978, -0.0422, +0.1087,
+ -0.4377, -0.3464, -0.0827, +0.0915, +0.0008, +0.3214, -0.1166,
+ -0.0198, -0.1859, -0.2302, -0.2074, -0.0078, -0.2070, +0.0302,
+ +0.1794, -0.0882, +0.0121, -0.2374, -0.1987, -0.3892, -0.4104,
+ -0.0611, +0.1686, +0.0921, -0.4782, -0.3420, -0.8396, -0.3065,
+ +0.0760, +0.1691, -0.2897, -0.1100, +0.4519, -0.6548, +0.3574,
+ -0.2755, -0.3936, -0.0137, -0.0957, +0.3792, +0.1755, -0.0097,
+ -0.2697, -0.0520, -0.1111, +0.0483, +0.0760, -0.2787, -0.0091,
+ -0.0703, -0.0605, -0.4374, -0.0477, +0.2326, +0.0533, -0.4199,
+ -0.1989, +0.0147, -0.1653, +0.1292, -0.1568, +0.3050, -0.0993,
+ -0.0980, +0.1212, -0.0170, +0.0798, -0.3524, -0.0280, -0.0236,
+ -0.1151, +0.1826
+ ],
+ [
+ -0.2467, +0.1172, -0.0152, +0.0993, -0.2194, +0.1785, +0.0350,
+ -0.1104, -0.3253, -0.6443, +0.1784, +0.0353, -0.0128, -0.2158,
+ +0.1635, -0.2837, +0.2682, -0.1172, -0.2201, -0.0922, +0.3524,
+ +0.2740, +0.3523, +0.0294, -0.1040, +0.5053, -0.0675, -0.1428,
+ -0.2636, -0.1438, +0.0137, -0.1672, -0.0066, +0.3998, -0.0263,
+ -0.0804, +0.1891, +0.3853, -0.0451, +0.0422, +0.0247, -0.0488,
+ -0.2068, +0.2859, -0.3719, +0.3085, +0.3887, -0.1576, +0.2532,
+ +0.0055, +0.3574, -0.0552, +0.0684, -0.3958, -0.0227, -0.0263,
+ +0.3915, -0.0799, -0.0883, -0.2491, +0.3389, -0.1571, -0.0407,
+ +0.3617, -0.0372, -0.1463, -0.1914, +0.0403, -0.3653, -0.2513,
+ +0.2132, -0.4592, +0.2080, +0.0221, +0.1709, -0.0067, +0.1605,
+ +0.0515, +0.0210, +0.1372, +0.1040, -0.4406, +0.5372, +0.1172,
+ -0.3725, -0.3438, +0.0618, -0.1765, +0.3595, +0.2272, +0.0550,
+ +0.1535, -0.0240, -0.1351, +0.1215, +0.1343, -0.0918, -0.3227,
+ +0.0299, +0.2198, -0.4449, -0.2217, -0.3357, +0.4860, -0.3386,
+ +0.1844, +0.2087, -0.1809, -0.0116, -0.0124, +0.2560, -0.0801,
+ -0.0154, +0.2344, -0.1114, -0.0739, +0.3299, +0.1055, +0.3951,
+ -0.1211, -0.3680, +0.3612, -0.6091, +0.0490, +0.0631, +0.2087,
+ +0.1592, +0.1056
+ ],
+ [
+ +0.2029, +0.0557, -0.0085, -0.3595, -0.1618, -0.1130, -0.0428,
+ -0.1348, -0.2826, +0.1473, -0.1350, +0.1554, -0.0454, -0.5012,
+ -0.4408, +0.1510, +0.1154, -0.2376, +0.2249, +0.0750, -0.4768,
+ +0.5343, -0.1295, +0.0161, -0.5796, -0.2848, +0.2328, -0.4933,
+ -0.2101, -0.1309, -0.6023, +0.1038, -0.2965, +0.2144, +0.3466,
+ +0.0884, +0.3949, +0.1081, +0.4113, -0.0865, -0.2316, -0.1709,
+ +0.2065, +0.0104, +0.0048, +0.1482, +0.0008, +0.0607, -0.3910,
+ -0.1948, +0.1229, -0.2527, -0.3891, -0.0286, -0.2299, -0.3915,
+ -0.0672, -0.0426, +0.3480, +0.3049, +0.0798, -0.2610, -0.4881,
+ -0.4540, -0.0310, +0.0497, +0.1947, +0.0685, -0.1108, +0.1231,
+ +0.0725, -0.1682, +0.4444, -0.4213, -0.5869, +0.4549, -0.1048,
+ +0.1328, -0.4244, +0.1140, -0.3106, -0.0655, +0.2712, +0.1341,
+ +0.2651, -0.0830, -0.0978, -0.2112, -0.1133, +0.1298, +0.0131,
+ +0.5820, +0.0212, -0.0882, -0.0126, +0.0561, +0.0849, +0.0870,
+ -0.2993, +0.0438, +0.1446, -0.4625, -0.4951, -0.2186, -0.1318,
+ +0.1579, -0.2303, -0.2380, +0.1778, +0.5354, -0.4924, +0.2349,
+ +0.0470, -0.3649, -0.5210, +0.0764, +0.0834, -0.4999, +0.0301,
+ -0.1041, +0.0504, +0.0143, -0.1836, +0.2100, -0.6752, -0.2314,
+ +0.4647, -0.1310
+ ],
+ [
+ -0.1335, -0.6320, -0.0721, -0.1399, +0.2147, -0.2856, +0.0098,
+ +0.1405, +0.4249, -0.2522, -0.1856, -0.1044, +0.0052, -0.0444,
+ -0.2619, +0.1746, +0.0588, +0.2658, +0.1085, +0.2029, +0.2338,
+ +0.1926, -0.1297, +0.0238, -0.3790, +0.0980, +0.3171, -0.1165,
+ -0.2144, +0.3379, -0.2969, -0.4162, +0.1183, -0.0417, +0.0213,
+ +0.1795, -0.6973, -0.0106, +0.1144, -0.4240, -0.0772, +0.1514,
+ -0.0282, +0.0907, -0.0655, -0.0164, +0.2066, -0.3083, +0.0271,
+ +0.5376, +0.2761, -0.1558, +0.1819, +0.0723, -0.0501, +0.0505,
+ -0.4723, -0.3211, -0.0367, -0.3155, -0.4286, +0.0182, +0.2657,
+ -0.2361, +0.1894, -0.4548, -0.1447, -0.1170, -0.1283, +0.2184,
+ +0.1186, -0.4415, -0.0122, +0.3546, -0.2868, -0.0750, -0.2940,
+ +0.1859, +0.1716, +0.2779, +0.5894, +0.1930, +0.2021, -0.1281,
+ -0.1225, +0.1017, +0.2843, +0.2552, -0.5806, +0.1193, +0.2005,
+ +0.0839, +0.0274, -0.0806, -0.2124, -0.0267, -0.0070, -0.3080,
+ +0.4123, -0.0053, +0.0142, -0.0142, +0.1642, +0.3051, -0.3333,
+ -0.1631, -0.0933, +0.1235, +0.2134, +0.0818, -0.3749, -0.2464,
+ -0.0994, +0.1438, +0.5946, -0.5342, -0.2824, +0.2526, -0.0492,
+ +0.2793, -0.0208, -0.0858, +0.2623, +0.2215, -0.1924, -0.0963,
+ -0.2523, -0.0009
+ ],
+ [
+ -0.0965, -0.2704, +0.3668, +0.0120, +0.1126, +0.0029, -0.0023,
+ -0.0716, +0.0513, +0.1389, +0.3988, -0.2024, +0.0216, +0.0985,
+ +0.1697, -0.5774, -0.4878, -0.1582, -0.2562, -0.0928, +0.2712,
+ +0.0256, +0.0846, -0.3739, -0.0232, +0.2041, -0.1263, -0.1368,
+ -0.2477, +0.4192, -0.2340, +0.1585, +0.2562, +0.0991, +0.2600,
+ +0.1384, -0.1755, +0.1171, -0.4825, +0.2500, +0.3398, -0.1792,
+ -0.1377, -0.0633, -0.3367, -0.0944, -0.3369, -0.0393, -0.0290,
+ +0.1388, -0.3144, -0.5235, +0.0624, +0.2081, -0.1346, +0.3517,
+ -0.1641, -0.2767, +0.3720, +0.1985, -0.5782, -0.0537, +0.2983,
+ +0.2773, +0.2039, +0.3844, -0.0659, -0.1036, +0.1812, +0.0295,
+ -0.1573, -0.1218, +0.2601, -0.5374, +0.0723, +0.2074, +0.0874,
+ -0.3085, -0.4962, -0.1246, +0.2095, +0.1047, +0.1184, -0.3327,
+ +0.2405, +0.4445, -0.0445, +0.0202, -0.3354, -0.3245, -0.0287,
+ +0.0117, -0.3978, +0.2340, +0.1290, -0.1872, +0.2734, -0.2626,
+ +0.2791, +0.2888, +0.4021, +0.1303, +0.2716, -0.0656, +0.1747,
+ -0.2927, -0.0966, -0.3251, +0.1773, -0.0566, -0.7090, +0.0475,
+ -0.2062, +0.1276, +0.1696, -0.0822, +0.3346, +0.0305, +0.0433,
+ +0.1581, +0.2455, +0.7108, -0.0827, +0.0132, +0.0526, +0.0960,
+ -0.5570, +0.1225
+ ],
+ [
+ +0.0388, -0.0636, +0.1128, -0.7107, +0.0510, +0.0457, +0.2695,
+ +0.0538, +0.0499, -0.3330, -0.1929, -0.0447, -0.3854, -0.0374,
+ +0.1305, +0.0504, +0.2096, -0.1844, -0.0142, -0.1926, -0.5354,
+ +0.0787, -0.1043, +0.3655, -0.4451, -0.5379, +0.0621, +0.2261,
+ +0.0861, +0.0017, -0.3028, +0.3339, -0.0214, -0.3797, -0.0736,
+ -0.2597, -0.2715, -0.1934, +0.0972, +0.0316, +0.1169, -0.1531,
+ -0.1452, -0.2641, +0.4219, +0.0188, -0.0380, -0.1284, +0.3214,
+ -0.1688, +0.0353, +0.1345, -0.0009, -0.3808, -0.2310, -0.3112,
+ +0.1768, -0.1447, +0.0555, -0.1069, +0.0140, +0.2427, -0.2623,
+ -0.1330, -0.4790, -0.5952, -0.1756, +0.2288, -0.1291, -0.3195,
+ +0.1972, +0.1825, +0.4229, -0.4074, +0.0268, -0.0891, +0.0307,
+ -0.3039, -0.1674, -0.2262, +0.2759, +0.0243, -0.0882, -0.2424,
+ +0.0466, +0.1849, +0.2599, -0.3188, -0.0019, +0.0316, -0.1839,
+ +0.1146, -0.0135, +0.1848, -0.1582, +0.2988, -0.2181, -0.1353,
+ +0.2797, +0.1535, -0.4733, +0.3432, -0.1280, -0.0376, +0.1161,
+ +0.3127, -0.0292, +0.1098, +0.0416, -0.1454, -0.6312, +0.0712,
+ +0.1358, -0.1406, +0.3819, -0.4414, -0.2037, -0.4202, +0.3249,
+ +0.0824, -0.1337, +0.4004, +0.1487, -0.0552, -0.0084, -0.1390,
+ -0.0482, -0.1248
+ ],
+ [
+ -0.4128, +0.2052, +0.2958, -0.3893, -0.0600, +0.3388, +0.1471,
+ +0.6266, +0.0719, +0.0795, +0.1113, -0.0794, +0.2958, -0.3836,
+ +0.2189, -0.2763, -0.1984, -0.0548, +0.0141, +0.3920, +0.1112,
+ +0.1945, -0.3078, -0.1977, +0.4840, +0.0353, -0.2194, -0.0675,
+ +0.3084, -0.0209, -0.4920, -0.2000, +0.0816, +0.2593, +0.2055,
+ +0.0129, +0.3046, +0.2836, -0.1813, +0.2242, +0.0291, +0.5517,
+ -0.3370, -0.1868, -0.3485, +0.0305, -0.1064, +0.2045, +0.0184,
+ -0.3670, -0.0152, -0.0200, -0.1716, -0.1810, +0.3369, -0.3953,
+ -0.1427, -0.2410, +0.1023, -0.3459, +0.2171, +0.1283, +0.0246,
+ -0.0337, +0.0616, +0.2949, -0.0022, +0.2681, -0.1617, +0.0665,
+ +0.2323, +0.2869, +0.1649, +0.0549, +0.0304, +0.3420, +0.3354,
+ -0.1135, -0.2278, -0.3374, -0.2583, +0.1136, -0.0953, +0.4171,
+ -0.0457, -0.2206, -0.0775, +0.5886, -0.3775, -0.0945, -0.1287,
+ -0.0535, -0.1528, -0.2011, +0.3860, +0.0621, +0.3707, +0.2414,
+ +0.2101, +0.2129, +0.0745, +0.2882, -0.0609, +0.0956, +0.6585,
+ +0.2371, +0.3142, +0.3645, -0.3500, +0.4032, -0.1893, +0.3913,
+ -0.1542, +0.5176, -0.2579, +0.1003, +0.0392, -0.0504, -0.0099,
+ +0.1852, -0.6551, +0.5900, +0.0159, -0.3024, +0.0359, -0.0668,
+ +0.5517, -0.1909
+ ],
+ [
+ +0.3670, -0.2043, -0.3874, +0.1384, -0.3181, -0.3793, +0.4070,
+ -0.0632, -0.0811, -0.4977, -0.1542, +0.2034, +0.0090, +0.0183,
+ +0.1164, +0.1852, +0.0746, +0.2922, -0.5590, -0.1761, -0.0964,
+ +0.0395, -0.1406, +0.4059, -0.2998, -0.0835, +0.0505, -0.2801,
+ -0.3259, -0.1370, -0.0225, -0.1448, -0.2951, +0.0185, +0.1420,
+ -0.0444, +0.0485, +0.1125, +0.0880, +0.0358, +0.1630, +0.0944,
+ -0.0179, -0.0282, +0.0427, +0.1591, -0.2212, -0.0059, -0.2907,
+ +0.3376, -0.1032, -0.0613, -0.0754, -0.0883, +0.1277, -0.2644,
+ +0.0250, +0.2450, +0.2345, -0.1500, +0.0214, -0.3306, -0.3280,
+ -0.4140, -0.1308, +0.1845, +0.3871, -0.1751, -0.5124, -0.2345,
+ -0.3059, +0.0198, -0.3429, +0.1973, +0.2410, +0.0830, +0.1969,
+ +0.1841, +0.1586, +0.5007, -0.0386, +0.4823, +0.0990, -0.1071,
+ +0.7270, -0.5509, -0.1579, -0.0578, -0.1482, -0.2949, +0.1369,
+ -0.1196, -0.2340, -0.0337, +0.2561, +0.2443, +0.2854, +0.1953,
+ +0.6365, +0.3849, -0.2038, +0.1991, +0.3220, -0.5066, +0.2866,
+ -0.4086, +0.2213, +0.1634, +0.4147, +0.3091, -0.0201, +0.0549,
+ -0.2503, +0.0361, -0.4524, -0.0050, -0.2277, +0.1714, -0.3072,
+ -0.2726, -0.0663, +0.1505, +0.0956, +0.1795, +0.2184, +0.0895,
+ -0.0352, -0.1389
+ ],
+ [
+ -0.3348, -0.2786, -0.2106, -0.5730, +0.4078, +0.4301, +0.3458,
+ +0.3719, -0.3752, -0.7945, +0.1194, +0.2255, -0.2442, +0.4542,
+ +0.0496, +0.3049, -0.3019, -0.1939, -0.2180, -0.0326, -0.0967,
+ -0.0724, -0.0132, -0.1313, -0.2640, +0.3037, +0.0211, +0.1566,
+ -0.1398, -0.3756, +0.2154, -0.0992, -0.0184, +0.2347, +0.1184,
+ -0.0317, -0.1532, -0.1048, -0.1554, +0.7122, -0.1325, -0.5138,
+ -0.2219, +0.2559, +0.3198, -0.0820, +0.1997, +0.0260, +0.1107,
+ -0.3232, -0.1882, +0.2708, +0.0517, -0.0525, -0.0100, -0.0401,
+ -0.3590, +0.4664, -0.0902, -0.0504, -0.1897, -0.2423, -0.1299,
+ -0.0916, +0.3512, +0.0399, -0.0183, +0.4090, +0.3299, -0.3154,
+ -0.0441, +0.1673, -0.2959, -0.3447, -0.0845, +0.1023, +0.0251,
+ -0.0797, -0.4498, -0.1061, -0.2575, +0.4544, -0.2686, -0.1497,
+ +0.1097, -0.3093, -0.1853, -0.2578, +0.0300, +0.2576, +0.1469,
+ -0.0733, +0.0148, -0.0595, -0.1906, +0.1903, -0.1623, -0.0291,
+ -0.9437, +0.2876, +0.0216, +0.2890, +0.0375, -0.1492, -0.3442,
+ -0.0061, +0.3488, +0.3416, +0.4879, -0.3436, -0.3196, -0.4589,
+ -0.0626, +0.1611, -0.4217, +0.3166, -0.0914, +0.2433, +0.1901,
+ -0.1086, -0.2327, +0.2995, -0.0638, +0.0670, +0.0415, +0.2278,
+ +0.2642, -0.0850
+ ],
+ [
+ +0.4386, +0.0676, -0.2674, +0.1742, +0.1818, -0.0317, +0.1438,
+ +0.3393, +0.2597, +0.1952, -0.0306, -0.3890, -0.1543, -0.3078,
+ -0.0870, +0.1543, -0.3517, -0.0337, -0.3475, +0.0875, -0.1180,
+ -0.8558, +0.2351, -0.3425, +0.2135, -0.3808, -0.5150, -0.1233,
+ +0.2568, +0.3028, +0.2748, -0.1705, +0.0912, -0.3502, -0.0125,
+ -0.2252, +0.0556, +0.0496, +0.0618, +0.4268, +0.1870, +0.2768,
+ +0.3715, -0.2413, -0.3389, +0.3985, -0.1171, -0.1966, -0.1881,
+ +0.2652, -0.3795, -0.1719, -0.5104, +0.4924, +0.3802, +0.0183,
+ -0.0325, -0.2123, +0.1092, -0.2778, +0.0937, +0.1390, -0.0038,
+ -0.2063, +0.3351, -0.1438, +0.2943, -0.1989, -0.5708, -0.2186,
+ +0.2609, +0.0052, -0.0960, +0.0196, -0.0849, -0.2720, +0.2187,
+ +0.1293, -0.1299, -0.1866, -0.0398, +0.1556, -0.0259, -0.0590,
+ +0.0550, -0.3297, -0.0573, -0.1482, -0.3060, +0.1401, +0.1256,
+ +0.3440, -0.1418, +0.0503, -0.4561, +0.2492, +0.3486, +0.1667,
+ -0.0210, -0.0506, -0.0107, -0.3938, -0.2330, -0.0178, +0.0308,
+ +0.1686, -0.1246, -0.0050, -0.0322, -0.1045, -0.4248, -0.1345,
+ -0.0218, +0.1072, +0.2226, -0.0004, -0.2046, +0.2163, +0.2451,
+ -0.2167, -0.3689, +0.0503, +0.0823, -0.4537, -0.1243, -0.2189,
+ +0.0481, +0.0286
+ ],
+ [
+ +0.2334, +0.3500, +0.0662, -0.5046, -0.0597, +0.2471, -0.2703,
+ +0.1399, -0.7505, -0.2562, +0.1958, -0.1235, -0.0242, +0.1839,
+ -0.2893, -0.0599, +0.1254, -0.0912, -0.2353, -0.0842, -0.0949,
+ -0.3746, +0.1217, -0.0073, -0.3354, +0.1315, +0.1889, +0.0823,
+ -0.1858, +0.0864, +0.0734, -0.0304, +0.0318, -0.0612, +0.3508,
+ -0.3706, +0.4253, +0.0354, -0.0071, +0.2244, +0.1871, -0.0562,
+ -0.3139, -0.1369, +0.1179, +0.0226, -0.3849, +0.0362, +0.2879,
+ -0.1569, +0.0192, +0.1190, -0.5616, -0.1535, +0.2427, -0.1210,
+ +0.1751, -0.2340, +0.1810, +0.0469, +0.2542, +0.1152, +0.5797,
+ -0.3496, +0.2892, -0.4287, -0.4724, -0.0397, -0.2464, +0.3701,
+ +0.2956, +0.1254, -0.2646, -0.5452, +0.2122, +0.0656, +0.3347,
+ -0.1340, +0.2442, +0.5514, +0.0956, -0.2359, -0.0320, +0.0060,
+ -0.3456, +0.1637, -0.1336, -0.3153, +0.2063, +0.3379, -0.1048,
+ +0.1892, +0.0051, -0.2549, +0.1573, +0.2851, +0.2117, +0.0171,
+ -0.5138, -0.2967, -0.1822, -0.3411, +0.4851, +0.2196, -0.0956,
+ -0.2143, -0.1333, -0.1878, -0.0897, -0.3669, +0.0232, -0.5985,
+ +0.0040, +0.0890, -0.2406, +0.1359, -0.2536, +0.3302, +0.1070,
+ +0.2824, +0.1760, -0.2326, -0.1464, -0.1637, -0.0883, -0.1651,
+ -0.0040, +0.1147
+ ],
+ [
+ +0.3286, +0.1446, -0.4889, -0.2560, +0.0087, -0.0032, +0.2922,
+ -0.0571, -0.2620, +0.3276, +0.1989, -0.2671, +0.4530, +0.1760,
+ +0.2313, +0.1735, -0.2025, +0.0857, -0.1717, +0.0649, +0.4153,
+ -0.2159, -0.3218, +0.1366, +0.1428, +0.2280, +0.0951, -0.3740,
+ +0.0134, +0.1685, -0.4610, +0.2619, +0.2539, +0.6643, -0.0249,
+ +0.2896, +0.2262, -0.0896, -0.4443, -0.4768, -0.1166, +0.2017,
+ +0.1794, +0.1467, -0.0412, -0.1558, -0.6156, -0.1934, +0.1678,
+ -0.4609, +0.0233, +0.0560, -0.3037, +0.0028, -0.2147, -0.1994,
+ -0.1285, +0.1422, -0.3720, +0.4516, +0.1110, -0.0126, -0.2277,
+ -0.0637, +0.1997, +0.0929, -0.2787, -0.1123, +0.0398, -0.0013,
+ +0.0914, -0.0602, +0.0658, -0.3143, -0.1310, +0.1215, -0.6516,
+ +0.1930, -0.3655, +0.0721, -0.1805, +0.2513, -0.1496, +0.3213,
+ -0.0998, -0.8379, -0.2334, +0.3020, -0.5952, +0.1214, +0.0053,
+ -0.0599, +0.1029, -0.2348, -0.3246, +0.1276, -0.2573, -0.2010,
+ +0.2362, +0.0115, -0.0638, -0.8319, -0.4884, +0.2041, +0.5310,
+ -0.4298, -0.4542, +0.1823, -0.1613, -0.0605, -0.1559, -0.1895,
+ -0.0180, -0.1241, +0.0350, -0.0068, +0.0332, +0.1763, -0.6629,
+ +0.0312, -0.3316, +0.3880, -0.0538, -0.0834, +0.1576, -0.0561,
+ +0.2621, +0.4432
+ ],
+ [
+ +0.0147, +0.2064, -0.1060, -0.1746, +0.2711, -0.0502, -0.0490,
+ +0.0768, -0.2528, -0.1784, -0.0798, +0.1602, -0.0534, -0.1266,
+ -0.0137, +0.0807, +0.1191, +0.1377, +0.3625, -0.2101, -0.2833,
+ +0.4921, -0.0155, +0.2985, -0.1394, +0.0707, -0.1297, +0.2470,
+ -0.1117, -0.2487, +0.2999, +0.3454, +0.6182, -0.1765, +0.2013,
+ +0.3832, +0.1082, +0.2044, +0.1132, +0.2920, +0.1542, -0.0685,
+ +0.2194, -0.6517, +0.4470, +0.0458, -0.5681, -0.3213, +0.0855,
+ -0.0332, -0.0109, -0.3474, +0.1339, -0.1649, +0.1788, -0.0983,
+ +0.0417, -0.2880, +0.0338, -0.2320, -0.1456, +0.3784, +0.0509,
+ +0.4927, +0.2587, -0.4095, -0.4250, +0.1030, +0.1446, -0.2185,
+ -0.5015, +0.0271, +0.1479, -0.1742, -0.1102, +0.1514, -0.4440,
+ +0.2041, +0.0649, -0.1766, -0.6038, +0.0087, +0.3342, +0.2130,
+ -0.2297, +0.0348, -0.2462, +0.0589, -0.1637, -0.2169, +0.0430,
+ -0.0695, -0.1463, +0.1773, -0.2813, -0.2043, -0.3637, -0.0631,
+ -0.5325, -0.1955, -0.2975, -0.0015, -0.7195, +0.2291, -0.2418,
+ -0.2807, +0.1495, -0.3170, -0.0369, +0.2704, +0.2877, -0.1725,
+ +0.1326, +0.0250, -0.6804, +0.2416, +0.1008, -0.4565, -1.0737,
+ +0.0460, +0.4516, +0.3291, -0.2031, -0.0634, -0.2550, +0.0027,
+ +0.1835, -0.0018
+ ],
+ [
+ +0.2131, -0.1562, +0.2594, +0.3605, +0.0794, -0.2570, -0.1648,
+ -0.1512, +0.2541, +0.0463, +0.2055, -0.0796, +0.3198, -0.3074,
+ -0.1550, -0.6142, -0.1965, +0.1646, -0.1567, -0.0085, -0.6113,
+ +0.1408, -0.1080, -0.0539, -0.1120, -0.2428, +0.1481, -0.0837,
+ +0.1244, -0.6752, +0.1054, -0.4174, -0.0913, +0.0177, -0.2791,
+ -0.1516, +0.2192, +0.2722, -0.0131, -0.1560, +0.2537, +0.1266,
+ +0.0385, +0.5191, +0.1330, +0.1316, -0.3468, -0.6043, -0.0150,
+ -0.4329, -0.2545, +0.1611, -0.2530, -0.1260, +0.1557, -0.0315,
+ -0.3780, +0.1580, +0.4637, +0.0735, +0.4587, +0.0042, +0.3587,
+ -0.2023, +0.2841, +0.1234, -0.0320, +0.2958, +0.1814, +0.2309,
+ +0.2298, +0.3475, +0.3997, -0.0162, +0.1529, +0.2248, -0.3285,
+ +0.0518, +0.0312, -0.3026, +0.3310, -0.2357, -0.2514, -0.0588,
+ +0.1067, +0.6822, +0.0420, +0.0773, -0.0075, +0.1280, +0.2329,
+ -0.3757, -0.3127, -0.8525, -0.4980, +0.2605, -0.2104, -0.2117,
+ -0.2872, -0.1171, +0.6722, +0.2380, +0.1887, +0.0774, +0.0733,
+ -0.3621, -0.3701, +0.0127, -0.2220, -0.1010, +0.0380, -0.0259,
+ -0.0563, +0.4471, -0.2937, -0.0447, -0.2557, -0.0682, -0.0725,
+ +0.1128, -0.0947, +0.0128, -0.0694, +0.1380, +0.0983, -0.1230,
+ +0.2008, -0.2720
+ ],
+ [
+ -0.0453, -0.0346, -0.3839, +0.3868, +0.0220, -0.1853, -0.2074,
+ -0.0472, +0.1150, -0.3498, -0.0552, -0.6694, -0.2392, -0.0460,
+ +0.2246, -0.1476, -0.1392, +0.2510, -0.1887, -0.1917, -0.2042,
+ +0.2376, -0.0070, +0.2963, -0.0532, -0.0655, -0.3930, -0.1404,
+ +0.0261, -0.2433, +0.0650, -0.1541, +0.0865, +0.0560, +0.2193,
+ +0.1140, -0.3042, +0.4085, -0.6852, +0.1022, -0.3513, +0.1058,
+ +0.0876, +0.2140, +0.0388, -0.2567, -0.6992, -0.0034, -0.6875,
+ -0.1999, +0.3151, -0.1613, -0.0835, +0.1652, +0.0957, -0.1271,
+ +0.1856, -0.1912, +0.1145, -0.2005, -0.8172, +0.0768, -0.1519,
+ -0.1698, -0.0191, +0.2869, +0.1435, -0.7058, +0.2418, -0.0436,
+ -0.1621, +0.2957, +0.2039, +0.1225, -0.1435, +0.1232, -0.1169,
+ +0.1711, -0.4111, -0.0042, -0.0948, +0.2611, -0.2258, +0.0432,
+ -0.0917, +0.0722, -0.0662, -0.3754, +0.2176, -0.1570, -0.0478,
+ +0.0801, -0.1957, -0.4505, -0.2235, -0.0037, -0.1842, +0.1064,
+ +0.0296, -0.1689, +0.1312, +0.1572, +0.2111, -0.2654, +0.0155,
+ -0.1454, +0.1102, +0.1019, -0.2846, -0.1864, -0.4023, -0.8319,
+ -0.0978, -0.0292, +0.0817, -0.0044, +0.2086, -0.2492, +0.1939,
+ -0.2225, -0.0161, +0.4218, -0.3132, -0.2500, +0.0394, +0.0810,
+ -0.2824, -0.0876
+ ],
+ [
+ +0.0521, +0.0338, -0.3186, -0.1781, -0.0083, -0.1596, +0.2465,
+ +0.0134, +0.0067, -0.1868, -0.1395, -0.1180, +0.1019, -0.2491,
+ -0.0086, -0.1539, +0.3759, +0.1831, +0.2938, -0.2207, -0.0184,
+ -0.6517, +0.0625, +0.1342, -0.0452, -0.2810, -0.3562, +0.3716,
+ -0.2575, -0.2819, +0.1850, +0.2124, +0.5566, -0.2076, +0.2125,
+ +0.1027, -0.2377, +0.0428, +0.2231, -0.0640, -0.2934, -0.3954,
+ -0.3368, +0.3551, -0.1121, +0.0294, +0.0512, -0.0854, +0.0062,
+ +0.1703, +0.1667, +0.0405, +0.1268, -0.1969, -0.3350, +0.3519,
+ -0.2240, -0.1787, +0.0476, +0.5824, -0.2556, +0.0716, +0.2466,
+ -0.5204, +0.1523, -0.1415, +0.0159, +0.0313, +0.0817, -0.2416,
+ +0.2747, -0.5057, +0.1327, -0.0017, -0.0146, -0.0602, +0.1821,
+ +0.1724, -0.2857, +0.1645, -0.2909, -0.2520, +0.2880, -0.0180,
+ +0.3563, +0.3581, -0.3516, -0.1451, +0.2524, -0.2041, -0.5919,
+ +0.1345, -0.3076, -0.2650, -0.2368, -0.1035, -0.4026, -0.0506,
+ -0.2451, -0.2891, -0.0012, +0.0543, +0.0361, -0.4953, +0.2972,
+ +0.5363, -0.1967, +0.2217, -0.0397, -0.0310, -0.2884, +0.0688,
+ +0.1345, -0.2273, +0.0899, -0.0058, -0.2192, -0.7858, -0.2073,
+ -0.3786, -0.1811, +0.0313, +0.5153, -0.0858, -0.6176, -0.3263,
+ +0.0589, -0.3380
+ ],
+ [
+ +0.1447, +0.2487, -0.6313, -0.1172, +0.3038, -0.0346, +0.3458,
+ -0.3545, +0.0515, -0.0315, +0.3545, +0.4222, +0.2183, -0.2905,
+ -0.4228, +0.1554, -0.1838, +0.0974, -0.1378, -0.0138, -0.6740,
+ -0.1164, -0.3584, -0.3029, +0.3508, -0.7293, +0.0589, +0.1094,
+ -0.1223, +0.0556, +0.3249, -0.0600, +0.0921, -0.3111, -0.0515,
+ +0.1411, +0.1957, -0.3911, +0.4253, +0.1002, -0.2081, +0.1676,
+ -0.2270, +0.4213, -0.0185, +0.0843, -0.2100, +0.3430, -0.3339,
+ -0.3463, +0.0952, +0.1126, +0.3449, +0.2709, +0.0589, +0.1621,
+ +0.0565, -0.0319, -0.6499, +0.0244, -0.1855, -0.1559, +0.0487,
+ +0.3415, +0.1673, +0.3028, -0.3281, +0.4202, +0.0914, -0.4351,
+ +0.1292, +0.1558, -0.0536, +0.0330, +0.2806, -0.0259, -0.2538,
+ -0.0138, -0.1472, +0.5026, -0.0253, -0.3732, +0.1224, -0.4254,
+ -0.1082, -0.3270, -0.3147, +0.1014, -0.2948, -0.0454, -0.1176,
+ -0.0191, +0.1183, +0.0991, -0.0198, -0.1597, -0.3980, +0.0045,
+ -0.4451, +0.2247, -0.5023, -0.2342, -0.2534, -0.0949, -0.3167,
+ -0.4225, +0.1585, -0.0170, -0.0155, -0.3302, -0.0495, +0.5261,
+ +0.1370, +0.0982, -0.4810, +0.0509, -0.1396, +0.0714, -0.1373,
+ -0.2343, +0.1735, -0.3991, +0.0299, -0.1299, -0.4131, -0.1460,
+ -0.1579, -0.6897
+ ],
+ [
+ +0.3441, +0.0737, -0.0593, +0.0654, -0.1225, -0.4470, +0.0438,
+ +0.0068, -0.2765, +0.2492, +0.4912, +0.2499, +0.3068, +0.0180,
+ -0.0732, +0.5831, -0.5952, +0.2953, -0.3798, +0.0246, -0.5543,
+ -0.2677, -0.0940, -0.0550, +0.3922, +0.4636, +0.2015, -0.4508,
+ -0.0827, -0.1641, +0.2124, -0.0723, -0.0722, +0.3228, -0.1877,
+ -0.0485, +0.3905, +0.3360, +0.1375, -0.6253, +0.0363, -0.1901,
+ +0.0090, +0.1640, +0.4249, +0.0625, +0.1969, +0.1006, -0.0418,
+ -0.1701, +0.1958, -0.1299, -0.0117, +0.2508, +0.0986, -0.0891,
+ -0.2224, -0.0778, -0.0769, +0.0503, -0.0035, -0.2170, -0.2238,
+ +0.0978, -0.1376, +0.0552, -0.2644, -0.1994, +0.0275, -0.0587,
+ -0.3096, +0.1249, +0.1441, -0.2852, +0.0708, +0.4758, +0.3501,
+ +0.0984, -0.1571, +0.4909, +0.0790, +0.3450, +0.1971, -0.3667,
+ -0.2532, +0.4407, -0.4904, -0.4967, -0.3008, -0.2038, +0.2675,
+ +0.4027, -0.3156, +0.0270, -0.2254, -0.4563, -0.1682, +0.0739,
+ -0.1076, -0.3718, -0.4797, -0.0824, +0.0357, +0.0902, -0.2714,
+ -0.1323, -0.0632, +0.3007, +0.1690, +0.1473, -0.1669, +0.3348,
+ +0.1822, +0.0872, -0.2891, -0.3508, +0.2752, +0.2002, -0.2944,
+ +0.3862, -0.0587, -0.0842, +0.0930, +0.5323, +0.2875, -0.0869,
+ +0.0191, +0.2297
+ ],
+ [
+ -0.6072, +0.1593, +0.2208, +0.2001, -0.2024, +0.4413, -0.0058,
+ -0.1402, -0.0808, +0.1493, -0.0617, +0.2193, +0.1257, +0.2183,
+ +0.1666, +0.1011, -0.0891, -0.0807, +0.1919, -0.2049, +0.4302,
+ -0.2231, +0.0180, +0.5705, +0.1127, -0.8658, +0.2152, +0.2400,
+ -0.0795, -0.1434, -0.0897, +0.0144, +0.2679, -0.0472, +0.3482,
+ -0.1740, -0.1166, -0.0111, +0.2472, +0.0246, -0.4565, +0.1551,
+ -0.1582, -0.5669, +0.2494, -0.1287, -0.1204, +0.0194, +0.2248,
+ -0.1516, +0.0207, +0.1093, +0.0377, -0.0904, -0.3342, -0.1444,
+ +0.0697, -0.7370, +0.0026, +0.3587, -0.3404, -0.1049, +0.1460,
+ +0.2110, -0.0948, +0.0207, -0.5619, -0.0783, -0.1985, -0.1016,
+ +0.4217, -0.1562, +0.0041, -0.1838, -0.2449, -0.0854, +0.0799,
+ -0.0302, +0.1423, +0.3082, +0.3283, -0.0281, +0.0788, +0.0031,
+ +0.0979, -0.2028, +0.1922, -0.2306, +0.3849, -0.0142, +0.1072,
+ -0.0440, +0.2191, -0.0470, -0.0593, +0.1763, +0.3983, -0.1238,
+ -0.1037, -0.1137, +0.2317, +0.0110, +0.0663, -0.0086, +0.3465,
+ -0.1617, -0.1074, -0.0111, -0.1016, -0.1653, -0.5738, -0.1034,
+ +0.0073, -0.3014, +0.1830, -0.5022, -0.1954, +0.2247, +0.3253,
+ -0.5072, +0.1528, +0.1081, +0.1963, +0.2882, -0.1681, -0.3225,
+ +0.1462, -0.1778
+ ],
+ [
+ -0.0621, -0.0065, -0.3092, -0.5112, -0.0462, +0.2084, +0.1376,
+ -0.1595, +0.1336, +0.0280, -0.3018, -0.3498, +0.2132, -0.1355,
+ -0.0954, +0.1179, -0.3046, -0.2161, -0.1197, +0.2271, +0.0295,
+ +0.0027, +0.1243, -0.0162, +0.0080, +0.2658, -0.2266, +0.1659,
+ -0.0576, +0.0842, -0.2875, -0.0643, -0.1392, +0.1416, +0.2400,
+ -0.1915, +0.4021, -0.1661, +0.0662, -0.0546, -0.6020, -0.1279,
+ -0.0794, -0.3350, +0.0300, +0.4654, -0.1535, -0.2146, -0.2576,
+ +0.2092, -0.3546, -0.3744, -0.2862, +0.1899, -0.0562, +0.0341,
+ -0.1427, -0.2849, +0.3981, -0.5012, -0.5592, -0.0965, +0.2206,
+ +0.1673, -0.0776, -0.0799, -0.0701, +0.0430, +0.3948, +0.1132,
+ -0.1944, -0.2089, +0.3454, -0.3165, +0.0127, -0.6068, -0.0567,
+ -0.0150, +0.1678, +0.1062, +0.4325, +0.4888, -0.2010, +0.0061,
+ +0.3314, -0.0006, +0.0562, +0.0097, +0.0471, +0.0274, -0.1399,
+ +0.0915, -0.1559, -0.0540, +0.0179, -0.0970, -0.0034, +0.0097,
+ -0.0536, -0.0886, +0.0977, -0.0228, +0.0384, +0.0912, -0.2899,
+ -0.1391, +0.0680, +0.3766, -0.0591, +0.2232, +0.0645, +0.1108,
+ +0.0218, -0.0100, +0.0267, +0.1913, -0.1655, +0.0788, -0.0509,
+ +0.1814, +0.3006, -0.1914, -0.2365, +0.0325, +0.2767, -0.1839,
+ +0.1656, +0.2733
+ ],
+ [
+ -0.3155, +0.0389, +0.4308, +0.1264, -0.1675, -0.1606, +0.1710,
+ +0.0357, -0.0301, -0.4734, -0.2261, -0.2828, -0.0484, +0.0398,
+ -0.1375, +0.3210, +0.1318, -0.0164, +0.4136, -0.2305, -0.1101,
+ -0.1665, -0.1446, -0.2818, +0.1191, +0.1567, -0.0592, -0.1728,
+ -0.0280, -0.3277, +0.0417, +0.0186, +0.1433, -0.2331, +0.3428,
+ -0.2597, -0.2454, +0.2911, +0.3652, -0.4929, -0.3262, -0.0204,
+ -0.0260, +0.0530, +0.0388, +0.3999, -0.2114, -0.1950, +0.1543,
+ +0.3246, +0.0052, +0.0575, -0.3312, +0.2627, +0.2212, -0.1697,
+ -0.1365, +0.1331, +0.5793, -0.0025, -0.4241, -0.0567, -0.1132,
+ +0.0464, -0.1080, +0.0713, -0.3824, -0.1196, -0.0296, -0.1167,
+ +0.2810, -0.0735, -0.0077, +0.0522, -0.6794, -0.3256, +0.2814,
+ +0.2920, -0.1246, -0.1849, +0.1548, -0.0411, -0.2095, -0.3796,
+ +0.2976, -0.0762, -0.2796, +0.1759, -0.1947, -0.3021, +0.0684,
+ -0.4101, +0.2244, -0.2481, -0.0010, +0.1781, +0.1309, +0.0754,
+ -0.0103, +0.3149, -0.0591, -0.3657, +0.3807, -0.0334, -0.0809,
+ -0.3037, +0.1025, -0.2377, +0.1171, -0.3675, +0.0805, -0.0576,
+ +0.2433, +0.1461, +0.0423, -0.2294, -0.0224, -0.3102, +0.0088,
+ -0.3047, +0.3373, +0.3147, -0.3534, -0.3323, +0.1021, +0.1079,
+ -0.2814, +0.1050
+ ],
+ [
+ -0.0245, -0.3205, -0.0550, -0.1720, +0.1572, -0.3884, -0.3543,
+ +0.3351, -0.0099, +0.3584, +0.1196, -0.1128, -0.2587, +0.0681,
+ -0.0158, +0.1732, -0.4172, -0.3108, +0.0267, +0.1163, -0.1939,
+ -0.3101, -0.0248, +0.0025, -0.1209, -0.2918, +0.0999, -0.2748,
+ -0.4083, +0.1218, +0.0835, -0.0999, +0.3580, +0.0629, +0.0313,
+ -0.1036, +0.1496, +0.0291, -0.0168, +0.0395, -0.3607, -0.0815,
+ +0.2716, +0.0342, -0.0334, +0.2555, +0.1654, +0.2385, -0.7064,
+ +0.2392, +0.1459, -0.0964, -0.3108, +0.1539, -0.0590, -0.6246,
+ -0.1621, -0.0648, +0.3419, -0.3539, -0.1544, +0.0877, -0.2943,
+ -0.0809, +0.2675, +0.0130, +0.0175, -0.2230, +0.0429, -0.1819,
+ -0.0576, +0.1783, -0.4099, +0.2766, -0.0295, -0.1116, +0.0644,
+ +0.3015, -0.1678, -0.0302, -0.1903, -0.0368, +0.1126, +0.0354,
+ +0.2034, -0.1899, +0.1751, +0.1841, -0.3028, +0.0064, -0.6946,
+ +0.0640, +0.0450, -0.0954, +0.1070, -0.4622, +0.0043, +0.3927,
+ -0.0924, +0.0170, +0.1991, +0.1029, -0.4010, -0.5260, +0.3099,
+ +0.1169, -0.3201, +0.1383, +0.0304, +0.4974, +0.0375, -0.2105,
+ +0.4277, -0.0385, -0.1893, +0.2602, +0.1801, -0.3028, +0.3519,
+ -0.0072, +0.0575, -0.0439, -0.0147, +0.0971, -0.1810, +0.2790,
+ +0.3070, +0.1567
+ ],
+ [
+ -0.3593, +0.3125, +0.2294, +0.1004, -0.0686, +0.2577, +0.0183,
+ +0.0088, -0.0294, -0.0669, +0.0566, +0.2798, -0.0858, -0.0387,
+ +0.0556, -0.2810, +0.0240, -0.5967, -0.2381, -0.1677, -0.0648,
+ -0.4832, +0.0483, -0.1887, -0.1410, -0.0185, +0.0323, -0.8195,
+ -0.2986, -0.1578, +0.0644, +0.0243, -0.5457, -0.7528, +0.2299,
+ +0.1152, -0.1551, -0.0403, +0.0335, -0.4697, +0.4705, +0.2231,
+ +0.0153, -0.3863, -0.1568, -0.1220, -0.7400, +0.0445, +0.0043,
+ -0.0574, +0.1877, -0.5959, -0.0730, +0.2549, +0.1350, +0.1365,
+ +0.2877, -0.2223, -0.3385, -0.2589, +0.0974, -0.0737, -0.1565,
+ -0.2140, +0.1631, +0.2298, +0.3280, -0.1305, -0.5843, +0.0501,
+ +0.0569, +0.2176, -0.0486, +0.1723, -0.0183, -0.2988, -0.1125,
+ -0.0802, -0.0333, -0.6227, -0.1824, -0.2171, -0.0956, +0.0165,
+ +0.1714, +0.0483, +0.3055, -0.0871, +0.0996, -0.4671, +0.3062,
+ -0.1808, +0.2514, -0.0150, +0.1948, +0.0196, +0.5776, +0.2378,
+ +0.0446, +0.2286, +0.4647, -0.4668, +0.0440, -0.0914, -0.4420,
+ +0.2602, +0.1791, +0.1920, -0.3575, +0.1086, -0.1176, -0.0526,
+ -0.1220, +0.0907, +0.1720, +0.2100, -0.1284, -0.0736, -0.2041,
+ -0.0051, -0.2761, -0.2553, +0.0368, -0.1468, -0.3486, -0.3645,
+ +0.2823, -0.1184
+ ],
+ [
+ -0.5915, -0.1844, -0.3926, +0.2582, +0.1572, -0.0428, -0.0333,
+ -0.1803, +0.2298, +0.2510, +0.0504, +0.4947, +0.0043, -0.2448,
+ -0.3863, +0.1712, +0.4349, -0.2526, +0.0374, +0.1115, -0.0840,
+ +0.0980, +0.0218, +0.1006, +0.0466, +0.2759, +0.0063, +0.1454,
+ +0.0132, +0.3720, +0.1462, -0.0060, +0.1965, +0.0738, -0.0544,
+ +0.3279, -0.0334, +0.2048, -0.2162, -0.1511, -0.1620, +0.0853,
+ -0.0094, +0.0964, +0.4726, -0.1591, -0.5189, +0.3182, -0.6680,
+ -0.2251, +0.0435, +0.3286, -0.0167, -0.1225, -0.0941, -0.0467,
+ +0.3194, +0.1592, +0.0540, +0.1801, +0.1991, -0.1422, +0.0651,
+ +0.0313, +0.0565, +0.2132, +0.0259, -0.1215, -0.0465, +0.2803,
+ +0.2929, +0.2781, -0.0417, +0.1751, -0.4823, +0.0149, -0.3763,
+ +0.1523, -0.3554, +0.0224, -0.0570, -0.5339, +0.0914, +0.2395,
+ +0.2099, -0.2714, -0.5664, -0.0861, -0.2449, -0.1557, -0.0394,
+ -0.0997, +0.0458, +0.1191, -0.1428, +0.0270, +0.1114, +0.0614,
+ -0.0379, -0.2785, +0.0696, +0.0675, -0.0510, +0.0598, -0.1880,
+ -0.1675, +0.0851, -0.2465, -0.1332, -0.0188, +0.3592, +0.0251,
+ -0.3794, +0.0634, +0.1697, +0.2868, -0.0108, -0.4742, +0.0380,
+ -0.0434, -0.3096, -0.3023, -0.4648, +0.2064, -0.3723, +0.1903,
+ +0.4308, -0.1828
+ ],
+ [
+ +0.0533, -0.3794, +0.0423, -0.1411, -0.0702, +0.1252, +0.0546,
+ +0.1258, +0.4106, -0.0027, -0.0846, +0.0810, +0.0087, -0.3069,
+ +0.0778, +0.2796, +0.1095, -0.2539, +0.1197, +0.0380, +0.0192,
+ +0.0596, -0.1093, +0.1209, -0.2235, -0.0996, +0.0827, -0.1329,
+ -0.3149, -0.0009, -0.2465, -0.0712, -0.4329, -0.8865, +0.2083,
+ +0.0827, -0.2544, -0.0157, -0.0426, -0.0675, +0.2012, +0.1082,
+ -0.1642, -0.2945, -0.0814, -0.4239, +0.0364, -0.1153, -0.5297,
+ +0.1528, -0.1251, -0.2883, -0.1123, -0.2345, -0.1243, +0.0758,
+ +0.7976, -0.0334, -0.0996, +0.1035, -0.1435, -0.3511, -0.3324,
+ +0.3685, -0.2246, +0.1072, -0.1100, -0.0016, -0.1830, +0.0871,
+ -0.0546, +0.0046, -0.2693, +0.2749, -0.0977, -0.3543, +0.0312,
+ +0.0677, +0.2466, +0.0712, +0.0769, +0.2314, -0.2621, +0.1475,
+ +0.0944, +0.0745, -0.6371, -0.5103, -0.7600, -0.0428, -0.0085,
+ +0.0334, -0.4792, +0.1178, +0.1895, +0.2825, -0.1221, -0.3944,
+ -0.3124, -0.1355, +0.4852, +0.1503, +0.0985, +0.0310, -0.0247,
+ -0.1419, +0.0191, +0.0767, +0.1392, +0.0055, +0.0104, -0.0360,
+ -0.2649, -0.0748, -0.1387, +0.1615, -0.4313, -0.0540, +0.0122,
+ -0.1171, -0.5336, -0.0798, -0.1408, -0.2159, +0.3831, -0.0502,
+ -0.1978, -0.1882
+ ],
+ [
+ -0.0209, -0.0106, -0.1195, -0.0162, -0.1540, +0.0713, -0.2198,
+ -0.4215, +0.0070, +0.2775, +0.2773, +0.1619, +0.0935, +0.5805,
+ -0.4682, -0.0517, -0.3038, -0.3515, -0.0305, -0.0407, +0.0964,
+ +0.1052, -0.0705, -0.1846, +0.2016, +0.1809, -0.0402, +0.0914,
+ +0.0949, +0.0608, -0.5812, +0.0606, -0.2100, +0.0656, +0.1924,
+ +0.0935, -0.6964, +0.0585, -0.0135, -0.2383, +0.3479, -0.1264,
+ +0.1433, +0.0711, +0.2887, +0.0683, -0.1336, -0.0104, +0.2000,
+ -0.0962, -0.2787, -0.0522, -0.3700, +0.0234, -0.2526, +0.0739,
+ -0.7853, +0.0755, -0.0885, +0.0962, -0.4285, +0.0612, -0.2318,
+ -0.3520, -0.2696, +0.2609, +0.0439, +0.3858, +0.0346, -0.0265,
+ -0.0480, +0.1523, -0.1361, +0.2122, +0.0862, -0.2789, -0.1964,
+ +0.0047, -0.2021, -0.4251, -0.2270, +0.0885, -0.3531, -0.1673,
+ +0.1966, +0.3255, +0.3677, +0.2451, +0.2206, +0.1645, -0.0509,
+ +0.2135, -0.3057, +0.1289, +0.3612, +0.0751, -0.2921, +0.0211,
+ +0.1665, -0.1668, -0.4720, +0.0643, +0.1883, -0.2529, -0.2803,
+ +0.2548, +0.0644, +0.3636, -0.1947, +0.1404, -0.4078, +0.1706,
+ +0.2401, +0.2231, -0.1344, +0.3388, -0.0723, +0.0942, -0.3626,
+ +0.0288, +0.1905, -0.5602, +0.5321, +0.3668, -1.0004, +0.0396,
+ -0.1636, +0.4003
+ ],
+ [
+ -0.6009, -0.1764, +0.1790, -0.4413, -0.2962, -0.2103, -0.3839,
+ +0.5148, -0.0473, -0.0155, -0.7608, -0.0242, +0.0403, -0.0810,
+ +0.6040, -0.2872, +0.1655, +0.5840, +0.3057, -0.2255, -0.3538,
+ -0.0057, +0.1084, -0.0653, -0.3629, +0.0327, -0.2162, +0.4229,
+ -0.3050, -0.3602, +0.2457, -0.0923, -0.3345, +0.0993, -0.1577,
+ +0.2566, -0.2755, +0.0090, +0.6055, -0.2832, +0.1900, -0.4449,
+ -0.2049, +0.0905, +0.3360, -0.1946, +0.0111, +0.3941, -0.0312,
+ +0.1419, -0.1522, -0.2697, +0.1142, +0.1145, -0.0213, +0.3917,
+ +0.0264, +0.2655, +0.5183, +0.0405, +0.5094, +0.3597, -0.2183,
+ -0.2867, +0.0580, +0.1505, -0.1060, -0.4326, +0.3122, -0.2913,
+ -0.2615, -0.2251, +0.2661, -0.0916, +0.0263, +0.2415, -0.0010,
+ -0.1383, +0.0939, -0.1808, +0.4885, -0.5949, +0.0661, -0.0190,
+ -0.2434, +0.0903, +0.0335, +0.2637, -0.1724, +0.1309, +0.3296,
+ -0.0518, +0.2669, -0.4770, +0.1438, +0.0770, -0.1400, -0.1650,
+ +0.0405, +0.1128, +0.4488, -0.4113, +0.7159, +0.4405, -0.2670,
+ -0.2373, +0.1552, -0.3004, -1.0047, -0.4442, -0.1569, -0.1711,
+ +0.1751, +0.1856, -0.2171, -0.4630, +0.3209, +0.1233, +0.0427,
+ -0.1323, +0.0847, +0.4391, -0.0433, -0.3804, +0.0234, +0.1642,
+ +0.1413, -0.4204
+ ],
+ [
+ -0.0382, +0.0697, +0.1954, +0.1232, -0.3950, +0.0410, -0.0058,
+ -0.2217, +0.2788, -0.0926, +0.0316, -0.2992, +0.1791, -0.0543,
+ -0.0835, -0.3470, -0.6962, -0.2087, +0.3590, -0.0578, +0.5484,
+ +0.1435, +0.1078, -0.3716, +0.1744, -0.1441, +0.0480, +0.3284,
+ +0.3241, +0.0057, +0.1665, -0.6800, -0.0559, -0.8574, -0.3013,
+ +0.0994, -0.1789, -0.0773, -0.1086, -0.6569, -0.3416, -0.4008,
+ +0.2978, +0.4831, -0.6239, -0.0037, -0.4366, +0.1802, -0.0730,
+ +0.4826, -0.3240, -0.1030, -0.4562, -0.3693, -0.6823, +0.0320,
+ -0.3837, -0.1544, -0.1656, +0.0836, -0.1672, +0.0018, -0.1044,
+ +0.0743, +0.3075, -0.0115, +0.0808, -0.3066, -0.3586, -0.0228,
+ +0.1209, +0.1033, -0.3932, +0.2474, +0.2178, +0.1313, -0.5326,
+ +0.0827, -0.2049, -0.3722, -0.0023, +0.4377, +0.0418, -0.2483,
+ -0.0836, +0.1767, +0.2034, -0.0476, -0.1573, +0.5566, +0.2577,
+ +0.0562, -0.1836, -0.1882, +0.5193, +0.0079, -0.3756, +0.0340,
+ -0.1755, +0.2817, -0.3039, +0.2948, -0.5376, -0.0007, -0.5880,
+ -0.5485, +0.0770, +0.1617, +0.1887, +0.1492, -0.0807, -0.3650,
+ -0.0540, -0.2106, +0.0963, +0.0005, +0.1230, +0.0178, -0.1458,
+ -0.1242, -0.3049, +0.1069, +0.2919, +0.4823, -0.1985, +0.7479,
+ -0.0910, +0.0032
+ ],
+ [
+ +0.0999, +0.1129, +0.0788, +0.0146, -0.2431, -0.0529, -0.0087,
+ +0.0799, -0.0451, -0.0487, -0.1577, +0.1812, -0.0007, +0.2515,
+ -0.2335, -0.0300, -0.0498, -0.1109, -0.4123, +0.0599, +0.3430,
+ +0.0924, -0.3990, +0.0617, -0.3780, +0.2513, -0.1506, -0.1866,
+ +0.2113, -0.0043, +0.1018, +0.0475, -0.1532, +0.1009, +0.2183,
+ +0.0201, +0.0020, +0.1105, -0.2671, +0.2815, +0.1835, -0.4436,
+ -0.0833, -0.0476, -0.2875, -0.1545, +0.4175, -0.4003, -0.5049,
+ -0.0427, +0.1898, +0.1642, -0.6990, -0.4362, +0.4377, -0.0246,
+ +0.0071, -0.1784, +0.0141, -0.2318, -0.7877, +0.1683, +0.0151,
+ +0.1172, -0.4099, +0.0956, +0.2033, +0.1802, -0.2204, -0.4969,
+ -0.2697, +0.0227, -0.3113, +0.3833, -0.2007, -0.0491, +0.3474,
+ +0.0419, +0.1888, +0.1764, -0.0694, +0.0286, +0.2823, +0.0565,
+ +0.2045, +0.0872, +0.0970, +0.4547, +0.3809, +0.1010, -0.0356,
+ -0.4323, +0.0784, -0.4963, +0.0527, -0.3812, -1.2797, -0.0429,
+ -0.1506, -0.3298, -0.0177, -0.2223, -0.0632, +0.0620, +0.2290,
+ +0.0297, +0.2258, -0.2569, -0.9111, -0.1175, -0.1230, +0.1327,
+ +0.0528, +0.1498, -0.2203, -0.4755, +0.0978, -0.0368, +0.2662,
+ -0.0755, +0.1348, +0.1874, -0.6464, -0.0296, -0.0794, +0.2649,
+ -0.1350, +0.2607
+ ],
+ [
+ -0.1078, -0.3764, -0.1381, +0.0869, -0.2514, +0.0132, +0.0976,
+ +0.1634, +0.0764, +0.4871, +0.2087, +0.1099, -0.1876, -0.0077,
+ +0.2282, +0.0318, -0.0299, -0.1394, +0.3569, +0.1685, +0.3756,
+ +0.0565, -0.3884, -0.0255, -0.3361, -0.1637, -0.0515, -0.1319,
+ +0.0730, -0.1038, -0.0948, -0.4817, +0.2756, +0.0562, -0.1065,
+ -0.4606, +0.2205, +0.2330, -0.0423, +0.4746, -0.1326, +0.0192,
+ +0.0178, +0.0128, +0.0501, +0.3476, +0.0619, -0.3693, +0.1192,
+ +0.3615, +0.6273, -0.0511, -0.1759, +0.0573, +0.3286, -0.1206,
+ -0.6524, +0.0031, -0.1262, -0.2288, +0.3611, -0.0265, -0.2484,
+ +0.4420, -0.2119, -0.4760, -0.1120, -0.1045, -0.2260, -0.1096,
+ +0.1383, +0.2693, -0.0881, +0.5958, -0.2183, -0.3405, +0.1038,
+ +0.2003, +0.3021, -0.0557, -0.2225, -0.2724, +0.1702, +0.1224,
+ +0.2801, +0.3151, -0.0497, -0.1870, +0.0490, +0.3350, -0.2218,
+ -0.4137, +0.3848, -0.0899, -0.0908, -0.2358, +0.4977, +0.1214,
+ -0.0100, +0.1173, -0.2396, -0.2299, +0.2137, +0.0491, -0.7133,
+ -0.0605, -0.0278, +0.2408, +0.0260, -0.0671, +0.1543, -0.3159,
+ -0.2227, +0.1132, -0.2261, -0.0250, -0.1055, +0.0683, +0.2335,
+ +0.3028, +0.0236, -0.4458, +0.0361, -0.5405, -0.0442, -0.6218,
+ +0.1025, +0.0115
+ ],
+ [
+ -0.1324, +0.4260, -0.0147, -0.5004, -0.0002, +0.0140, +0.2995,
+ +0.2757, -0.1943, -0.3776, +0.0813, +0.1067, -0.2905, -0.2673,
+ -0.4926, -0.2956, +0.4968, -0.0698, +0.3007, +0.1967, +0.0180,
+ -0.6847, +0.1337, -0.0526, +0.2531, +0.1462, +0.2974, -0.4869,
+ +0.1167, -0.1194, +0.0620, +0.2449, +0.2284, +0.0841, +0.0588,
+ +0.0418, +0.0891, -0.0507, -0.3089, -0.2124, -0.7492, -0.0292,
+ +0.1146, -0.4990, +0.2225, -0.0327, +0.1191, +0.4086, -0.3497,
+ +0.0704, -0.4547, +0.6996, +0.2663, -0.1322, +0.1495, +0.1802,
+ -0.2279, +0.3308, -0.0674, +0.1613, -0.1077, +0.0122, -0.0466,
+ +0.1396, -0.3371, -0.4765, -0.2150, -0.0451, +0.1198, -0.1538,
+ -0.1045, -0.7362, +0.0373, +0.2297, -0.8950, +0.3760, -0.3753,
+ +0.2895, +0.5398, -0.1854, +0.1583, +0.4056, +0.4843, -0.1372,
+ +0.5370, +0.3985, +0.1525, -0.1650, +0.0182, -0.3630, +0.1980,
+ +0.1669, -0.0329, -0.2845, +0.1200, +0.2052, +0.3971, -0.1553,
+ +0.4036, -0.3132, +0.2581, +0.5021, -0.0966, -0.1518, -0.3456,
+ -0.1915, -0.0816, +0.0773, -0.4633, +0.4096, -0.1858, +0.0532,
+ +0.3825, -0.1854, -0.1189, +0.2893, -0.1457, +0.4268, +0.0553,
+ -0.4428, -0.0553, -0.2409, +0.4323, -0.2580, -0.5131, +0.1144,
+ -0.5439, -0.0324
+ ],
+ [
+ -0.0951, -0.2398, -0.1207, +0.1439, -0.0112, +0.0403, +0.2109,
+ +0.2822, +0.0714, -0.0061, -0.3167, +0.0310, -0.0433, -0.3120,
+ -0.3933, +0.1612, +0.1771, -0.1223, +0.2668, +0.2125, +0.2258,
+ -0.1501, -0.3047, -0.3328, -0.0758, -0.3413, -0.0997, -0.0709,
+ -0.1279, -0.2422, -0.3422, +0.1265, -0.7878, -0.0616, -0.1220,
+ -0.0724, +0.2619, -0.4331, +0.0029, +0.0384, +0.0974, -0.2454,
+ +0.0472, +0.1363, -0.1616, +0.0008, +0.2507, +0.1707, +0.2489,
+ -0.0522, +0.2306, +0.0220, +0.0743, -0.0148, +0.1893, -0.3129,
+ -0.0313, +0.0656, +0.1938, +0.5220, +0.4117, +0.0448, +0.1463,
+ -0.1240, +0.1775, +0.0772, -0.6103, -0.1047, +0.0278, -0.4253,
+ -0.0560, -0.1347, -0.0628, +0.1269, +0.0191, -0.2100, -0.2395,
+ -0.0466, -0.3006, -0.2604, +0.3735, +0.2593, -0.1534, -0.0976,
+ -0.4843, -0.4349, -0.1046, -0.0600, +0.1310, -0.1107, -0.5161,
+ -0.3044, -0.2743, -0.0216, +0.1310, -0.3426, -0.1695, +0.1092,
+ +0.2327, +0.0663, +0.0718, +0.1479, +0.1967, +0.0784, -0.1789,
+ -0.1532, -0.3373, -0.3602, +0.0155, +0.3476, -0.1938, +0.1991,
+ -0.1335, -0.2120, -0.0719, -0.4957, -0.1461, -0.0870, +0.0535,
+ +0.0260, -0.1487, -0.0610, -0.0131, +0.0925, +0.0041, +0.0706,
+ -0.3249, +0.3076
+ ],
+ [
+ +0.0541, +0.4655, -0.4223, -0.2331, -0.0581, +0.5284, +0.0901,
+ -0.0378, +0.2620, -0.2267, +0.2851, +0.1581, +0.2739, +0.4589,
+ +0.2652, +0.1516, -0.2050, -0.0756, +0.0852, +0.1785, +0.0971,
+ -0.1604, +0.0089, +0.1134, -0.2514, +0.4193, +0.0698, -0.1063,
+ +0.1228, -0.4191, -0.0360, +0.2030, +0.0081, +0.1340, -0.1340,
+ +0.1388, +0.4455, +0.0481, -0.4398, -0.0168, -0.3045, -0.0132,
+ +0.0051, -0.2227, -0.6544, -0.0354, -0.2273, +0.4308, +0.2649,
+ -0.4759, -0.2885, +0.1836, -0.3740, +0.1777, +0.0127, +0.0164,
+ -0.4780, +0.3226, +0.3391, +0.3711, -0.1510, -0.5826, -0.0895,
+ -0.1212, -0.0941, -0.2657, -0.0334, +0.1040, +0.1568, -0.2225,
+ -0.2873, +0.3292, -0.0350, -0.1347, +0.3132, +0.3021, -0.1590,
+ +0.1355, -0.3929, +0.1691, +0.2215, +0.4122, -0.1927, +0.1729,
+ -0.6266, -0.2215, +0.1797, -0.1774, +0.0737, +0.0295, -0.0419,
+ +0.2605, +0.2356, +0.0833, -0.2404, +0.3106, +0.1529, -0.2097,
+ +0.1342, -0.3574, +0.4464, -0.0297, +0.0385, +0.0653, -0.7114,
+ -0.3072, -0.0939, -0.0451, -0.1536, +0.1754, -0.2410, -0.3136,
+ -0.1038, -0.2600, -0.0292, +0.1328, -0.1258, -0.1659, -0.1376,
+ -0.4014, +0.0359, +0.0221, -0.2341, -0.2213, -0.0071, -0.2549,
+ +0.1757, +0.2961
+ ],
+ [
+ -0.0045, +0.3948, +0.2514, +0.1126, -0.0968, -0.0414, +0.2683,
+ -0.7427, -0.2207, -0.1312, +0.3067, +0.4822, -0.3512, +0.1159,
+ -0.0726, -0.0937, +0.2098, +0.1605, +0.0238, -0.0439, +0.1858,
+ -0.2014, -0.2361, -0.2284, -0.0099, +0.5000, +0.2455, +0.0184,
+ +0.0253, -0.4009, -0.4215, -0.7544, -0.3624, -0.0567, -0.3579,
+ +0.0272, +0.4209, -0.0857, +0.1130, -0.2006, -0.4367, +0.0771,
+ +0.0491, +0.4899, -0.3251, +0.0659, -0.5332, +0.1157, -0.5820,
+ +0.1902, +0.1078, -0.3355, -0.4025, +0.0392, +0.2063, +0.1495,
+ +0.0616, +0.1051, -0.4266, +0.0420, +0.0316, +0.0614, -0.2423,
+ +0.3125, -0.0700, +0.0286, +0.3859, -0.3231, +0.0262, -0.2398,
+ -0.1127, +0.2679, -0.4434, +0.3665, +0.1111, -0.1690, +0.0793,
+ +0.4125, -0.0157, -0.2707, -0.4898, -0.0642, +0.3456, +0.2465,
+ -0.5142, -0.2889, -0.2712, -0.2100, +0.2719, +0.2298, -0.0976,
+ +0.1110, +0.3158, -0.0420, -0.0406, -0.0493, -0.4078, +0.0645,
+ +0.5344, +0.3139, -0.1080, +0.1376, -0.2784, -0.0195, +0.3964,
+ -0.0877, -0.0800, -0.1061, -0.0690, -0.1506, -0.1644, -0.0561,
+ -0.3988, -0.2351, -0.2194, +0.1311, -0.0139, -0.0584, -0.0780,
+ -0.5172, +0.1721, -0.3860, -0.2823, +0.2836, -0.0941, -0.2243,
+ +0.1657, -0.4716
+ ],
+ [
+ -0.0641, -0.3698, -0.2212, +0.1342, -0.3151, +0.0310, -0.2151,
+ +0.0262, -0.1678, +0.3159, +0.1253, -0.2815, +0.1199, +0.0624,
+ +0.1208, +0.3487, -0.3874, -0.1471, -0.1021, +0.2997, -0.5750,
+ -0.3173, +0.4029, -0.2965, -0.2111, -0.5049, +0.0513, -0.0693,
+ -0.0425, +0.1383, -0.1910, -0.9026, -0.5273, -0.4481, -0.3645,
+ +0.0307, -0.0129, +0.0054, +0.1593, +0.0492, -0.1182, +0.0122,
+ +0.2354, +0.1718, +0.2423, -0.0851, +0.1524, -0.0100, +0.0852,
+ -0.2707, +0.1983, -0.0776, -0.5558, +0.1277, +0.1845, +0.4677,
+ +0.1273, -0.2698, +0.3344, -0.1939, -0.1121, -0.0507, +0.3284,
+ -0.0188, +0.2441, +0.1043, +0.0416, -0.4772, -0.2314, +0.1646,
+ +0.0371, +0.3291, -0.2173, +0.0456, +0.1533, -0.0692, +0.4015,
+ +0.0198, -0.2382, +0.0169, +0.0245, -0.0967, -0.1479, -0.1204,
+ +0.2310, -0.0040, +0.1312, +0.0790, -0.1959, -0.4960, +0.2153,
+ -0.2277, +0.1761, -0.1988, -0.0739, -0.0226, +0.2609, -0.2217,
+ -0.6110, -0.2360, -0.0289, +0.4274, +0.0961, +0.1861, +0.0216,
+ +0.2856, -0.0471, +0.0139, +0.2482, -0.2179, -0.0888, +0.1368,
+ -0.0699, -0.1128, +0.0713, +0.2249, -0.1332, -0.0250, -0.1889,
+ +0.0095, -0.0816, +0.0571, +0.5398, +0.2336, +0.2598, +0.1348,
+ +0.2462, -0.4051
+ ],
+ [
+ -0.1438, -0.2210, -0.2563, +0.0057, -0.0217, -0.0290, -0.0967,
+ +0.3873, +0.0832, -0.6249, -0.1031, +0.0495, -0.0176, +0.1595,
+ +0.2288, -0.1882, +0.2508, -0.4344, +0.1012, -0.3476, +0.3677,
+ -0.1171, +0.0703, -0.0809, +0.0032, -0.0119, -0.0557, +0.0087,
+ -0.3490, +0.3963, -0.5019, +0.0933, -0.0076, +0.0988, +0.1388,
+ +0.1707, +0.3001, -0.2023, +0.2833, -0.3746, +0.0634, -0.3222,
+ +0.0022, -0.2720, -0.0643, -0.1532, -0.1900, -0.2513, +0.3039,
+ +0.1634, -0.3249, -0.2999, +0.1867, -0.0237, +0.0407, -0.1726,
+ +0.1812, -0.1945, +0.0753, -0.0624, +0.2736, -0.1881, +0.3375,
+ +0.0451, -0.4780, +0.1311, -0.3083, +0.0327, +0.0122, +0.1714,
+ -0.1143, +0.2245, +0.1845, -0.1023, -0.0519, -0.2336, -0.5005,
+ -0.0854, +0.3170, -0.1398, -0.0307, +0.1428, -0.0750, -0.1836,
+ -0.3896, +0.2932, -0.3616, +0.1044, -0.1114, +0.3557, +0.0386,
+ +0.1663, +0.1116, -0.1692, +0.2538, -0.0329, +0.1425, -0.1310,
+ +0.3025, +0.2110, -0.1981, -0.5602, +0.0119, +0.0663, -0.0021,
+ -0.0495, +0.0595, -0.2126, -0.2603, +0.1909, -0.0732, -0.3379,
+ +0.3198, +0.1815, +0.2507, -0.2851, +0.2290, +0.0121, +0.2947,
+ +0.1516, -0.4416, +0.3535, +0.0362, +0.4227, +0.2058, -0.3077,
+ -0.7662, +0.0039
+ ],
+ [
+ -0.0084, +0.1321, -0.0739, +0.1690, -0.2521, -0.1354, -0.2330,
+ +0.3076, -0.3387, +0.3118, -0.1261, -0.5501, -0.1610, -0.1947,
+ -0.1845, -0.4091, -0.0699, -0.1083, +0.1431, +0.0793, -0.3411,
+ -0.4424, -0.3152, -0.2997, +0.0218, +0.0610, -0.3120, +0.5040,
+ -0.1015, +0.2065, +0.2869, -0.5926, -0.4347, -0.1448, +0.1443,
+ +0.0241, -0.0808, -0.3136, +0.0794, +0.1769, -0.2137, -0.3096,
+ +0.1118, -0.2514, +0.0731, -0.1291, +0.3789, +0.3855, +0.1416,
+ +0.2163, +0.1692, -0.0849, -0.5013, +0.2453, -0.2681, +0.1146,
+ -0.0248, +0.5772, -0.0399, -0.1557, +0.4552, -0.0198, -0.4703,
+ -0.2443, +0.1341, -0.1853, +0.2554, -0.3664, -0.0049, -0.1806,
+ +0.1591, +0.4685, -0.3846, +0.3275, -0.5392, -0.0238, +0.2383,
+ +0.1893, -0.2952, -0.1149, +0.3631, +0.0357, -0.3412, +0.5988,
+ -0.0815, -0.0911, +0.0158, +0.0341, +0.0265, +0.2634, -0.0081,
+ -0.2504, -0.3421, +0.2368, +0.5963, +0.1872, +0.0543, -0.0797,
+ +0.1321, -0.0278, -0.4313, +0.1046, -0.0670, -0.0294, -0.0356,
+ -0.2410, +0.0999, +0.3321, +0.0379, -0.1456, +0.2748, -0.0311,
+ +0.2177, -0.1558, +0.0286, -0.1212, -0.0144, +0.1093, -0.0799,
+ -0.5326, +0.3965, -0.1177, -0.2089, -0.2105, -0.5678, -0.0271,
+ +0.0421, -0.1457
+ ],
+ [
+ -0.4219, -0.0642, +0.1520, +0.2730, +0.0215, +0.2991, -0.0341,
+ +0.3181, +0.1450, -0.2327, +0.0440, +0.2632, +0.3848, +0.2312,
+ +0.3035, -0.4698, +0.3574, +0.1646, -0.1934, -0.2782, +0.4133,
+ +0.0815, -0.3259, +0.3120, -0.0893, +0.0461, +0.2430, -0.1055,
+ +0.3371, +0.2021, -0.0185, +0.0365, +0.5522, +0.1110, -0.0574,
+ +0.1748, -0.5135, +0.3464, -0.0352, +0.2477, -0.5143, +0.0434,
+ -0.0307, +0.0653, -0.1172, -0.1443, -0.0161, +0.2203, +0.1484,
+ -0.1537, -0.0051, -0.2373, -0.0219, -0.4247, -0.2263, -0.0316,
+ +0.3961, -0.1794, -0.1073, -0.0504, +0.1702, -0.2868, -0.0476,
+ -0.2767, +0.2287, -0.4326, -0.1071, +0.0696, -0.7776, +0.2128,
+ -0.1849, +0.3147, +0.2155, -0.2478, -0.0849, +0.3377, -0.4766,
+ +0.0997, +0.0508, -0.3671, +0.0700, +0.2319, +0.1564, -0.0436,
+ +0.1947, +0.1576, +0.1914, +0.1839, +0.1461, -0.1716, -0.2761,
+ -0.1924, -0.0864, -0.4610, -0.0227, -0.1417, -0.3146, +0.1264,
+ -0.2383, -0.1555, -0.3563, +0.0651, +0.2672, +0.1644, -0.0204,
+ -0.3279, -0.2122, +0.1154, -0.1318, -0.1615, +0.0484, -0.4275,
+ -0.5074, +0.2201, -0.5123, -0.3129, +0.2558, -0.0904, -0.1861,
+ +0.1214, -0.4799, +0.1607, +0.2893, -0.2543, -0.3875, +0.4410,
+ +0.0593, -0.0176
+ ],
+ [
+ -0.1470, -0.2327, +0.0815, -0.1459, -0.2291, -0.0562, +0.1376,
+ +0.1604, -0.0832, +0.2067, +0.0586, -0.0354, +0.2460, -0.0497,
+ -0.2480, -0.6084, -0.2743, -0.5487, -0.0208, -0.0933, +0.1163,
+ -0.1184, -0.3381, +0.3618, -0.2309, +0.0550, -0.1798, -0.0875,
+ +0.2540, -0.4719, +0.0159, -0.0701, -0.1830, -0.1771, -0.0436,
+ -0.0899, -0.1044, +0.1469, -0.1417, +0.1335, -0.0024, -0.2346,
+ +0.2030, -0.2100, +0.2577, -0.0560, -0.2534, -0.2908, +0.6886,
+ +0.0102, +0.0461, +0.0156, +0.1817, -0.1090, -0.2347, -0.6208,
+ -0.0059, -0.7716, -0.3923, +0.0970, -0.3165, +0.0535, -0.3916,
+ +0.1415, +0.3424, -0.1105, -0.3802, +0.0150, +0.4469, -0.2943,
+ +0.0476, -0.3771, +0.3636, -0.0410, -0.0079, +0.2929, +0.3688,
+ -0.4768, +0.2274, +0.1870, +0.0247, +0.1752, -0.0923, +0.3461,
+ -0.0168, +0.0372, +0.2772, -0.2258, +0.2398, -0.0877, -0.0927,
+ -0.0272, +0.3592, -0.4846, -0.1541, +0.2650, -0.0134, -0.1856,
+ -0.1688, +0.2972, +0.3202, +0.2967, +0.0885, +0.1266, -0.3913,
+ +0.6079, -0.1323, +0.2003, +0.0828, -0.4133, -0.0906, +0.2161,
+ -0.0804, -0.0228, +0.0707, -0.2550, -0.1726, +0.2102, +0.3182,
+ -0.2587, +0.0575, -0.0176, +0.0198, -0.1165, -0.5896, +0.1733,
+ -0.3348, -0.1469
+ ],
+ [
+ -0.3824, +0.2283, +0.2410, +0.2186, -0.5470, +0.1103, -0.0149,
+ -0.2098, -0.1996, +0.2482, -0.3463, -0.1121, +0.3371, -0.0417,
+ +0.0075, -0.0541, +0.2727, +0.2832, +0.2670, +0.3552, -0.4192,
+ -0.0801, -1.0397, +0.2101, -0.2077, +0.3952, +0.1731, -0.3074,
+ -0.0472, -0.1154, +0.2872, -0.0417, -0.0287, +0.2925, -0.4077,
+ +0.0301, +0.3340, +0.2400, -0.1239, -0.4566, -0.1001, -0.2440,
+ +0.3035, -0.1512, +0.5552, -0.0397, -0.2366, -0.1716, +0.1308,
+ -0.6144, -0.3075, +0.1430, +0.0632, -0.4414, -0.4012, -0.2610,
+ -0.1726, +0.0840, +0.3784, -0.1463, -0.1945, -0.1464, +0.0453,
+ -0.6733, +0.1245, -0.1531, -0.0880, -0.0046, +0.1832, +0.2703,
+ +0.2005, +0.2362, +0.1479, -0.1326, +0.2796, +0.3101, +0.0988,
+ +0.0696, +0.1107, +0.1591, +0.3960, +0.1939, -0.1844, -0.0916,
+ -0.4749, -0.0713, +0.1138, -0.3296, +0.0143, +0.1719, +0.1194,
+ -0.1216, +0.1262, -0.0051, +0.1966, -0.0664, -0.2489, -0.3240,
+ +0.1552, -0.3418, -0.2673, +0.0230, +0.0407, +0.1522, -0.0475,
+ +0.1207, -0.2826, -0.0798, -0.5290, -0.0987, +0.1027, -0.0802,
+ +0.3484, -0.1592, +0.2472, -0.1101, -0.1823, -0.0829, -0.5066,
+ -0.1147, -0.0391, -0.0087, -0.3388, +0.1701, -0.3465, -0.0286,
+ -0.5400, -0.1208
+ ],
+ [
+ +0.2132, -0.2038, -0.3343, +0.3540, +0.1567, -0.0095, -0.0718,
+ -0.2499, -0.1994, +0.2980, -0.5719, -0.0183, +0.1170, +0.1715,
+ -0.0344, -0.2624, +0.2696, -0.0722, -0.2631, +0.1950, -0.2201,
+ -0.2901, -0.2445, -0.1541, -0.1788, +0.0809, +0.0669, -0.0549,
+ -0.0294, -0.2629, -0.2968, -0.2379, +0.0772, +0.2484, -0.1016,
+ +0.1574, -0.1376, -0.1910, +0.0483, +0.0839, -0.1902, +0.3949,
+ +0.1495, +0.2443, -0.1737, -0.3951, -0.0341, -0.1647, +0.3102,
+ -0.1957, +0.1148, -0.1085, +0.2525, -0.2577, -0.2769, -0.0665,
+ -0.1045, -0.0036, +0.4137, -0.1179, -0.0173, -0.1624, +0.1537,
+ +0.0199, -0.4035, -0.7585, -0.1749, +0.0859, -0.5522, -0.2950,
+ +0.2526, -0.0636, +0.2784, -0.0519, -0.0059, -0.0829, -0.2314,
+ +0.0356, +0.0620, -0.3004, +0.3659, +0.1431, +0.0440, +0.0523,
+ +0.0418, -0.3607, -0.0321, +0.5865, -0.3718, -0.0894, +0.0159,
+ -0.3719, +0.1833, -0.2633, -0.0643, +0.1656, +0.1638, -0.0804,
+ +0.0640, -0.2463, -0.2730, +0.1763, +0.5623, -0.1374, +0.0886,
+ +0.1344, -0.3440, -0.1357, -0.6086, +0.0246, +0.1226, -0.1262,
+ -0.0284, -0.1652, +0.2808, +0.0982, +0.1970, -0.0293, +0.0909,
+ -0.2475, +0.1229, +0.0832, +0.2307, -0.0334, -0.0804, +0.0204,
+ -0.2117, -0.0586
+ ],
+ [
+ +0.0675, -0.2419, -0.0014, -0.4854, +0.0023, +0.2432, -0.0517,
+ +0.1820, +0.4027, +0.0418, +0.0799, +0.0445, -0.0124, +0.0331,
+ +0.2243, -0.2098, -0.2624, +0.2788, -0.3206, +0.0902, -0.2575,
+ +0.0033, -0.2722, -0.4836, -0.1144, -0.1933, +0.2316, +0.0758,
+ +0.1769, +0.1349, +0.1459, -0.2154, -0.5491, -0.3184, -0.2450,
+ +0.1040, +0.1301, -0.1167, -0.3166, +0.0286, +0.2324, -0.1594,
+ +0.0272, -0.0249, +0.1742, -0.0705, -0.6673, +0.0315, -0.0686,
+ -0.0554, +0.4494, -0.1243, +0.0745, -0.1677, +0.1072, -0.4070,
+ +0.1072, +0.2513, +0.0360, -0.2995, +0.2032, -0.3525, +0.3108,
+ -0.2647, -0.0185, -0.5729, -0.5350, +0.1348, -0.1505, -0.1331,
+ +0.1911, +0.0579, +0.1075, +0.5838, +0.0835, +0.1951, -0.0697,
+ -0.0039, -0.0510, -0.0248, -0.0074, +0.0340, +0.1015, +0.2119,
+ +0.3729, -0.2766, -0.3635, -0.6286, -0.0736, +0.1996, +0.1481,
+ +0.3434, +0.1094, -0.1140, +0.5084, -0.5502, -0.0116, -0.4196,
+ +0.0949, -0.3190, +0.1712, +0.3119, -0.1757, +0.1424, -0.5219,
+ +0.0941, -0.1334, +0.3036, +0.1787, +0.2328, -0.2946, -0.3538,
+ +0.1910, +0.2116, +0.0395, +0.0577, -0.1220, +0.1180, -0.1978,
+ +0.0592, -0.0584, +0.0025, -0.1686, -0.0445, -0.2022, -0.1837,
+ -0.2602, -0.1407
+ ],
+ [
+ -0.1744, -0.8762, -0.3103, +0.2088, +0.0916, +0.1287, +0.1121,
+ -0.0153, +0.4726, +0.2825, -0.2776, +0.0350, -0.4953, -0.2063,
+ -0.0148, +0.2523, -0.1347, +0.5798, -0.2609, +0.0847, +0.0427,
+ -0.3157, +0.1366, +0.0639, -1.1886, -0.3338, +0.2632, +0.2140,
+ +0.1212, +0.0615, +0.1265, -0.3571, -0.3810, -0.1950, +0.1283,
+ +0.4208, -0.0645, +0.2335, -0.0536, -0.1666, -0.5196, -0.1766,
+ +0.0389, -0.0928, +0.2835, -0.2057, -0.1431, -0.1885, -0.1333,
+ +0.3195, +0.5281, +0.1723, +0.2516, -0.4471, -0.0755, -0.1637,
+ -0.1736, +0.2543, -0.4973, +0.3659, -0.4391, +0.1213, -0.2301,
+ +0.3803, +0.0656, -0.0887, +0.2067, +0.1039, -0.4810, -0.0604,
+ +0.1715, +0.1020, +0.1995, -0.3312, -0.0330, +0.0063, +0.2141,
+ +0.1343, +0.1104, -0.2821, +0.0149, -0.0748, -0.6820, +0.1135,
+ -0.2427, +0.0882, -0.3350, -0.4962, +0.0746, -0.5144, -0.2352,
+ -0.6495, +0.1126, -0.0372, +0.1189, +0.1819, -0.2603, +0.2579,
+ +0.0144, -0.0856, +0.0396, +0.4175, -0.3289, +0.0564, -0.5482,
+ -0.3679, -0.2993, +0.2652, -0.3313, -0.0960, -1.0742, +0.1309,
+ -0.0777, +0.0461, +0.1375, -0.2558, +0.3850, -0.0150, -0.0683,
+ -0.2016, +0.1779, -0.0040, -0.5633, +0.4249, +0.0947, -0.1701,
+ -0.1790, +0.0456
+ ],
+ [
+ +0.2227, +0.3859, -0.5481, +0.3966, -0.1252, -0.1814, -0.3651,
+ +0.0602, -0.0624, -0.1084, -0.0863, -0.1190, -0.3369, -0.2076,
+ -0.0288, +0.0967, +0.1341, -0.1406, +0.1152, +0.1108, +0.1126,
+ +0.0225, +0.0296, -0.2515, +0.0096, -0.3407, +0.1904, +0.0932,
+ +0.1056, -0.2407, -0.3035, -0.6642, +0.0766, -0.0051, -0.1253,
+ -0.0573, -0.1765, +0.0353, -0.0813, -0.0554, +0.0684, -0.1930,
+ +0.3949, +0.5141, -0.2099, -0.1756, +0.2932, +0.0988, -0.3515,
+ -0.0981, +0.2816, -0.2699, -0.0574, +0.1006, +0.1862, -0.2341,
+ +0.0580, +0.0033, -0.5301, +0.1795, -0.4353, +0.2311, -0.4071,
+ +0.0076, -0.3294, +0.1999, -0.0014, +0.0322, -0.0437, +0.2237,
+ +0.1607, -0.0705, +0.1966, +0.1185, +0.0895, +0.0366, +0.2373,
+ +0.3228, -0.0158, +0.1706, +0.2027, +0.2311, +0.1457, -0.0654,
+ -0.1269, +0.1568, -0.1764, +0.2731, -0.1151, +0.1550, +0.0696,
+ -0.3907, -0.0029, +0.0559, -0.0434, +0.2866, -0.5386, -0.0351,
+ +0.1053, -0.4544, +0.4387, -0.2036, +0.3323, +0.1084, +0.1890,
+ -0.1239, -0.0291, +0.0868, -0.2892, -0.4491, -0.0075, +0.2157,
+ -0.4047, -0.1612, +0.1290, -0.2041, -0.3116, -0.0338, +0.3411,
+ +0.3371, +0.0646, +0.1989, -0.4181, +0.0404, -0.6931, -0.5505,
+ -0.1889, -0.0642
+ ],
+ [
+ +0.2256, +0.2926, -0.4043, -0.3903, -0.4751, -0.2227, -0.0575,
+ -0.0882, +0.2724, -0.2748, -0.0479, +0.0765, +0.3881, +0.1026,
+ +0.4699, +0.0094, +0.1006, -0.4406, -0.7706, +0.0133, +0.1709,
+ -0.1822, -0.1068, -0.4774, -0.1233, +0.2721, +0.1207, -0.1251,
+ +0.3195, +0.2374, -0.1329, -0.1427, +0.0076, +0.0051, -0.1095,
+ -0.0654, -0.0352, -0.5934, -0.0047, -0.6171, +0.1857, +0.1955,
+ -0.1583, -0.2563, +0.0400, -0.0183, -0.0950, -0.0957, -0.0747,
+ +0.0212, +0.2658, -0.2555, -0.1685, +0.0820, +0.0191, +0.1119,
+ -0.1408, +0.1895, -0.3520, -0.1373, -0.0728, +0.1701, -0.2122,
+ -0.4124, -0.1474, +0.0735, +0.4498, +0.0624, -0.4918, +0.2062,
+ -0.2238, -0.1642, -0.4840, +0.1531, -0.1195, -0.7067, +0.1031,
+ -0.1102, +0.1100, -0.1363, +0.2572, -0.3112, -0.0680, -0.0723,
+ -0.1689, +0.0442, +0.0321, +0.0800, +0.0119, +0.0997, +0.0725,
+ -0.0631, -0.0758, +0.2844, -0.2049, +0.2828, +0.2275, -0.1323,
+ +0.0606, -0.0013, -0.3762, +0.4734, -0.0862, +0.1600, -0.2358,
+ -0.2673, +0.1551, -0.3200, -0.3787, +0.2681, +0.1187, -0.6766,
+ -0.3171, -0.1608, +0.2374, +0.1025, -0.1801, -0.0285, +0.5813,
+ +0.0297, -0.1882, -0.1819, +0.3774, -0.4983, +0.0110, -0.1292,
+ -0.0681, -0.3819
+ ],
+ [
+ +0.3995, +0.0792, +0.2270, -0.1042, +0.0255, +0.0016, +0.0451,
+ -0.4750, +0.2975, -0.0082, +0.1990, -0.2409, -0.1112, -0.0032,
+ -0.0150, +0.0236, +0.0402, -0.4979, +0.0779, -0.8938, +0.1598,
+ -0.2129, -0.1096, -0.0302, +0.1266, +0.2907, +0.1035, -0.0407,
+ -0.0064, +0.6170, +0.1004, -0.2439, +0.2264, +0.1643, +0.3614,
+ -0.1352, -0.0361, +0.2193, -0.3154, -0.0397, +0.1876, +0.1772,
+ -0.0195, -0.2464, -0.1978, +0.0346, +0.1175, +0.2480, -0.2430,
+ -0.1466, +0.1590, -0.7108, +0.2289, -0.1052, +0.1022, +0.2594,
+ -0.2415, -0.4879, -0.1105, +0.2639, +0.2423, -0.2152, -0.3059,
+ +0.0374, -0.1305, -0.1193, -0.0154, +0.0652, +0.0368, -0.1518,
+ -0.0899, +0.1403, +0.4033, -0.4159, -0.1961, -0.2257, -0.7238,
+ -0.1221, -0.2337, +0.1632, -0.1829, +0.1615, +0.0519, -0.1620,
+ +0.0202, +0.2269, -0.0179, +0.1654, +0.2221, +0.1940, +0.2173,
+ -0.1658, -0.0575, -0.2079, +0.0749, +0.2243, +0.2232, -0.2720,
+ +0.2174, +0.1650, +0.0177, -0.9978, -0.1015, -0.1992, +0.1488,
+ +0.0473, +0.0417, -0.1459, -0.1290, -0.4732, +0.0117, +0.0948,
+ -0.4470, +0.3781, -0.2532, +0.2187, +0.1776, +0.3040, -0.1388,
+ +0.1961, -0.3581, +0.0463, -0.2575, -0.2168, -0.1670, +0.0914,
+ +0.1767, +0.0329
+ ],
+ [
+ -0.0719, -0.0129, +0.1824, +0.1606, +0.0118, +0.4255, -0.3841,
+ +0.0168, -0.2329, +0.2727, -0.0545, -0.0857, +0.2463, -0.0496,
+ -0.1933, +0.1361, -0.3163, -0.1022, -0.4908, +0.2080, -0.8547,
+ -0.0581, +0.0596, +0.0500, -0.0236, -0.4260, +0.1134, +0.3017,
+ +0.3550, +0.2028, +0.0589, -0.1067, -0.2976, -0.0816, -0.2182,
+ -0.3664, -0.4302, +0.0603, -0.2987, -0.0127, +0.1153, +0.5534,
+ -0.5987, +0.1623, +0.2119, +0.1387, +0.4423, +0.2260, +0.2509,
+ +0.0003, +0.1126, -0.3886, +0.4243, -0.2974, -0.4794, -0.1321,
+ +0.0050, -0.3510, -0.1899, +0.1342, -0.0394, +0.2204, +0.2973,
+ +0.0876, +0.0616, +0.0392, -0.0947, +0.4138, +0.1118, +0.1043,
+ -0.1129, -0.1313, -0.2991, -0.0102, -0.5176, -0.2947, +0.2615,
+ -0.4811, -0.5075, +0.4473, +0.2060, +0.3958, -0.0906, -0.3490,
+ +0.2906, -0.1646, +0.2291, +0.2641, -0.0809, -0.4005, +0.4230,
+ +0.1208, +0.1348, -0.3537, -0.8684, -0.3071, -0.2783, +0.4847,
+ +0.2391, +0.3747, +0.0634, +0.0961, -0.6026, +0.2197, -0.1453,
+ -0.5520, -0.2687, -0.0875, -0.2119, -0.1724, -0.2896, +0.3976,
+ -0.1967, +0.3804, -0.1371, +0.0116, -0.0573, +0.1395, -0.2590,
+ +0.5540, +0.4139, -0.1111, +0.0032, -0.5963, +0.1533, +0.1480,
+ -0.0091, -0.0380
+ ],
+ [
+ +0.0012, +0.1069, +0.2834, +0.5471, +0.3943, -1.0956, -0.6526,
+ +0.1492, -0.2587, +0.2581, -0.2517, +0.1173, -0.3567, -0.1059,
+ -0.3055, -0.5180, -0.3182, -0.4056, +0.3925, -0.7240, +0.4440,
+ -0.3679, +0.2120, -0.4817, -0.2700, -0.2675, -0.0082, +0.1994,
+ -0.0305, +0.0769, -0.1151, +0.2111, +0.2388, -0.2470, -0.5172,
+ +0.1661, -0.3072, -0.6651, +0.3812, +0.2448, +0.3609, +0.0592,
+ -0.4010, -0.0854, +0.0913, -0.2651, -0.2003, +0.0285, -0.1954,
+ -0.0110, -0.1873, +0.0350, -0.6736, +0.1600, +0.2878, +0.2839,
+ +0.1939, +0.1168, +0.1899, -0.5686, +0.1056, +0.1304, -0.1370,
+ -0.0459, +0.2497, -0.3285, +0.1665, -0.2200, -0.2023, +0.0026,
+ +0.0299, +0.1613, -0.1322, +0.3270, -0.3678, -0.4051, +0.1920,
+ -0.4154, -0.3370, -0.3895, -0.4571, +0.2233, +0.7171, -0.3209,
+ -0.0292, -0.0030, +0.1388, -0.0513, -0.3499, +0.3362, +1.1707,
+ +0.2713, -0.2278, -0.0987, -0.0367, -0.4828, +0.0630, +0.0861,
+ -0.2023, -0.0871, -0.3521, +0.0436, -0.1448, -0.0160, +0.2777,
+ +0.2555, +0.0985, +0.3363, -0.3503, +0.2365, +0.1922, -0.3820,
+ -0.0583, -0.5146, -0.2775, -0.2208, -0.6312, -0.3039, +0.0200,
+ +0.0497, +0.2308, -0.1536, +0.0240, -0.1044, +0.1552, -0.0842,
+ -0.2783, -0.6521
+ ],
+ [
+ -0.1033, -0.2561, -0.4736, -0.0597, -0.0797, -0.4603, +0.4766,
+ +0.1068, +0.2594, -0.0076, -0.1516, -0.0376, -0.2234, -0.3159,
+ +0.0309, -0.1892, -0.1140, +0.0944, +0.2417, -0.0854, -0.2391,
+ -0.2417, -0.1581, -0.1739, +0.2623, -0.0809, -0.1402, -0.3131,
+ -0.0720, -0.0981, -0.3073, +0.0374, -0.2073, -0.0267, +0.3198,
+ -0.0897, +0.0588, +0.1556, -0.2769, +0.1468, -0.1361, +0.1517,
+ +0.0508, +0.1800, -0.0042, -0.1437, +0.1092, +0.1007, -0.2394,
+ -0.1057, -0.0724, +0.1075, -0.2697, -0.0019, +0.1269, -0.4539,
+ -0.0310, -0.5206, +0.0402, +0.2359, +0.1970, -0.0350, -0.1356,
+ -0.1909, -0.2260, -0.2991, +0.1422, +0.0233, -0.1608, +0.1696,
+ +0.2657, -0.0255, +0.1677, +0.1096, -0.1565, -0.2521, -0.2247,
+ +0.4512, -0.1818, -0.3770, +0.0591, +0.0206, +0.2336, -0.3824,
+ -0.1396, -0.0481, -0.4078, -0.0919, +0.2656, -0.4486, -0.3153,
+ +0.3548, +0.0438, -0.1504, -0.2451, -0.0608, +0.2721, +0.5385,
+ -0.5558, -0.0335, -0.1426, -0.1339, -0.1453, -0.3019, -0.0639,
+ +0.2590, +0.0014, -0.1803, +0.0016, +0.1237, +0.0215, -0.4817,
+ -0.3749, -0.3583, -0.0471, +0.3784, +0.0463, -0.1954, +0.3093,
+ +0.0892, +0.1876, -0.2148, -0.4419, -0.0425, +0.0657, -0.0078,
+ -0.0399, +0.0840
+ ],
+ [
+ +0.2048, -0.0109, +0.1986, +0.0436, +0.0085, -0.2514, +0.0744,
+ +0.3315, -0.2824, -0.1131, +0.2103, +0.2959, +0.1904, +0.1686,
+ -0.2302, +0.0652, +0.2257, -0.0390, -0.1976, +0.4371, +0.3736,
+ +0.1314, -0.0126, +0.3901, +0.2941, +0.3069, -0.0508, +0.1621,
+ +0.0574, +0.0418, +0.0242, -0.0419, +0.1573, +0.0410, +0.0999,
+ -0.4115, -0.5998, -0.2344, -0.0975, -0.2688, +0.3834, +0.1553,
+ -0.1397, +0.3657, -0.0091, +0.3628, -0.1618, +0.2892, +0.0037,
+ -0.2724, -0.1981, -0.2372, +0.1146, -0.3035, -0.1188, -0.0730,
+ -0.0547, +0.2505, +0.2670, -0.2053, -0.1383, -0.1420, +0.2132,
+ -0.1123, -0.0540, -0.0160, +0.0854, -0.0068, +0.1348, +0.0903,
+ +0.2632, -0.2247, +0.2532, +0.0560, -0.3529, +0.0306, -0.0395,
+ +0.0279, -0.1100, -0.0622, +0.2833, +0.4174, +0.3505, +0.1969,
+ +0.2820, -0.2032, +0.4617, +0.1298, +0.4777, -0.0402, -0.2765,
+ +0.2737, -0.1355, -0.0264, -0.1436, +0.1520, -0.0959, +0.2017,
+ -0.0632, +0.4270, +0.2518, +0.4939, +0.1018, +0.0747, +0.1341,
+ +0.0282, +0.2620, +0.0788, -0.3611, -0.2884, +0.0078, +0.2888,
+ +0.3522, +0.2354, -0.2122, -0.2427, +0.2523, +0.1396, -0.0883,
+ -0.3950, -0.2682, -0.0492, -0.0755, -0.2473, +0.4263, +0.1355,
+ -0.0157, +0.1215
+ ],
+ [
+ -0.6594, -0.1441, -0.6773, +0.0221, +0.2166, +0.1332, +0.4537,
+ -0.3027, +0.2430, +0.1959, -0.0301, +0.3205, +0.0271, -0.0874,
+ -0.0352, +0.2214, +0.1944, +0.0452, -0.1779, +0.4921, +0.1605,
+ -0.5882, -0.0086, +0.0444, -0.0399, +0.0324, -0.1361, -0.0327,
+ +0.0511, -0.0984, -0.1174, +0.2776, -0.1695, -0.1711, +0.0936,
+ +0.2987, -0.1364, -0.1538, -0.3138, +0.3584, +0.0546, +0.1571,
+ +0.0399, -0.4413, +0.1119, +0.1473, +0.2313, -0.0097, +0.0350,
+ -0.7444, -0.2951, +0.3243, +0.3613, -0.0437, +0.0579, -0.4394,
+ +0.2956, +0.2459, -0.3762, -0.2147, -0.0802, +0.1008, +0.1602,
+ -0.0851, -0.1126, -0.0523, -0.3132, +0.1352, +0.1302, -0.1389,
+ -0.0498, +0.0982, -0.1858, +0.1293, -0.1504, -0.1349, -0.3510,
+ +0.2715, +0.1284, -0.1167, +0.3469, +0.0383, -0.0128, -0.5008,
+ -0.2260, +0.0122, -0.1545, +0.0764, -0.0789, -0.1429, +0.0672,
+ +0.1962, +0.1719, +0.3646, -0.4545, -0.0100, -0.4631, +0.1818,
+ -0.0828, +0.0147, -0.1522, -0.3076, +0.0254, +0.1547, +0.1381,
+ -0.0803, +0.1292, -0.1365, +0.1041, -0.1373, +0.0217, +0.1911,
+ +0.1273, -0.5073, -0.1208, +0.0419, -0.1274, -0.1256, -0.1218,
+ +0.2354, +0.2424, -0.5111, -0.0158, +0.3000, -0.0153, -0.1388,
+ -0.3299, -0.2895
+ ],
+ [
+ -0.0294, -0.4273, -0.5489, +0.0763, +0.1031, +0.1471, -0.0484,
+ -0.1350, -0.0842, +0.4926, -0.1590, +0.1943, -0.1764, -0.3718,
+ -0.1390, -0.1777, +0.0206, +0.1419, +0.0295, -0.0456, +0.3345,
+ -0.0964, +0.1943, +0.3729, +0.2595, -0.1374, +0.1387, -0.1465,
+ +0.2086, +0.1584, +0.0832, +0.2783, +0.2321, +0.0113, +0.0094,
+ -0.1108, +0.5348, -0.0977, +0.1038, +0.0583, +0.3153, -0.0785,
+ -0.1228, +0.1034, -0.2553, +0.2126, -0.1070, -0.3386, -0.0340,
+ +0.0104, -0.2674, +0.0326, +0.0932, +0.2535, -0.0153, +0.2262,
+ +0.1104, -0.0296, -0.7565, +0.3795, +0.0197, +0.2188, +0.2597,
+ +0.1066, -0.1249, +0.2491, +0.0502, +0.1698, -0.2272, +0.1036,
+ +0.0705, -0.2946, +0.0419, +0.3711, -0.1070, -0.1108, +0.3419,
+ -0.1523, +0.2069, -0.4476, -0.2259, -0.0181, -0.3392, +0.0217,
+ -0.1096, -0.1765, -0.1857, +0.0584, -0.4739, -0.2082, -0.3502,
+ +0.0002, -0.2312, +0.4239, +0.0566, +0.2188, +0.0941, +0.4267,
+ +0.3656, -0.4763, +0.1702, +0.2638, +0.2592, -0.1975, -0.0054,
+ +0.0141, -0.4314, -0.2415, -0.1606, +0.1459, -0.0972, +0.1166,
+ +0.0096, +0.0501, -0.1138, +0.3070, +0.2190, +0.1775, -0.6364,
+ +0.0455, +0.1728, -0.4195, -0.1555, -0.0181, -0.0655, -0.2914,
+ +0.1061, +0.1944
+ ]])
-weights_dense2_w = np.array([
-[ +0.3879, +0.2396, +0.0232, +0.0493, -0.0340, +0.1665, +0.2217, +0.1171, +0.0085, +0.3267, +0.2266, -0.0363, -0.2285, +0.1748, -0.1585, +0.0734, -0.3677, +0.0954, +0.2970, -0.1971, +0.0358, +0.2842, +0.1077, +0.1848, -0.3721, +0.3555, +0.0312, +0.3012, +0.1629, -0.0240, +0.1497, -0.0660, -0.1494, -0.0224, +0.1263, -0.9698, -0.1457, +0.1154, -0.2845, +0.0623, +0.1252, -0.4020, +0.0405, -0.2055, -0.7892, +0.3388, +0.2717, +0.2135, -0.0900, +0.2047, +0.3570, +0.1618, -0.0130, -0.1451, +0.0269, -0.3374, -0.0319, +0.0781, +0.1225, -0.2690, -0.3954, -0.1528, -0.1380, -0.3103, +0.0119, -0.2609, +0.1626, -0.1506, -0.1703, +0.1453, -0.1559, +0.0226, +0.2468, +0.1129, -0.3168, +0.3180, -0.4714, -0.2041, +0.0954, +0.0695, -0.2502, -0.5624, -0.0675, +0.1097, +0.1381, +0.0817, -0.2450, +0.1088, +0.2002, -0.1809, -0.1564, -0.0451, -0.1434, -0.0938, -0.3670, +0.4046, +0.2029, +0.1312, +0.1496, -0.4210, -0.1977, +0.1471, +0.4224, -0.3782, -0.2004, +0.1622, +0.0707, -0.0112, -0.4681, +0.1948, +0.0322, -0.0500, +0.2589, -0.0610, +0.0823, -0.2286, +0.1807, -0.5483, -0.5366, -0.1090, +0.2459, -0.0599, -0.0595, +0.5233, +0.0837, +0.6305, -0.3973, +0.3492],
-[ -0.1334, -0.0525, +0.1074, -0.3238, -0.0303, +0.0381, +0.0375, -0.2776, -0.2203, +0.0472, -0.0031, +0.0020, +0.0296, +0.0328, -0.3609, -0.1506, -0.3898, -0.3399, +0.1574, -0.0749, +0.1668, -0.2909, +0.4024, +0.1138, -0.0228, -0.0884, -0.1580, -0.2851, +0.1364, +0.0736, +0.1732, +0.0582, -0.3385, -0.0205, +0.1458, -0.2729, +0.0598, +0.1277, +0.1406, +0.2345, +0.3031, -0.7386, +0.1244, -0.0150, +0.0451, -0.0418, +0.3890, +0.2390, -0.0930, +0.0282, +0.2572, -0.3782, -0.1127, -0.2627, +0.1525, +0.2133, -0.2603, +0.3870, -0.3704, +0.0680, +0.1075, +0.0063, -0.1415, -0.5181, +0.0323, +0.0563, +0.0615, +0.8169, +0.0176, +0.0858, -0.0934, +0.2120, +0.1557, -0.2070, +0.2223, +0.1712, +0.2042, -0.4291, -0.1514, -0.2126, +0.0720, -0.3121, -0.0420, -0.1002, +0.0914, -0.1049, +0.3737, +0.3156, -0.0343, +0.3863, -0.1249, +0.0459, +0.1408, +0.0087, -0.1110, -0.0767, +0.2177, -0.2325, -0.0777, +0.0536, -0.0612, -0.1087, -0.5225, +0.2759, -0.2000, +0.3127, -0.0211, -0.0045, -0.3404, +0.0398, -0.0767, +0.1566, -0.2795, -0.1252, +0.1945, -0.2738, -0.0554, -0.1285, +0.0640, +0.2618, +0.0349, +0.1813, +0.3157, +0.2025, -0.0145, -0.0113, +0.2274, +0.2284],
-[ +0.0546, +0.1862, +0.1502, -0.2191, +0.1300, -0.4032, +0.0688, -0.1727, +0.2701, -0.0894, -0.0106, +0.0361, -0.0038, +0.0384, -0.3165, -0.0239, +0.2474, -0.1388, +0.0296, +0.0637, +0.1847, -0.2262, -0.0378, +0.3002, +0.0082, -0.3944, -0.0419, +0.1132, -0.0422, +0.1070, -0.0537, +0.1755, +0.1924, -0.0057, -0.4325, +0.4300, +0.4567, -0.2306, -0.3064, -0.7085, -0.4412, +0.0413, -0.0133, -0.1687, -0.2661, -0.3792, -0.3363, +0.0660, -0.6811, +0.2143, +0.2445, +0.0295, -0.3500, -0.3781, +0.1208, -0.2184, -0.2113, +0.1053, -0.1678, -0.2032, -0.1639, -0.1226, +0.4539, +0.0142, -0.3058, +0.1940, +0.2655, -0.3414, +0.1642, -0.1385, +0.0784, -0.4992, +0.0288, -0.1054, -0.1665, +0.1739, -0.0872, -0.0894, -0.2990, +0.2007, -0.1665, -0.0540, -0.0317, -0.2191, -0.3372, -0.4565, -0.3386, +0.1020, +0.0560, -0.2470, +0.6016, -0.1027, +0.3426, +0.1477, +0.0364, +0.4503, +0.4186, +0.3667, -0.0920, +0.3414, +0.0065, -0.3542, +0.0795, +0.2348, -0.1317, -0.0349, -0.0729, +0.2412, +0.0103, -0.1912, +0.0650, -0.2161, -0.0071, +0.1522, +0.0506, +0.0947, -0.1561, +0.3604, -0.1740, -0.0589, -0.3219, -0.0495, +0.0784, +0.1333, +0.0137, +0.1009, +0.0227, -0.0451],
-[ -0.3659, +0.3609, +0.0757, +0.0230, -0.2625, +0.1963, +0.2730, -0.0915, +0.5428, -0.3923, -0.4557, +0.4054, +0.1263, +0.1352, -0.2606, +0.1874, +0.2919, +0.2726, +0.0937, -0.4385, +0.2201, -0.0312, +0.4016, +0.0312, +0.0897, +0.2672, -0.2690, -0.0755, -0.0904, +0.1233, +0.0601, -0.2100, +0.3736, -0.2714, +0.0402, -0.2663, -0.2331, +0.1311, -0.0994, +0.0008, +0.0423, +0.3885, -0.3188, +0.2140, +0.0799, +0.2551, +0.0308, +0.1343, +0.2759, -0.0590, -0.2743, +0.0347, -0.0869, -0.3184, -0.1484, -0.1302, +0.0563, -0.0078, +0.1153, +0.2749, -0.1931, -0.1806, -0.0848, -0.0633, +0.4508, -0.3048, -0.5275, -0.0930, -0.1693, +0.1414, +0.2661, +0.2183, +0.1022, -0.0988, +0.1789, +0.3381, +0.3250, +0.2161, -0.0701, -0.0880, -0.0250, -0.4079, +0.1521, -0.1058, -0.1326, -0.4439, -0.0534, +0.0147, -0.2594, -0.1968, -0.4695, +0.4551, +0.0918, -0.1311, -0.0133, -0.1826, -0.1722, -0.0214, -0.1624, +0.1087, -0.0513, +0.1001, +0.2597, +0.1829, -0.3807, +0.0630, -0.6444, +0.2731, -0.2359, -0.2519, -0.4507, +0.1038, +0.3720, +0.0332, +0.3184, +0.0875, +0.4122, -0.5976, +0.3661, +0.4470, -0.0326, -0.2758, +0.1908, +0.0329, +0.1615, -0.0914, -0.0453, +0.4482],
-[ -0.2430, -0.3549, -0.0276, +0.1378, +0.2154, +0.2232, -0.1917, +0.1653, -0.0327, +0.3117, +0.2781, +0.2424, +0.1836, -0.3393, +0.1929, -0.0290, +0.0036, -0.2437, +0.4067, -0.1402, +0.3959, -0.2194, -0.3789, +0.1764, +0.1075, +0.5430, +0.1783, -0.7655, +0.2199, -0.0012, +0.2896, -0.1150, +0.3509, -0.6355, +0.1095, +0.3083, -0.0508, -0.0598, -0.0387, -0.0025, +0.4012, +0.0249, -0.0440, +0.1306, -0.6685, -0.1638, -0.6928, +0.0289, -0.1748, +0.1177, -0.2184, +0.1238, -0.2337, -0.0699, +0.0479, +0.2468, -0.1428, -0.6832, +0.1362, +0.0542, +0.5767, +0.0347, +0.0209, -0.0161, +0.2824, -0.1168, -0.1527, -0.1239, -0.1223, -0.1625, +0.2880, -0.0471, -0.0704, +0.0848, +0.0982, -0.1967, +0.0792, -0.3727, -0.1337, +0.1517, +0.3242, -0.2300, -0.3668, +0.0836, +0.0464, +0.3718, +0.1789, -0.4262, -0.2959, -0.0873, -0.2063, +0.1702, +0.1758, -0.9966, +0.4564, +0.1455, -0.0353, +0.1924, -0.0855, +0.1689, +0.2077, -0.2827, +0.1126, +0.5277, -0.0065, +0.2269, +0.1638, +0.0831, +0.4475, -0.0235, +0.0283, +0.1552, +0.0741, +0.2731, +0.3797, -0.2383, +0.0321, +0.1676, -0.0378, +0.2820, -0.2878, -0.2193, -0.1462, -0.0376, -0.2963, -0.1336, +0.0065, +0.0854],
-[ -0.0133, -0.0774, +0.1653, +0.1993, -0.1944, +0.2581, -0.5533, +0.1396, -0.0609, +0.1267, +0.3908, +0.4858, -0.3452, -0.6476, -0.1710, +0.0953, -0.0442, +0.1262, -0.5125, +0.2027, +0.3703, +0.1319, -0.1080, -0.2917, +0.2201, -0.2632, +0.2595, +0.2278, +0.6085, -0.0118, +0.0925, +0.3054, -0.0123, +0.2886, -0.1033, -0.0968, +0.0884, +0.0583, -0.1286, -0.2528, -0.2092, +0.3955, -0.2216, +0.1546, +0.1519, +0.1909, +0.3702, -0.0994, +0.0918, -0.4807, +0.1935, +0.0671, +0.4320, +0.1125, +0.2946, +0.1016, +0.2781, +0.0859, -0.0694, -0.0845, +0.6580, -0.3224, +0.0815, -0.0230, +0.1600, +0.3728, +0.0250, +0.4401, +0.0357, -0.0074, -0.1148, -0.3906, +0.0645, +0.1275, +0.0094, +0.1263, -0.3057, -0.2418, +0.0812, -0.0549, -0.2169, +0.3138, -0.1004, +0.0720, -0.3993, +0.2240, -0.2293, -0.6645, +0.0360, +0.2128, -0.2250, +0.1115, +0.3698, +0.1463, +0.2279, +0.1816, +0.0021, +0.2644, -0.0813, -0.3536, +0.3171, -0.0141, +0.1692, -0.0735, +0.1099, -0.0055, -0.9204, -0.6968, -0.0667, -0.4571, -0.2269, -0.1844, +0.2342, +0.0805, +0.1731, -0.0038, -0.0085, -0.0471, -0.8529, -0.1257, -0.1424, +0.2724, -0.5343, -0.1496, -0.0828, +0.0974, -0.1696, +0.1288],
-[ +0.1253, -0.1387, +0.1862, +0.1052, -0.0798, +0.2158, +0.0780, +0.0028, -0.1907, +0.0812, +0.4299, -0.1405, +0.0977, +0.0346, -0.3432, -0.0439, +0.4926, +0.2405, -0.2341, -0.4948, -0.2674, +0.2975, -0.1626, -0.0767, -0.1164, -0.0418, -0.1568, +0.0083, -0.4281, +0.0491, -0.8546, +0.2168, -0.1845, +0.1116, +0.0233, -0.3213, -0.2366, -0.3144, +0.1870, -0.1365, +0.0464, +0.2936, +0.3069, +0.4470, -0.4670, -0.1529, -0.3486, -0.0822, -0.0776, +0.0347, +0.0510, +0.4063, -0.2823, +0.3495, +0.0887, +0.2299, -0.0561, -0.2744, +0.3720, +0.0752, +0.1584, +0.0464, -0.6384, +0.2085, -0.0736, -0.1031, +0.0997, +0.0094, +0.1853, -0.1647, +0.3305, -0.5368, +0.1890, -0.2845, +0.0550, +0.2342, +0.2572, +0.0622, +0.0434, -0.0867, -0.4546, -0.0118, +0.1483, -0.0886, -0.1938, +0.0504, -0.1731, +0.4389, +0.0260, -0.1393, -0.3271, +0.0401, +0.3255, +0.0470, -0.1401, -0.2314, +0.0622, -0.4021, -0.1835, +0.3193, +0.4884, +0.0147, -0.2552, +0.0416, -0.2928, -0.2332, -0.5361, +0.2024, +0.1249, -0.1697, -0.0577, +0.2168, -0.0566, +0.2298, +0.1822, -0.0007, +0.0391, -0.1377, +0.0574, +0.0774, -0.3464, +0.0214, -0.2252, -0.0265, -0.6877, +0.4879, -0.4100, +0.2385],
-[ +0.1236, +0.0376, -0.2100, +0.1883, +0.6826, +0.0220, -0.1377, -0.5746, +0.2344, +0.0867, +0.0319, +0.0259, -0.2913, +0.0787, +0.3157, -0.0364, -0.1010, +0.1857, -0.2598, -0.5244, -0.1616, -0.2685, -0.0613, -0.1655, +0.0230, -0.9140, +0.1744, +0.1221, -0.0847, +0.1691, +0.3710, -0.3452, -0.3138, +0.2219, +0.0426, +0.2347, -0.1529, +0.1309, +0.0586, +0.4190, +0.2861, -0.2072, +0.1766, -0.3183, -0.2827, +0.0666, +0.2583, -0.0261, -0.2540, +0.0545, -0.6264, +0.0025, +0.4261, +0.0022, -0.0614, +0.3319, +0.3828, -0.1452, -0.5253, -0.1200, +0.0946, -0.0143, +0.2909, -0.0688, -0.0306, +0.0080, +0.0100, -0.1666, -0.5132, -0.0863, +0.2882, -0.1029, -0.3055, +0.0813, -0.5334, +0.0466, -0.5523, +0.2712, +0.1460, -0.2548, +0.0861, -0.4035, -0.0165, +0.3279, +0.0435, -0.0565, -0.3307, +0.3140, +0.0406, -0.3739, +0.3179, -0.0782, +0.1537, -0.0256, -0.0541, +0.2213, -0.0156, +0.0488, +0.1589, -0.2548, +0.2501, -0.2476, -0.0498, +0.1194, -0.1299, -0.1299, +0.0690, +0.1347, -0.2261, +0.0083, -0.5431, -0.0652, -0.3608, -0.0647, -0.4625, -0.2278, -0.0067, +0.2591, -0.0100, +0.1405, +0.1602, +0.1952, +0.2865, -0.1792, -0.2396, +0.2345, -0.4069, -0.2045],
-[ +0.1412, -0.0696, +0.2341, +0.0624, -0.0594, -0.2349, -0.1230, -0.1535, +0.3358, -0.1074, -0.3703, -0.0583, +0.1001, +0.1808, +0.1181, +0.0321, +0.0653, +0.2051, +0.2186, +0.2763, +0.2867, -0.0883, -0.1351, +0.0331, +0.0249, +0.1005, +0.1122, -0.1683, -0.3847, -0.0855, -0.0645, -0.0530, -0.4018, -0.1309, +0.3548, +0.1746, -0.0786, -0.2527, -0.3668, -0.2196, +0.1073, +0.0013, +0.1540, -0.1488, -0.2231, +0.2583, +0.0985, +0.1557, -0.0295, +0.0735, +0.1870, +0.1670, +0.1750, +0.1122, +0.0238, -0.1360, +0.0549, -0.0896, +0.3355, +0.0450, -0.1712, -0.0521, -0.0163, +0.1979, -0.0057, +0.3001, +0.2147, +0.2500, +0.2662, +0.0464, +0.2511, -0.6088, +0.1502, -0.2170, +0.1770, +0.2396, +0.0731, -0.1072, -0.1218, -0.1094, +0.4303, +0.2937, +0.3561, -0.4019, +0.1205, +0.2295, +0.2342, +0.6585, -0.0954, +0.2403, -0.0643, +0.1362, -0.5167, +0.2533, -0.1717, -0.0405, -0.6613, -0.0652, -0.0399, +0.1727, +0.2228, +0.1647, +0.2706, +0.1907, +0.1552, +0.1832, +0.0371, -0.1880, +0.3491, -0.1936, +0.3391, -0.2626, +0.0834, -0.0342, -0.0088, +0.3202, +0.3206, -0.1806, +0.0846, +0.0579, -0.3797, +0.0252, -0.0016, -0.1575, -0.0163, -0.1510, -0.2674, +0.5437],
-[ -0.4375, +0.0691, +0.0132, -0.1952, +0.3240, -0.5280, -0.2317, +0.0060, +0.0420, +0.0655, +0.1332, -0.1609, +0.6019, +0.3035, -0.0744, +0.1198, +0.0335, +0.2761, +0.0182, +0.1792, -0.1436, +0.2985, -0.1630, -0.0314, -0.3092, -0.3348, -0.4410, +0.4206, -0.5009, -0.1961, -0.0061, +0.0646, +0.0028, -0.2830, +0.3189, +0.1332, -0.6681, -0.3721, +0.1576, -0.2649, -0.2122, -0.3793, -0.0257, +0.1096, -0.4736, -0.3285, -0.1774, +0.1045, -0.0412, -0.1999, -0.0392, -0.1256, -0.4455, -0.1380, -0.0893, -0.0456, -0.1794, +0.3297, -0.3258, -0.1020, -0.0237, +0.0481, -0.0306, -0.3762, +0.0582, +0.1159, -0.6488, +0.1295, -0.5503, +0.2942, -0.1794, +0.2656, -0.3145, +0.0916, -0.1934, -0.3004, -0.0553, -0.1828, +0.1933, -0.1394, -0.4347, +0.0881, -0.0648, +0.4279, -0.5049, -0.2819, -0.0962, -0.1774, -0.1217, +0.0309, +0.1803, -0.5215, +0.0935, -0.0073, -0.0846, -0.3536, -0.1036, -0.0593, -0.0982, +0.1005, -0.2521, -0.2301, -0.0937, +0.1199, +0.0164, -0.1238, -0.0819, -0.1452, -0.2476, -0.2147, +0.2090, -0.3116, +0.1075, +0.0734, -0.1381, +0.5389, -0.2394, -0.0474, -0.3343, +0.3611, -0.1414, -0.2948, +0.2472, +0.0805, +0.1058, -0.2458, -0.5851, -1.0465],
-[ -0.0729, -0.0000, -0.5724, +0.0407, +0.0246, -0.0118, -0.1285, -0.9905, +0.1176, +0.2563, -0.0043, -0.0942, +0.2825, -0.0513, +0.2612, +0.1671, -0.4420, +0.1831, -0.1955, +0.4174, -0.4772, +0.2477, -0.2401, -0.0887, -0.1148, -0.1394, +0.2506, -0.0922, +0.0623, -0.2368, -0.1567, -0.1732, +0.0966, +0.3062, +0.0234, -0.1121, +0.0395, +0.0600, -0.0824, +0.3137, +0.0234, +0.0647, +0.3534, -0.2083, +0.2899, +0.0567, -0.1504, -0.0071, -0.1387, +0.2099, -0.2346, -0.5326, +0.0601, -0.1498, +0.1787, +0.2529, -0.0069, -0.2794, +0.2950, -0.1160, +0.1059, +0.0679, +0.1995, -0.2776, +0.5507, -0.1011, -0.3149, -0.0066, +0.0007, -0.2899, -0.2901, -0.0797, -0.5042, +0.0141, -0.1412, -0.1831, -0.1403, +0.2004, -0.2061, -0.0208, -0.0286, -0.4134, +0.1362, +0.1245, +0.1593, -0.5630, -0.1738, -0.2171, +0.4737, -0.1202, -0.2229, +0.1831, +0.1676, -0.3322, -0.2468, -0.2791, -0.9385, +0.2221, -0.1161, +0.0797, -0.0176, +0.0949, +0.3332, -0.2890, -0.1364, +0.0956, +0.0007, -0.1070, -0.5448, -0.2041, +0.2900, +0.6012, +0.0403, +0.3847, +0.0888, +0.0928, +0.2970, +0.0699, -0.1121, -0.2804, +0.0752, +0.0984, -0.0516, +0.0121, -0.1547, +0.0065, +0.0952, -0.6576],
-[ -0.1941, +0.1027, -0.0436, +0.2440, -0.3934, +0.0835, +0.0386, +0.4993, +0.3126, -0.2644, +0.0530, +0.0557, +0.2344, +0.2061, +0.1085, -0.0502, -0.3185, +0.2997, +0.1358, -0.0412, -0.1765, -0.0993, +0.2982, -0.0366, -0.1480, +0.0941, +0.1698, -0.0107, +0.1538, -0.2916, -0.1777, +0.1294, -0.3267, -0.2505, +0.1930, +0.4406, +0.1421, +0.1251, -0.1535, -0.5110, +0.2285, -0.5197, -0.3456, -0.3984, -0.1507, +0.2693, -0.0057, +0.1237, +0.5077, -0.5996, -0.0316, +0.0890, -0.1346, -0.0719, +0.5849, -0.0047, -0.1471, -0.2270, -0.3822, -0.2037, +0.4138, -0.0996, +0.2080, -0.0058, +0.1905, -0.1074, -0.0531, +0.1024, +0.0889, -0.1927, +0.3300, +0.1352, -0.3513, -0.0935, +0.1051, +0.0342, +0.6585, +0.2677, +0.0296, +0.1483, +0.0249, +0.0613, -0.0130, +0.1439, -0.6456, -0.2417, +0.1079, +0.0304, -0.2229, -0.2422, -0.3059, -0.2534, -0.0870, +0.0549, +0.5176, -0.2529, +0.2052, -0.4333, +0.3257, -0.6656, +0.0274, -0.0220, +0.3784, +0.3136, +0.0937, -0.2548, -0.0259, +0.4648, +0.0983, +0.0135, +0.0472, -0.0407, +0.0268, -0.0681, -0.2091, +0.1238, -0.0575, -0.3694, +0.2273, +0.2093, -0.0348, -0.1528, +0.1878, -0.3958, -0.0159, +0.0110, +0.1729, +0.0470],
-[ -0.1267, -0.3113, +0.1357, +0.1027, +0.2379, -0.0068, +0.4349, -0.0623, -0.5615, -0.1304, +0.1250, -0.3323, +0.3609, +0.4355, -0.2552, +0.3060, +0.0983, -0.0872, -0.0180, +0.1222, +0.0775, -0.1083, +0.0396, -0.1034, -0.0120, -0.3544, +0.2029, -0.2021, +0.2533, +0.2070, +0.1599, -0.0763, -0.2680, -0.0949, -0.2347, -0.3042, -0.1092, -0.5819, +0.0953, -0.2701, -0.1846, -0.2815, +0.0169, -0.1685, +0.3497, -0.4498, +0.1862, +0.2418, +0.2738, -0.1878, -0.6743, -0.2682, +0.1436, +0.0281, -0.0953, +0.3988, +0.0264, +0.2932, +0.0583, -0.1579, +0.6084, +0.2165, +0.5541, -0.0631, +0.0807, -0.2303, +0.3342, -0.2916, -0.0861, +0.0810, -0.1595, -0.4391, -0.2134, -0.1567, -0.5746, -0.2862, -0.0570, -0.0424, -0.0724, +0.0939, -0.4046, -0.3838, -0.0559, +0.3115, +0.2509, +0.1488, -0.2606, +0.1532, -0.1418, -0.1425, -0.3906, -0.0388, -0.1576, +0.2442, +0.0740, -0.0508, -0.0483, +0.2111, -0.2049, -0.2607, -0.4858, +0.2897, -0.0702, +0.0321, +0.0956, -0.1905, -0.4853, +0.1617, +0.2493, -0.1314, -0.4004, -0.2519, -0.4157, +0.0929, +0.0758, +0.3717, -0.0497, +0.3306, -0.1561, +0.2532, +0.0411, -0.4520, +0.2099, +0.2967, +0.1842, +0.1563, -0.1585, -0.1759],
-[ -0.0254, -0.0619, +0.3396, -0.0740, -0.0445, -0.1535, +0.1428, -0.3223, -0.3919, +0.4651, +0.0604, +0.0437, +0.0966, +0.1825, -1.2489, -0.0932, +0.4027, -0.2825, -0.1588, -0.4097, -0.0175, -0.0916, +0.1347, -0.2389, +0.4690, +0.1414, -0.3526, +0.0226, -0.3026, -0.0544, -0.6268, +0.2633, +0.1651, -0.4040, -0.1251, +0.3515, +0.4103, -0.4826, +0.0880, +0.1935, -0.2374, +0.1883, +0.2930, -0.0785, +0.0563, -0.2351, +0.1083, +0.0530, -0.4314, +0.3210, +0.3915, +0.3193, +0.3019, +0.2164, -0.0151, -0.0877, +0.2483, +0.0276, +0.2023, -0.5203, +0.2165, -0.5460, -0.6132, -0.3681, +0.5059, -0.8269, -0.5508, -0.7987, -0.4734, +0.3606, -0.0343, -0.4660, +0.2890, +0.1699, -0.0946, +0.1705, +0.1884, +0.5705, -0.6233, +0.1696, +0.1865, +0.1485, +0.3090, +0.1678, -0.2003, +0.4189, -0.6977, -0.4489, -0.2648, +0.3523, +0.0024, -0.0019, -0.4196, +0.6541, +0.0061, -0.1462, +0.2370, +0.3574, +0.0846, -0.0241, +0.4114, -0.3442, -0.4623, -0.2267, +0.2023, -0.3360, +0.0956, +0.0317, +0.1955, -0.1893, -0.0042, +0.4674, -0.1063, -0.1893, -0.2424, +0.2492, -0.1736, +0.3326, +0.2834, +0.5649, -0.3040, -0.0840, -0.3259, -0.0314, -0.3128, -0.0751, +0.0886, +0.2745],
-[ -0.0964, +0.0265, -0.0213, -0.1072, +0.1414, -0.2006, -0.1852, -0.0680, -0.3082, -0.0446, +0.0275, +0.2967, +0.3372, +0.3806, -0.3462, -0.0765, +0.3793, -0.1660, -0.1671, +0.1254, +0.0304, +0.2077, +0.1840, -0.0107, -0.5985, +0.0081, +0.3911, -0.0964, -0.0192, -0.3845, -0.1633, +0.0627, +0.1709, -0.5199, -0.0662, +0.2973, -0.0476, -0.0106, +0.2571, -0.4352, -0.0863, -0.0472, +0.0214, -0.1154, -0.7335, +0.0613, -0.0339, +0.1994, +0.1911, +0.2564, -0.0221, -0.1719, -0.0692, +0.1077, +0.0255, +0.2926, +0.2895, -0.2671, +0.0639, -0.0263, +0.1419, +0.0450, -0.1025, -0.0003, +0.0131, +0.0963, -0.0279, -0.1671, -0.3886, -0.2855, +0.0036, +0.1207, +0.0048, -0.2887, +0.0294, -0.2211, +0.3091, -0.0269, +0.0516, -0.6725, +0.3413, -0.1767, +0.1770, -0.0460, -0.2211, -0.2099, +0.0021, -0.1276, -0.0644, +0.1490, -0.1115, +0.2595, -0.3224, -0.4780, +0.0815, -0.5460, -0.0702, -0.3853, -0.0679, -0.1372, -0.0327, +0.1929, -0.3156, -0.2680, +0.3684, -0.4465, -0.1663, +0.1810, -0.1622, -0.0172, +0.0767, +0.0161, -0.1824, +0.4669, -0.5076, -0.2199, -0.0133, +0.3653, +0.2747, -0.0800, -0.3138, -0.0949, +0.2533, -0.0900, +0.1011, +0.2880, +0.1251, -0.1881],
-[ -0.0063, +0.1103, -0.1303, -0.0870, +0.0031, -0.2372, -0.1525, -0.1338, -0.1362, -0.1119, -0.2048, -0.5003, -0.4117, -0.1900, +0.2692, +0.0322, -0.2947, -0.0933, +0.4165, -0.1908, -0.2739, -0.2490, +0.0153, +0.2060, -0.3180, -0.0127, -0.2742, -0.6272, +0.1028, +0.0392, +0.0631, +0.4220, -0.0728, -0.0180, +0.0193, +0.2475, -0.4501, -0.2177, +0.0264, -0.3409, -0.1080, +0.1319, +0.2073, -0.1404, -0.1683, +0.0385, +0.4418, -0.0943, +0.3003, -0.4947, -0.3381, +0.0047, -0.1739, +0.0727, -0.0840, -0.0679, -0.6355, -0.1313, -0.5041, +0.1045, +0.5695, +0.3238, +0.1534, -0.0200, -0.4393, -0.0425, -0.1652, +0.0850, -0.2406, -0.2257, +0.0294, +0.4809, -0.2471, -0.0967, +0.2424, -0.5018, -0.2205, -0.1493, +0.0341, -0.1234, -0.1192, -0.5870, -0.2536, -0.1993, -0.1386, +0.0683, -0.3497, +0.0733, +0.2698, -0.1142, -0.0668, +0.1648, -0.3611, -0.0740, -0.3633, +0.4252, -0.2167, -0.1510, +0.0723, +0.1177, -0.1335, -0.0920, +0.1246, +0.0240, -0.1628, +0.3220, +0.2826, +0.1347, -0.3111, -0.1399, -0.2744, -0.2070, -0.0708, +0.0089, -0.2029, -0.2701, +0.0167, +0.2531, +0.0292, +0.5538, +0.5037, -0.0892, -0.1198, -0.1806, -0.1155, +0.0682, +0.0992, +0.1278],
-[ -0.3892, -0.4112, +0.0692, -0.0743, +0.0754, +0.1185, -0.1115, +0.0526, -0.1577, -0.3541, -0.1263, -0.0474, -0.5270, -0.1722, -0.5393, +0.3133, +0.2965, -0.0296, +0.1989, -0.2590, +0.0554, +0.0375, +0.1727, -0.8208, -0.0429, -0.1936, +0.1494, -0.1485, +0.2725, -0.1334, -0.1841, +0.3110, -0.2692, -0.8445, +0.1759, +0.1046, -0.0473, -0.2881, -0.0947, +0.0488, -0.1750, -0.1608, +0.0893, +0.1647, -0.5554, -0.2797, -0.7124, -0.6744, -0.2102, +0.1397, +0.0133, +0.1617, -0.1435, +0.0960, -0.1028, -0.0140, -0.0536, -0.1890, +0.2581, -0.2165, -0.1061, -0.1182, +0.2503, +0.5655, -0.3958, +0.0204, +0.2095, +0.3389, -0.1195, +0.0742, +0.3064, -0.4154, -0.0185, +0.2993, -0.4896, -0.4842, +0.0000, +0.2412, +0.1470, +0.2875, -0.0558, -0.3003, -0.1561, +0.2015, -0.4600, +0.2405, -0.5617, +0.0419, +0.0919, -0.0401, -0.1036, -0.4643, -0.3563, +0.0631, +0.2055, +0.1592, +0.4003, -0.1694, +0.0298, +0.0438, +0.0447, +0.1505, +0.2846, -0.2341, +0.2087, +0.0529, +0.1660, -0.2887, -0.4005, -0.0296, -0.2068, -0.0832, -0.1425, -0.0368, -0.0351, +0.2398, -0.0911, -0.1891, -0.7638, -0.0778, -0.1400, -0.1751, -0.3126, +0.1764, -0.0813, -0.2103, -0.2434, +0.0032],
-[ -0.0357, -0.2668, -0.1127, +0.0598, +0.2980, -0.0779, +0.1944, -0.2414, +0.1748, +0.1547, -0.1568, +0.3791, -0.1141, -0.5528, +0.0845, +0.0841, -0.6744, +0.1313, -0.2061, +0.1047, +0.1434, -0.1319, -0.2199, -0.0972, -0.0120, -0.0425, -0.3748, +0.1776, +0.1601, -0.0042, +0.2022, -0.3657, +0.1848, -0.0978, -0.1360, +0.0169, -0.1384, +0.0957, -0.2801, +0.3112, -0.3811, -0.1796, -0.1115, -0.1707, -0.2593, +0.1178, -0.1374, +0.1978, -0.4550, +0.1624, -0.7096, +0.0412, +0.2822, -0.1694, -0.1609, +0.2064, -0.0363, -0.1055, -1.1760, -0.0517, +0.3019, -0.1031, -0.0140, +0.4577, -0.2882, -0.0930, -0.0780, +0.1255, -0.0155, +0.0442, +0.1144, -0.0569, -0.3376, -0.0483, +0.0346, -0.4206, -0.0416, +0.3018, -0.1322, +0.1616, -0.4345, -0.8509, +0.4203, -0.1752, +0.4466, +0.0259, +0.2046, -0.1646, +0.1396, +0.0633, +0.2265, +0.0700, -0.0138, -0.1109, -0.7053, -0.0275, +0.0227, +0.0829, -0.4602, -0.2059, -0.1101, +0.1778, -0.3476, +0.2725, -0.6471, -0.8565, -0.1445, +0.0229, -0.0902, -0.0000, +0.1050, +0.1833, +0.0342, +0.1775, +0.1618, -0.1348, +0.2888, -0.1435, -0.3121, -0.0145, -0.0838, +0.1918, -0.0012, +0.2892, +0.0822, -0.3897, -0.1889, +0.3133],
-[ +0.0687, -0.1425, -0.2918, -0.0124, -0.1191, +0.5113, -0.0458, -0.2026, +0.1903, -0.2631, -0.1719, -0.0891, +0.1167, -0.4310, +0.1749, +0.0637, -0.2985, +0.0289, +0.0650, +0.0673, -0.2936, -0.1160, +0.0858, +0.1307, -0.3330, -0.8444, +0.4467, +0.2170, +0.0191, +0.2063, +0.3432, +0.3044, +0.1887, -0.0953, +0.1251, +0.2465, -0.0316, -0.1012, +0.3532, -0.0733, -0.5563, +0.0876, -0.0479, +0.2727, -0.1127, -0.0031, +0.2553, +0.2084, -0.1991, +0.0461, +0.2093, -0.1241, -0.1590, -0.2749, -0.3333, +0.2033, -0.5573, +0.0258, -0.0032, +0.0843, -0.1145, +0.2153, +0.1418, -0.1910, -0.0054, +0.0351, +0.1492, +0.3882, -0.0541, -0.3486, -0.2434, -0.2268, +0.3660, +0.1080, -0.3659, +0.0102, -0.1396, -0.1952, +0.0272, -0.2913, -0.3832, -0.0728, -0.3145, +0.0215, -0.4121, -0.3307, +0.4352, -0.0253, -0.0588, +0.0272, -0.1483, +0.1393, -0.0073, +0.1142, -0.0115, +0.1358, -0.1048, -0.1909, +0.1376, +0.2979, -0.5140, -0.0762, +0.0734, -0.2475, +0.1982, +0.1673, -0.0969, -0.0437, -0.3698, -0.1260, +0.0262, +0.0649, +0.4337, -0.1104, -0.1702, -0.0254, +0.0276, +0.1572, -0.1630, -0.0185, +0.0140, -0.0844, +0.2117, +0.0716, +0.0515, -0.0174, -0.6157, -0.0414],
-[ +0.4181, -0.1027, -0.5953, -0.2716, +0.0776, +0.0781, -0.5109, +0.1030, +0.2771, -0.0260, +0.0929, -0.2771, -0.4549, +0.0623, -0.3257, -0.0775, +0.1166, +0.1562, -0.0574, +0.3033, +0.1967, -0.0404, +0.0676, -0.0867, -0.3187, -0.0758, -0.0009, -0.0113, -0.0341, +0.0605, -0.4264, -0.6552, +0.1799, +0.0700, -0.0374, -0.0114, -0.1146, +0.0999, -0.0757, -0.1578, +0.1074, +0.3107, +0.1008, +0.1590, +0.1258, -0.0781, -0.1203, -0.0616, +0.3600, +0.0990, -0.2904, +0.1173, +0.1832, -0.0751, -0.1231, +0.1683, -0.0037, -0.2329, +0.1468, +0.0243, -0.1334, -0.0890, +0.0893, -0.1151, -0.2679, +0.0001, +0.2118, +0.1272, -0.1189, -0.0188, -0.3389, +0.4803, -0.0542, -0.0435, +0.2108, -0.0349, +0.0001, -0.1910, +0.2580, +0.1186, +0.0134, +0.2241, +0.1215, +0.0804, +0.1249, -0.4045, -0.7299, +0.2040, +0.1098, +0.1849, -0.2002, -0.3071, +0.3402, +0.0603, -0.4271, -0.0413, -0.1134, -0.1907, -0.0385, -0.1099, -0.2834, -0.2318, -0.0175, +0.1223, +0.0880, -0.1988, -0.1323, +0.0046, -0.2709, -0.2632, -0.1952, +0.0714, -0.2587, +0.0643, -0.4457, -0.0552, +0.1938, +0.0585, +0.3212, -0.1974, +0.1730, -0.0263, +0.0388, +0.0617, +0.2161, -0.1703, +0.1905, +0.2715],
-[ +0.0930, +0.1679, +0.2751, -0.1692, -0.1356, +0.2604, +0.0225, +0.1217, -0.2549, -0.3477, +0.2173, -0.3041, -0.1303, -0.0979, +0.2413, -0.7162, -0.1729, -0.0653, +0.0465, +0.2631, +0.1323, +0.0231, -0.0955, -0.4612, +0.1609, -0.2387, -0.1092, +0.2000, -0.4562, -0.0711, -0.0483, +0.3552, +0.0795, +0.1893, -0.6706, +0.0193, +0.0274, +0.2531, +0.2990, +0.2438, +0.0986, -0.1109, -0.2137, +0.4588, +0.3006, -0.3244, -0.3664, +0.2272, -0.1332, +0.0289, -0.2323, +0.0689, +0.1008, -0.5734, +0.0855, +0.0575, +0.2418, -0.0182, -0.4540, -0.2439, +0.0172, -0.4748, -0.1435, +0.0309, +0.0632, -0.2346, +0.2038, -0.0480, -0.7751, -0.0894, +0.0641, +0.1264, -0.1953, -0.0275, -0.3926, +0.1423, +0.2923, +0.1021, +0.1765, -0.1492, -0.1441, -0.0768, -0.1498, +0.1910, +0.1953, -0.2800, -0.1201, -0.0883, +0.2172, +0.3554, -0.1773, -0.4483, -0.3244, -0.1744, -0.3018, -0.2011, -0.2264, -0.0428, +0.0575, +0.0580, -0.5973, +0.1492, -0.0185, +0.1127, -0.1138, -0.0385, +0.2036, +0.2093, +0.0063, -0.1820, -0.1950, +0.0582, -0.3649, +0.3262, +0.1356, -0.0211, +0.0755, +0.2815, -0.3010, +0.0102, -0.0880, +0.0170, +0.2470, -0.2187, -0.3712, +0.1006, +0.1422, +0.0947],
-[ +0.3506, -0.4573, +0.0702, -0.0522, +0.0911, +0.3024, +0.0056, -0.2354, -0.0218, +0.0672, +0.2162, -0.2104, -0.5043, +0.2148, -0.0611, +0.2639, -0.3746, -0.1468, +0.2605, -0.0543, +0.2585, +0.3026, -0.2448, +0.0680, +0.3110, -0.3245, -0.0491, +0.0020, -0.2954, +0.1172, +0.0233, -0.1470, -0.1321, +0.2758, -0.0839, -0.0035, +0.2861, -0.2431, +0.1937, +0.1139, -0.5602, -0.4088, -0.1855, -0.9253, +0.0596, -0.0578, -0.2868, +0.1480, +0.2077, -0.0143, -0.0022, -0.0470, +0.2199, +0.0734, +0.1023, -0.1480, +0.1836, +0.3319, -0.1966, -0.0147, +0.0555, +0.0199, -0.2619, +0.1983, -0.0588, -0.5989, -0.3336, +0.0868, +0.1067, -0.2179, -0.3378, +0.1768, +0.3373, +0.3508, -0.2344, +0.0236, -0.1659, +0.2833, -0.5192, -0.2062, -0.0494, +0.2147, +0.0610, +0.2614, +0.0845, +0.5961, +0.1163, +0.3691, +0.1669, -0.2602, -0.1245, -0.1340, -0.1114, -0.6348, -0.2305, +0.3599, +0.0009, +0.0564, -0.1984, +0.2478, +0.0851, -0.4090, +0.0749, -0.1386, +0.1885, -0.2480, -0.1254, -0.1255, +0.0577, -0.0142, +0.0102, -0.4250, +0.2373, -0.3827, -0.0171, -0.1978, -0.2941, +0.2472, -0.2591, -0.6289, +0.4534, -0.2792, -0.4134, +0.1043, +0.2448, -0.1319, -0.1174, -0.1580],
-[ -0.2358, +0.2350, -0.3523, +0.2959, -0.0367, -0.0344, -0.3328, +0.4840, -0.3630, +0.1661, +0.1186, -0.2251, +0.0232, +0.2081, -0.0328, -0.0450, -0.2070, +0.5389, +0.1277, -0.4275, -0.2921, +0.1255, -0.4076, +0.2065, +0.2672, +0.2073, -0.0296, -0.4819, +0.2005, +0.0445, +0.0668, +0.0876, +0.3081, -0.3881, -0.0585, -0.6874, -0.0974, -0.0301, +0.1855, +0.3814, +0.1201, +0.1938, -0.0995, +0.0912, -0.6631, +0.2574, -0.0729, +0.3474, -0.0604, -0.3329, -0.0358, -0.9523, -0.4813, -0.3228, -0.4234, -0.4660, -0.1092, -0.0337, +0.1697, -0.2094, -0.1469, +0.2326, -0.5977, +0.0475, -0.3922, -0.4437, -0.3288, +0.3193, -0.7914, -0.0176, +0.0502, -0.0523, -0.2862, -0.2429, -0.1000, +0.4249, -0.3641, +0.1861, +0.1024, +0.0054, -0.2030, -0.0398, -0.2410, -0.3862, -0.2337, -0.0892, -0.3876, -0.0436, +0.1507, -0.0999, -0.3943, -0.9435, +0.5505, +0.1834, -0.0167, -0.0586, +0.0693, +0.1642, -0.5236, -0.1637, +0.1487, -0.8338, -0.0206, +0.2822, -0.2105, -0.0160, +0.3280, -0.1025, -0.3180, -0.3722, +0.0884, -0.2718, +0.0536, -0.2959, -0.3745, -0.2457, +0.0991, -0.4547, +0.4061, +0.0624, -0.0080, -0.1087, +0.2008, -0.1034, -0.0891, -0.6337, +0.3613, -0.0931],
-[ -0.6200, -0.1166, -0.4242, +0.3230, +0.0424, +0.1713, -0.0952, -0.1583, -0.1884, -0.1920, +0.2690, +0.0879, +0.3036, -0.2299, +0.1667, -0.0614, +0.1718, +0.4005, -0.0414, -0.2480, -0.0757, +0.0657, -0.5465, -0.0342, -0.3754, -0.0016, -0.2577, -0.1944, -0.4532, +0.3159, +0.2805, +0.0208, +0.3891, +0.4252, -0.1674, -0.1789, -0.6264, +0.2770, +0.2155, -0.0509, -0.0612, -0.0500, -0.3067, +0.1948, +0.2282, +0.1876, -0.2081, +0.0926, +0.2432, -0.1317, +0.2425, -0.3167, +0.1566, +0.2607, -0.1562, -0.5820, +0.2781, +0.2699, -0.0476, -0.2564, +0.5402, +0.1399, -0.0323, -0.2961, +0.1806, +0.1641, +0.3719, +0.0294, -0.0031, +0.0016, -0.0585, -0.4079, +0.3304, +0.1999, -0.3924, +0.0346, +0.0155, -0.4827, +0.1847, -0.1982, -0.1880, -0.1174, +0.4202, -0.1538, +0.3898, -0.3270, +0.2266, +0.0189, +0.0172, -0.0131, +0.4387, +0.0762, +0.1472, +0.0556, -0.3252, -0.2261, +0.0449, +0.2520, +0.0344, -0.2504, -0.3314, +0.2278, +0.1001, -0.0899, -0.0822, -0.2645, -0.1534, -0.3389, -0.2310, -0.1803, -0.0725, -0.1741, -0.2782, +0.0120, +0.0663, -0.1420, +0.1000, +0.0580, +0.2736, -0.0962, -0.1784, +0.0454, +0.1217, -0.1503, -0.1855, -0.0065, -0.2237, -0.1836],
-[ -0.3115, -0.1903, +0.5137, -0.1865, +0.4864, +0.2623, -0.0747, -0.0819, -0.0157, -0.6871, -0.0296, -0.3034, -0.2566, +0.1559, -0.5077, -0.5202, +0.0065, +0.0832, -0.4281, +0.0602, +0.1776, +0.0249, -0.3248, -0.5189, -0.5201, +0.2417, -0.4212, +0.0878, -0.2480, -0.7528, -0.1374, +0.2482, -0.0171, +0.3787, -0.1415, -0.0652, +0.2193, -0.5248, +0.1414, -0.1371, -0.2108, +0.1232, -0.0979, +0.2075, -0.5518, -0.1070, +0.0641, +0.3360, +0.3089, +0.2055, -0.2662, +0.0075, -0.1935, +0.0715, +0.2552, +0.3614, -0.1943, -0.3510, +0.3832, +0.0128, +0.0049, -0.0661, -0.3146, -0.1168, -0.0349, -0.0030, -0.1232, +0.1852, -0.1332, -0.0373, +0.0300, -0.0487, -0.1961, +0.1165, +0.0229, +0.0938, +0.1951, -0.2836, -0.0792, -0.0472, -0.2475, -0.5654, +0.1948, +0.2359, +0.0157, +0.1590, +0.0085, -0.1436, +0.1589, +0.0345, +0.0138, -0.1086, -0.0469, +0.1021, +0.1436, +0.2495, -0.0120, -0.0850, -0.0485, -0.1638, +0.1941, +0.0767, -0.0602, +0.5445, -0.5856, -0.0649, +0.0954, -0.4362, -0.1760, -0.0305, +0.1229, -0.2425, +0.3525, -0.1718, +0.2081, +0.2920, +0.2802, -0.1463, -0.0372, +0.2798, +0.1410, -0.2971, -0.0625, +0.2547, -0.4261, -0.0709, -0.1671, +0.0714],
-[ -0.2103, -0.0272, +0.3673, -0.4027, -0.4165, -0.3775, -0.2740, -0.4518, +0.3899, -0.1959, +0.3833, -0.2781, -0.0257, -0.2010, -0.3744, +0.1185, +0.0154, +0.0608, -0.1520, +0.3193, -0.1784, -0.1706, -0.5693, +0.0589, +0.1819, -0.2368, +0.0002, -0.1581, +0.1174, -0.3442, +0.0262, -0.5463, +0.4174, -0.1503, -0.3037, +0.1006, -0.0416, +0.2902, -0.0367, -0.5241, +0.1610, +0.5887, +0.2866, +0.1434, +0.0395, +0.1180, -0.0736, +0.3131, -0.2578, -0.4074, -0.6594, +0.1505, -0.5157, +0.2380, -0.0458, -0.2018, -0.0282, +0.3315, -0.1138, -0.3608, -0.0223, +0.2218, -0.2358, +0.2699, -0.7728, +0.2867, -0.2453, -0.5425, -0.1967, -0.0232, +0.2375, -0.4524, +0.4034, +0.0560, -0.2659, -0.0520, +0.1507, -0.2088, -0.0948, +0.4523, +0.2961, -0.2171, -0.3837, -0.3430, -0.0439, +0.4376, +0.1247, +0.1549, +0.3201, -0.2246, +0.0722, -0.1387, -0.2841, -0.3820, +0.2112, +0.1155, +0.0457, +0.0849, +0.0496, +0.2000, +0.3528, +0.1513, +0.2789, -0.5787, -0.0106, -0.0224, -0.3136, -0.2720, -0.3962, +0.2735, +0.2201, -0.4635, -0.2667, +0.3799, +0.0482, -0.3243, +0.2503, -0.1961, +0.2931, -0.0249, -0.6142, +0.3921, -0.0819, +0.1537, +0.1795, -0.4286, +0.3890, +0.0782],
-[ -0.0876, +0.0339, +0.1373, +0.1845, +0.1049, -0.2126, +0.4155, -0.2267, -0.1016, -0.3701, -0.2024, -0.6001, +0.1107, +0.1237, -0.0572, -0.2163, -0.0753, -0.2021, +0.0705, -0.1143, -0.0157, -0.3309, +0.3900, +0.0826, +0.0106, +0.2930, +0.0136, -0.8255, +0.0238, -0.3730, -0.0691, +0.0495, -0.1372, +0.0351, +0.1440, -0.1097, -0.6328, -0.2164, -0.1182, +0.1412, +0.0829, +0.2616, -0.0581, +0.2463, +0.0033, +0.1873, +0.1287, +0.0292, -0.0618, +0.4194, -0.0114, +0.3800, +0.4085, +0.2023, +0.1349, -0.4039, +0.0351, -0.1197, +0.3388, +0.0180, +0.0524, +0.3924, -0.5456, +0.3426, +0.0286, -0.1759, -0.0984, -0.0918, -0.0875, -0.0735, -0.1989, -0.2863, -0.0470, -0.0234, -0.0645, -0.3891, -0.0790, -0.1388, -0.2737, -0.6725, -0.1225, +0.2987, +0.5457, -0.1536, -0.1787, +0.0739, -0.2458, -0.2498, +0.0537, +0.4109, -0.1707, -0.2982, -0.3935, -0.3520, -0.0815, -0.2821, -0.4165, -0.0681, -0.1594, +0.0789, -0.2301, +0.0582, -0.1564, +0.2033, +0.0964, +0.2820, -0.1194, +0.0914, +0.0025, +0.3850, +0.0008, -0.6762, +0.0372, -0.2743, -0.0836, +0.0765, -0.3693, +0.1311, +0.0767, -0.4189, -0.1969, +0.1716, -0.2014, -0.1836, +0.0086, -0.5796, -0.1696, -0.2689],
-[ -0.5652, -0.0070, -0.2653, -0.2943, +0.2439, +0.1118, +0.0728, -0.0968, -0.3874, -0.2193, +0.4227, -0.4908, -0.1880, -0.3136, +0.0948, +0.2156, +0.6100, +0.2064, +0.1879, +0.1478, +0.0360, -0.0379, -0.2390, +0.0572, +0.2056, -0.1321, -0.0847, -0.3560, +0.1960, +0.1519, -1.1702, +0.1798, +0.0549, +0.3503, -0.1306, +0.1877, -0.5265, -0.3751, -0.1159, +0.1669, +0.3965, +0.1393, +0.0249, -0.1329, -0.0147, -0.0055, -0.0215, -0.2642, -0.4214, -0.1231, -0.3051, -0.0133, +0.0672, -0.2792, -0.2496, +0.0984, +0.4932, +0.3534, +0.0042, -0.1074, +0.2071, +0.0513, -0.4839, -0.2368, -0.1557, +0.0947, -0.0207, -0.6396, +0.0899, -0.0886, -0.1305, +0.2177, -0.0290, +0.1537, -0.3355, +0.2742, -0.2478, -0.1225, -0.2504, -0.0776, +0.0167, +0.3300, +0.3200, +0.2386, +0.4581, +0.0562, -0.0332, +0.0560, +0.1136, +0.2801, +0.0391, +0.2024, +0.2941, +0.0766, -0.1749, +0.2298, +0.1376, -0.0507, +0.0268, +0.0475, -0.3004, +0.2160, -0.0062, -0.2329, +0.0377, -0.2296, +0.0611, +0.1093, +0.3586, -0.2859, -0.2399, +0.6020, -0.3755, -0.0461, +0.1298, -0.5961, -0.3126, +0.1551, +0.1396, -0.4280, +0.3916, +0.0049, -0.3861, +0.1474, -0.2064, +0.1811, -0.2898, -0.2750],
-[ +0.0819, +0.3396, +0.6644, -0.4791, +0.4484, +0.3738, +0.3009, +0.4245, -0.0692, +0.1020, -0.1339, +0.4104, +0.0893, -0.3633, +0.3444, -0.0436, +0.3646, +0.0856, -0.0671, -0.1069, +0.0030, -0.1021, +0.5561, -0.4046, +0.1399, -0.2609, +0.1563, -0.1875, +0.0044, +0.5717, -0.4551, +0.1222, -0.1040, +0.2842, +0.0044, +0.3571, +0.2629, -0.5173, -0.3387, +0.0044, -0.0539, -0.1107, +0.1069, -0.1870, -0.0774, +0.3390, -0.1788, +0.3467, -0.0369, -0.1703, +0.0261, -0.7276, -0.0712, +0.0393, +0.0690, +0.1008, -0.2375, +0.4717, -0.0653, -0.1273, +0.3284, -0.1475, +0.3745, +0.3026, +0.2293, +0.1274, +0.1661, -0.2018, +0.0311, -0.0159, +0.1497, +0.2360, -0.2298, -0.2898, -0.3821, -0.2285, +0.0855, -0.2077, -0.4727, +0.0609, +0.1613, +0.2449, -0.0503, +0.1121, +0.0116, +0.1638, -0.2348, -0.0742, -0.1956, +0.5764, -0.1819, -0.1925, -0.1747, +0.0106, +0.3059, -0.7939, -0.3273, -0.0173, +0.0771, -0.4543, -0.1425, -0.1515, +0.0516, +0.1927, +0.4261, +0.2317, -0.2900, -0.4359, -0.2398, +0.2765, +0.0672, +0.1524, -0.3440, -0.0897, +0.0850, +0.4672, -0.5525, -0.1277, -0.2299, +0.5013, +0.2990, +0.1097, +0.1777, -0.0779, +0.2859, +0.0094, -0.4870, -0.2335],
-[ +0.1106, -0.2441, -0.0207, -0.2220, -0.3689, -0.1634, +0.0828, -0.2131, -0.0443, +0.2476, -0.0322, -0.4817, -0.1937, +0.1710, +0.2099, +0.1598, -0.6755, -0.1558, -0.1531, +0.1499, -0.2008, -0.4290, +0.1572, +0.1114, +0.2724, +0.1565, -0.1044, -0.1196, +0.1873, +0.3075, -0.0485, +0.4471, -0.1237, +0.4092, -0.0991, +0.1165, +0.1534, -0.0387, -0.0965, +0.5520, +0.2848, +0.0698, +0.0140, +0.0168, -0.1516, -0.0396, -0.5690, +0.3673, -0.2028, +0.2079, +0.3912, -0.2749, +0.0421, +0.0121, -0.1195, +0.2930, -0.5744, -0.0266, -0.3280, -0.2039, -0.6046, -0.0557, +0.1329, +0.2431, +0.2108, -0.6411, +0.2877, +0.2222, +0.0724, +0.2789, +0.0077, +0.2311, -0.3908, -0.1828, +0.0685, -0.0765, -0.1263, -0.2053, +0.3030, +0.0021, -0.3130, +0.4412, +0.4471, +0.1203, -0.4419, -0.0044, +0.0231, +0.1777, -0.1182, +0.4016, -0.0836, -0.3208, -0.2156, +0.1623, -0.0150, -0.0775, +0.0234, +0.0310, -0.1058, +0.2323, -0.3849, -0.5044, -0.3593, -0.2442, +0.1562, +0.1421, -0.1440, +0.2766, -0.2231, -0.1259, -0.0108, -0.0871, -0.0337, +0.0278, +0.1841, -0.0910, -0.2078, +0.1710, -0.1523, +0.6016, +0.1046, -0.1343, -1.1743, +0.1045, +0.1077, +0.0598, +0.2469, +0.1028],
-[ -0.0543, -0.0520, -0.0337, -0.0404, +0.1425, +0.1348, +0.3168, -0.2588, -0.2536, -0.1804, +0.0513, -0.2466, +0.2413, -0.0143, -0.0072, +0.2906, +0.6229, -0.1328, -0.2948, -0.0062, -0.0023, +0.2968, -0.1129, -0.1713, +0.0827, -0.0985, +0.0373, +0.3027, -0.1809, -0.0222, +0.0336, +0.1493, +0.1600, -0.2339, +0.2103, -0.2994, +0.0029, -0.0231, -0.2620, +0.0599, +0.1202, -0.2858, +0.3041, -0.1582, -0.0641, -0.2478, -0.2629, -0.9977, +0.1291, -0.4405, -0.1031, -0.2489, -0.1969, -0.0879, -0.4210, +0.0992, +0.0513, -0.3871, -0.1446, +0.3532, +0.2695, +0.5117, +0.1277, -0.6634, -0.6091, +0.2715, -0.1133, +0.1093, -0.1494, +0.0243, -0.7959, -0.3742, +0.4444, +0.2359, +0.4380, +0.0365, +0.0249, -0.2143, -0.5784, +0.3612, +0.2995, -0.2671, -0.0836, -0.1842, -0.1041, -0.0031, -0.0125, +0.2039, +0.0862, -0.3960, +0.3796, +0.3519, -0.1025, -0.2369, -0.4241, -0.0101, -0.1784, +0.1087, +0.1407, +0.0627, +0.0779, +0.0970, +0.2389, -0.1938, -0.1186, +0.0217, -0.4346, -0.1634, -0.2502, -0.0890, -0.3465, +0.2362, +0.1421, +0.2332, -0.3333, -0.1481, +0.3306, -0.0235, +0.0863, +0.1138, -0.2944, -0.1774, -0.2728, +0.0228, -0.3492, -0.0211, -0.2253, +0.2095],
-[ -0.5031, -0.0106, -0.5764, +0.2997, +0.0455, -0.2089, -0.0262, +0.1678, +0.0179, +0.0361, -0.0682, -0.2984, -0.7560, -0.4558, +0.1347, -0.1037, -0.2825, +0.1499, +0.1365, +0.3642, -0.6386, +0.1581, -0.4962, +0.3903, -0.1766, +0.2820, -0.0779, -0.1685, -0.2023, -0.1377, +0.4133, +0.0075, +0.2662, -0.0899, +0.2100, -0.0853, +0.0316, -0.1310, -0.5245, -0.3770, -0.2010, +0.2296, -0.1653, -0.2975, -0.2957, -0.1499, -0.2093, +0.0406, -0.0851, +0.0893, +0.1815, +0.0560, -0.1637, +0.3338, -0.0075, -0.4040, -0.3295, -0.0336, +0.1534, -0.5067, -0.5103, -0.0447, -0.0133, +0.0738, -0.1764, -0.0509, -0.1104, -0.0568, +0.3894, +0.0515, -0.2251, -0.2737, +0.0503, -0.3561, +0.0208, +0.0426, -0.2372, +0.2387, -0.1670, +0.1123, +0.0645, +0.0064, -0.2416, +0.3130, -0.2139, -0.4807, -0.3596, +0.0326, -0.2081, +0.2586, -0.3262, +0.0230, -0.0541, +0.1587, -0.2205, +0.2711, -0.1692, -0.1007, +0.0034, +0.2116, -0.2285, -0.3356, -0.4481, +0.0854, +0.4984, +0.4606, +0.0105, +0.1204, +0.3893, -0.0277, -0.0226, -0.0351, +0.1008, -0.1522, +0.0265, -0.1190, +0.2637, +0.0124, -0.0738, +0.2898, +0.1958, -0.1738, -0.0098, +0.1932, +0.0268, +0.1603, +0.6525, +0.0526],
-[ +0.0485, +0.0268, +0.0319, -0.3053, -0.4060, +0.0753, -0.0605, +0.1749, +0.2095, -0.1262, -0.2092, +0.1282, -0.3959, +0.1964, -0.3560, +0.0875, -0.1696, -0.1043, -0.1539, +0.0617, +0.2019, -0.2442, -0.3615, +0.0525, -0.0495, +0.2295, +0.1157, -0.0754, +0.1260, -0.0017, -0.2547, -0.0923, +0.1053, +0.4380, +0.6004, -0.3390, -0.0069, +0.2720, +0.1229, -0.1220, -0.0963, -0.0385, -0.2458, -0.1614, +0.3232, -0.0474, +0.0076, -0.0876, -0.1707, -0.2325, -0.3311, -0.1263, -0.1986, +0.0380, -0.1855, +0.1246, -0.0602, -0.4341, -0.3513, -0.2822, -0.4292, +0.2778, +0.3388, +0.1175, +0.1572, +0.3568, +0.4891, -0.1087, -0.8776, -0.3998, -0.2541, -0.3995, +0.0364, -0.0664, -0.0990, -0.0679, -0.0806, -0.1332, -0.0665, +0.1621, +0.0134, +0.0001, -0.2535, -0.1088, -0.3660, -0.0472, -0.1492, -0.0049, -0.2184, +0.4806, -0.1792, -0.0431, +0.2985, +0.0829, -0.1200, +0.3787, -0.2766, +0.0398, +0.1273, -0.1870, +0.3448, -0.7261, +0.0924, -0.0436, +0.3037, -0.3195, +0.0065, -0.1420, -0.1679, +0.1018, -0.3936, -0.2624, -0.0564, +0.1715, -0.2367, -0.2993, -0.0956, +0.0663, +0.1161, -0.0466, +0.2386, +0.2236, +0.1145, +0.2103, +0.0126, +0.2852, +0.1745, -0.3843],
-[ -0.4672, +0.2588, +0.0562, +0.1480, -0.4764, +0.1280, +0.4856, +0.0112, +0.2037, -0.0415, +0.1757, +0.3030, +0.2553, -0.0274, +0.2237, +0.2764, -0.0150, +0.1079, -0.3132, -0.0768, +0.0729, +0.1800, +0.1761, +0.4058, +0.2768, -0.3452, -0.3097, -0.9129, +0.0064, +0.0359, -0.0055, +0.2052, +0.0746, +0.1586, -0.3851, -0.2572, -0.2362, +0.0177, -0.4950, +0.0380, -0.4321, -0.5949, +0.2672, +0.1696, -0.1803, +0.1604, -0.1012, -0.2397, +0.2885, -0.0145, -0.1970, +0.2272, +0.0729, +0.0965, +0.1213, -0.3012, +0.1532, +0.1785, +0.1139, -0.3229, -0.0235, +0.0460, -0.1932, -0.4243, +0.2980, +0.6384, +0.0036, -0.0376, -0.2725, +0.1097, +0.0773, -0.0941, -0.2394, -0.0633, -0.4184, +0.0828, +0.3985, +0.3665, +0.0428, +0.2717, +0.0889, -0.4750, -0.1839, +0.2336, +0.0573, -0.1662, +0.2641, -0.2457, +0.1031, -0.1323, -0.1159, +0.1930, +0.1754, +0.2182, +0.1884, +0.0969, -0.0915, -0.4317, -0.1361, +0.1541, +0.2442, -0.2624, +0.2007, -0.1427, +0.1815, -0.1010, -0.2929, -0.0172, +0.1583, -0.1212, -0.3831, +0.3188, -0.0740, +0.1650, +0.2072, -0.1448, -0.0106, +0.1476, +0.0625, +0.3715, -0.7368, -0.0247, +0.0065, -0.3615, -0.0060, +0.0279, -0.3687, +0.1363],
-[ +0.3754, -0.2605, +0.0323, +0.2464, -0.1368, +0.1968, -0.0651, -0.0776, -0.4373, -0.3815, +0.4641, +0.5324, -0.1058, -0.0363, +0.0765, +0.1648, -0.4148, -0.3646, +0.5048, -0.0458, -0.0971, +0.2370, +0.2665, -0.1116, -0.0673, +0.1211, -0.1089, +0.2868, -0.0596, +0.1425, -0.4598, -0.3449, +0.0562, +0.2441, +0.3310, +0.2028, -0.5315, +0.2401, -0.0847, +0.3627, +0.0449, +0.0452, -0.1913, -0.3452, -0.1771, +0.0831, +0.0537, -0.3353, +0.1358, +0.3165, +0.1456, -0.7420, +0.0564, +0.2464, -0.1040, -0.1426, +0.3086, -0.3616, -0.2352, -0.0093, +0.6517, +0.3513, -0.3664, -0.3185, -0.2502, -0.2195, -0.2321, +0.0309, -0.0145, +0.1909, +0.4287, +0.1918, +0.4122, +0.0126, +0.3436, -0.0501, -0.2590, -0.3481, -0.1366, -0.1364, +0.2620, +0.1644, +0.3660, +0.4092, -0.2268, +0.2222, -0.0204, +0.2245, +0.2123, -0.0841, -0.2532, +0.0668, -0.0343, -0.4897, +0.2300, +0.2320, -0.3528, -0.3275, +0.1535, -0.0580, -0.2584, -0.1686, -0.0956, +0.3153, -0.1885, +0.0961, -0.1013, +0.2607, -0.1861, -0.0490, +0.0190, -0.1581, -0.1222, +0.3552, +0.5830, -0.3812, +0.2291, -0.1613, +0.4073, -0.5114, -0.0738, +0.4687, +0.0703, -0.5921, -0.0492, -0.3495, +0.2038, -0.0015],
-[ -0.1122, -0.4957, +0.4057, -0.1631, +0.0567, -0.1668, +0.3326, -0.2213, +0.2227, +0.6027, -0.0509, -0.1572, +0.0635, +0.0257, -0.3764, -0.2729, +0.0150, +0.3523, +0.3869, -0.0460, -0.2430, -0.1304, -0.0551, +0.0108, -0.0267, +0.0985, -0.3189, +0.0703, -0.6249, -0.2440, +0.5041, +0.1002, +0.3512, +0.3129, +0.1434, +0.2645, -0.1019, -0.3615, +0.2815, -0.0825, +0.3513, +0.4494, -0.1594, +0.1642, +0.0036, -0.1905, -0.2434, +0.1266, +0.2592, -0.3465, -0.3797, -0.0483, -0.2283, -0.0797, +0.1920, -0.2345, +0.1873, +0.4164, -0.6789, -0.2604, +0.3056, +0.0606, +0.3516, +0.1032, -0.1513, +0.3542, -0.1142, -0.2307, +0.1800, +0.2824, -0.2042, +0.0625, -0.0690, +0.2268, -0.3744, +0.0939, +0.2214, +0.2345, +0.1130, -0.1187, -0.3137, -0.2488, -0.3648, -0.0565, +0.0364, -0.2158, -0.5209, +0.0104, -0.6269, -0.1152, +0.1796, -0.0065, -0.2958, +0.2548, -0.1919, -0.1996, +0.2111, +0.0362, -0.0187, -0.2994, +0.1538, +0.0342, +0.1659, +0.2444, -0.1623, +0.0468, +0.0540, -0.1784, +0.3852, -0.3855, -0.2606, -0.6163, +0.1517, +0.1374, +0.1268, +0.0022, +0.2307, +0.2028, -0.0723, -0.1358, -0.1072, -0.3337, -0.0602, +0.1512, -0.0703, -0.1210, -0.3207, -0.2559],
-[ -0.2911, -0.1009, +0.1391, -0.0244, -0.1153, -0.2357, +0.1661, +0.4648, +0.3280, -0.1573, -0.4334, -0.0048, +0.1839, -0.0928, -0.1499, +0.3940, -0.0577, -0.4509, +0.2161, +0.2168, -0.4486, +0.1994, -0.0153, -0.3432, -0.1163, -0.2053, +0.0779, -0.2540, +0.3683, +0.4146, -0.2337, +0.2252, -0.2090, +0.2881, +0.0109, +0.0089, +0.2146, -0.1160, +0.0447, -0.1081, -0.0476, +0.1209, +0.1485, +0.0825, -0.1552, +0.1390, +0.3149, +0.1107, +0.0671, +0.1735, -0.5206, -0.4408, +0.3938, +0.0551, +0.2809, -0.0903, -0.2065, -0.2171, -0.3155, -0.2297, +0.0945, +0.2610, +0.1254, +0.0889, +0.1768, -0.1305, -0.2692, +0.0158, +0.1272, -0.2697, -0.0698, +0.2225, -0.3673, +0.3703, +0.1918, -0.1972, +0.1838, -0.0154, -0.2331, -0.5831, +0.0827, +0.1265, +0.3300, +0.4084, -0.2463, +0.1464, -0.2197, +0.0450, -0.1694, -0.2000, -0.3338, -0.0556, +0.0045, -0.6450, +0.0410, +0.0201, -0.5188, +0.1173, -0.3162, -0.1067, -0.0088, +0.0243, -0.0778, +0.1921, +0.0385, -0.0554, -0.1265, +0.0691, +0.3145, +0.2980, -0.1277, -0.0588, +0.0949, -0.3787, -0.0691, -0.0276, -0.0251, -0.1589, -0.0207, -0.1079, -0.4167, -0.2475, -0.2711, -0.0513, +0.3191, +0.6425, -0.2709, -0.1689],
-[ +0.0047, +0.0616, -0.1269, -0.0223, -0.1831, +0.3906, +0.2033, -0.1767, +0.1908, +0.0738, +0.0442, +0.2406, +0.1871, -0.0993, +0.0015, -0.1329, +0.0476, +0.5890, -0.2690, +0.0427, +0.1877, +0.0073, -0.2394, +0.1549, +0.3307, -0.3357, +0.2112, +0.0156, +0.3022, +0.0204, -0.1618, -0.2322, -0.1883, +0.1024, +0.0760, -0.6147, +0.2509, +0.0126, -0.1969, -0.0979, +0.3660, +0.0898, -0.0740, -0.0060, -0.1458, -0.0460, -0.4250, -0.3589, +0.0585, -0.0567, -0.2184, +0.1149, +0.1346, -0.0299, -0.0425, -0.2282, -0.0385, +0.1466, -0.4807, -0.3405, +0.0751, +0.5248, -0.1385, -0.0819, -0.3010, -0.0021, +0.1113, +0.0553, -0.0328, +0.4945, +0.3550, -0.0888, +0.0378, -0.2603, +0.1825, +0.1809, +0.0374, -0.0740, +0.0838, +0.4879, +0.0374, -0.0534, -0.0180, -0.1993, -0.4417, -0.3333, -0.3223, -0.3871, -0.0617, +0.2161, -0.0491, +0.0336, -0.0206, -0.0922, -0.2727, +0.0829, -0.2567, +0.0960, -0.1694, -0.5163, -0.0041, -0.0166, -0.4449, +0.1398, +0.2162, -0.5065, -0.1253, +0.0833, -0.0705, +0.1840, +0.1504, +0.2364, -0.1248, +0.1244, +0.2257, -0.0303, +0.3157, -0.2759, -0.1885, +0.0851, -0.0481, -0.1577, -0.2389, +0.1950, +0.3905, +0.0810, +0.0136, -0.0261],
-[ -0.2776, -0.3588, -0.4710, +0.2055, -0.0982, -0.0288, +0.3268, +0.0424, -0.1561, +0.3499, +0.4200, -0.5925, +0.2719, -0.5844, -0.2293, +0.0549, +0.0285, -0.1706, -1.1541, +0.2360, +0.0970, +0.0501, +0.0376, +0.1502, +0.0308, -0.0501, +0.1327, +0.3548, -0.0756, -0.2112, -0.4810, -0.2197, -0.0827, -0.2571, +0.2539, -0.2960, -0.0967, -0.1865, -0.2390, +0.2819, +0.2164, +0.0519, +0.0464, +0.2448, -0.2410, -0.1175, -0.0993, -0.7210, -0.0141, -0.0289, -0.1874, -0.2468, +0.1093, -0.2226, +0.1077, +0.3520, -0.2411, +0.1714, -0.3071, +0.1988, +0.5781, +0.3843, -0.0926, -0.2357, -0.4513, -0.3061, +0.3818, +0.3143, +0.4826, -0.1459, +0.1707, +0.3978, -0.1669, -0.2427, +0.4658, -0.2464, +0.3491, +0.1534, -0.1865, -0.3171, -0.0700, +0.0454, +0.4187, +0.2408, -0.0124, +0.4662, +0.4847, +0.2388, +0.2800, +0.2012, -0.0927, -0.2946, +0.1002, -0.2051, +0.0583, -0.2708, +0.0331, -0.0591, -0.1156, +0.1790, -0.4946, -0.3300, -0.3836, -0.0449, +0.2630, +0.1686, +0.0428, +0.0842, -0.0174, +0.0996, -0.0303, -0.3013, -0.0502, -0.5230, +0.1715, -0.2806, -0.1776, +0.2469, -0.2864, -0.3993, +0.2259, +0.1500, -0.3863, +0.2840, +0.0559, +0.2354, +0.2897, +0.4232],
-[ +0.0786, +0.3700, +0.2628, +0.0211, -0.5878, +0.3987, +0.0301, +0.2936, +0.1753, -0.1643, -0.2340, +0.1637, +0.2365, +0.0329, +0.0921, -0.0478, +0.1871, -0.1717, +0.0519, -0.1018, -0.3369, -0.0651, +0.0361, -0.1157, +0.6206, -0.3262, -0.0921, -0.2719, +0.5857, +0.1393, -0.3557, +0.0635, -0.3072, -0.5401, +0.0289, -0.0330, -0.0507, +0.3589, +0.0363, -0.2177, +0.2639, +0.0678, -0.1000, +0.1955, +0.1026, +0.1955, -0.0616, +0.5871, +0.1069, -0.3716, -0.0883, -0.4984, -0.3853, +0.4456, -0.1893, +0.0767, +0.1969, -0.0124, +0.0712, +0.0655, +0.4908, +0.2021, +0.1938, -1.0127, -0.0061, +0.3511, +0.0834, -0.5368, +0.2761, -0.2155, +0.0154, -0.1181, -0.1794, -0.2620, -0.2968, +0.4547, -0.4057, -0.2744, +0.0613, -0.0414, +0.1598, +0.0669, +0.1854, +0.1409, +0.0682, +0.1385, -0.0276, +0.0171, +0.1945, +0.0307, +0.0001, -0.2223, +0.1962, +0.0133, +0.0785, +0.0997, +0.1798, +0.0109, +0.1000, +0.4742, +0.0332, -0.5774, +0.2532, +0.0146, -0.1217, +0.1973, -0.1829, -0.4806, +0.0419, -0.2457, -0.3725, -0.1983, -0.1706, -0.3660, +0.0608, -0.1282, +0.3200, +0.0482, +0.5245, +0.2118, -0.8071, +0.0611, +0.3456, -0.4500, +0.2488, -0.1320, +0.4830, +0.2848],
-[ -0.1073, +0.1037, -0.3255, +0.0693, +0.1400, -0.2319, +0.0581, +0.0548, -0.0365, -0.1910, -0.2240, +0.2228, -0.2315, -0.2570, -0.0562, -0.4512, +0.0993, +0.2102, -0.0621, +0.0652, +0.2532, +0.1462, +0.2055, +0.4096, -0.0325, +0.0912, -0.2241, -0.0846, -0.0290, -0.3131, +0.0912, -0.3046, +0.2735, -0.2764, -0.1748, +0.0446, +0.0925, -0.3799, +0.2789, +0.1586, -0.1533, -0.0111, +0.1665, -0.3099, -0.2307, -0.4259, +0.3205, +0.0423, -0.2089, -0.1306, -0.0337, -0.4183, -0.4420, +0.2175, +0.1202, -0.0476, -0.2734, +0.1719, -0.3250, +0.0094, +0.3707, +0.0904, -0.4614, +0.1627, -0.3169, -0.3031, -0.0894, -0.1149, +0.3212, +0.3719, +0.0059, +0.2209, -0.2337, -0.3808, +0.3385, -0.2686, -0.0678, +0.5800, +0.3577, +0.0998, +0.2190, -0.1451, -0.4314, +0.2262, -0.1531, -0.1131, +0.1177, +0.0831, -0.3033, -0.0453, -0.1597, +0.2794, +0.0207, -0.4414, -0.1667, +0.1918, -0.0865, +0.3251, -0.0287, -0.0736, -0.1075, -0.1250, -0.4520, +0.3047, -0.0875, -0.2582, +0.4246, -0.0067, -0.0675, -0.0365, +0.3078, -0.2003, -0.1038, -0.2029, +0.1792, +0.3332, +0.1595, -0.0987, -0.1700, +0.2975, +0.5003, -0.2330, +0.2490, +0.3504, -0.2410, +0.5215, +0.1684, -0.2419],
-[ -0.0272, -0.0197, -0.0498, -0.3125, -0.1470, +0.2877, +0.0098, +0.0828, +0.3936, +0.1087, -0.0007, -0.0460, -0.1392, +0.0118, +0.2500, -0.1045, +0.0548, -0.0537, +0.1720, -0.2372, -0.1876, +0.1110, +0.1386, -0.1052, -0.1087, -0.0159, +0.1606, -0.1951, +0.2494, -0.1679, +0.1025, +0.3162, +0.2416, +0.0338, -0.0438, -0.0798, -0.2180, -0.0090, -0.0330, -0.2608, -0.1611, +0.3750, +0.3055, +0.1846, +0.1841, +0.3994, -0.0243, -0.3590, +0.0062, +0.0208, -0.0984, +0.2669, -0.2289, -0.4093, -0.0409, -0.1831, -0.1913, -0.2470, -0.1215, +0.1650, -0.3795, +0.0429, -0.0017, -0.0563, -0.2910, +0.4329, -0.4084, +0.1284, -0.2935, -0.0446, -0.1213, +0.0592, -0.3015, -0.1558, -0.4683, +0.1737, +0.1404, -0.1560, -0.1683, -0.0704, -0.1695, -1.1899, +0.0634, -0.2749, -0.3013, -0.6152, -0.0497, +0.4101, +0.3239, -0.3935, -0.0283, +0.0037, +0.3283, +0.0818, -0.4429, -0.4364, -0.2240, +0.1993, +0.0054, +0.3334, +0.5122, -0.0501, +0.2898, -0.1176, +0.1916, +0.0811, +0.2813, -0.4673, +0.0826, -0.0553, -0.0349, -0.1847, -0.1159, +0.4650, -0.1069, -0.3477, -0.0889, +0.0103, +0.0001, -0.3395, +0.2372, -0.0297, +0.2345, -0.0795, +0.2465, -0.1002, -0.1024, -0.0517],
-[ +0.1808, +0.0077, +0.1769, -0.2979, -0.0312, +0.1853, +0.1740, -0.3678, -0.0212, +0.0899, -0.2367, +0.2297, -0.1192, +0.1246, -0.0043, -0.4725, -0.3428, -0.0674, +0.5052, -0.4794, -0.2887, -0.4310, +0.1617, +0.4358, +0.3620, -0.0182, -0.1712, -0.1217, -0.4400, +0.1939, +0.2990, -0.4162, -0.1362, +0.0944, +0.1773, -0.2093, +0.1013, -0.0034, -0.2675, +0.1798, +0.0271, +0.2224, -0.4245, -0.1975, +0.1742, +0.4710, +0.1564, +0.2407, +0.1071, -0.2609, -0.6139, +0.1218, -0.2299, -0.1103, +0.4042, +0.0591, -0.0113, +0.0456, +0.4728, +0.0059, +0.3071, +0.0690, +0.0480, +0.4073, -0.0833, +0.0645, -0.3894, -0.2094, +0.0390, +0.2714, +0.0559, -0.0315, -0.4724, -0.2619, +0.0623, +0.0794, -0.1085, -0.0133, -0.0373, +0.1215, -0.5136, -0.4344, -0.4528, +0.2668, +0.0667, -0.1481, -0.2553, +0.0380, +0.2029, +0.2780, -0.3474, -0.2158, -0.3623, -0.0207, +0.1420, -0.0384, -0.0967, -0.0257, -0.0592, +0.3893, -0.2964, -0.1850, -0.3109, +0.3306, -0.5495, -0.0713, -0.0160, +0.2504, -0.3662, -0.4457, -0.1997, +0.0348, +0.2545, +0.0796, +0.2407, -0.6725, -0.2860, +0.1711, -0.0364, -0.3736, -0.0821, +0.1595, +0.0021, -0.0176, +0.0976, -0.1021, -0.3775, -0.6194],
-[ -0.1115, +0.2235, +0.1863, +0.2503, +0.1941, -0.1116, -0.0322, +0.0161, -0.0706, +0.2388, -0.5055, -0.3318, +0.1156, -0.5982, +0.2497, +0.2186, +0.0293, -0.0434, +0.5011, -0.4769, +0.2955, +0.3118, +0.3163, -0.1813, +0.3505, -0.6790, +0.3490, +0.1289, -0.0642, -0.0930, +0.5358, -0.3412, -0.2185, -0.0010, +0.0342, -0.1512, -0.2240, -0.1741, -0.0852, -0.0242, +0.2095, +0.2727, -0.1230, -0.2387, -0.1015, +0.0158, +0.0469, +0.0534, +0.1719, -0.1393, +0.2014, +0.0348, -0.1869, +0.1339, -0.1371, -0.0463, -0.0411, +0.2232, +0.0770, -0.0833, -0.1241, +0.1086, -0.1627, -0.0193, +0.3628, -0.2017, +0.1716, +0.3239, +0.4415, +0.1805, -0.2427, -0.5063, -0.2224, +0.1149, +0.2752, -0.1453, +0.1640, -0.1874, -0.0713, +0.0449, -0.1494, -0.0192, -0.0468, +0.0316, -0.6600, -0.1496, +0.2316, -0.2830, +0.0171, +0.0085, -0.5733, -0.2160, +0.2207, +0.1985, -0.1002, +0.2795, +0.2018, -0.0175, +0.0011, -0.1767, +0.0625, -0.1560, -0.3344, -0.7670, -0.1168, -0.1633, -0.1385, +0.1261, +0.1919, +0.1725, +0.0319, -0.0165, +0.0850, -0.2974, -0.4158, -0.3987, -0.0986, +0.2890, +0.3104, -0.2340, -0.1918, -0.2878, +0.0301, +0.0279, +0.3777, -0.4659, +0.0765, -0.0032],
-[ -0.1247, +0.3309, -0.3103, +0.1687, +0.0976, -0.2351, -0.0116, -0.1747, -0.6116, -0.0176, +0.2908, -0.1105, +0.1844, -0.6355, +0.0104, -0.1551, +0.4021, -0.0415, +0.2615, +0.0888, -0.1101, -0.0847, -0.1650, +0.5355, +0.3455, +0.0882, -0.0706, +0.1523, -0.0444, +0.0061, +0.0724, -0.3089, -0.0143, -0.0126, -0.0448, -0.2619, -0.0541, -0.2937, +0.1746, +0.0298, +0.2119, -0.1340, +0.0650, -0.0277, -0.3615, +0.2201, -0.1907, +0.1040, +0.2692, +0.4564, +0.1397, +0.1867, -0.0088, +0.3706, +0.3067, +0.0381, +0.4252, +0.2832, -0.0726, -0.3068, -0.1553, +0.0957, -0.1835, -0.1914, -0.2654, +0.1882, +0.4128, +0.0531, +0.0793, +0.3259, +0.0693, -0.0804, +0.0350, -0.1218, -0.1162, -0.2567, -0.1921, +0.1013, -0.0471, -0.1040, +0.3210, +0.0918, +0.1500, +0.0885, -0.2175, +0.2143, -0.0960, -0.3534, -0.1179, +0.0871, +0.4107, -0.3273, +0.0231, -0.1418, +0.0434, +0.2652, +0.3954, +0.1180, -0.3608, -0.3019, +0.0631, +0.0295, +0.0942, -0.0744, +0.1798, +0.0825, +0.3385, +0.2035, +0.1360, +0.0015, -0.3507, -0.3485, +0.3279, +0.2493, +0.1420, -0.0464, -0.0018, +0.0730, +0.4359, -0.0651, +0.3583, -0.1389, -0.6723, -0.3598, -0.0669, -0.1090, +0.0912, -0.0810],
-[ +0.2457, -0.1002, -0.3755, +0.1569, +0.2735, +0.0723, -0.2051, -0.2408, +0.0090, +0.2706, +0.1030, -0.0864, -0.0750, +0.0613, -0.0209, -0.0809, -0.3630, -0.3275, +0.2244, -0.0836, -0.0974, +0.1007, -0.1786, +0.1611, -0.2397, +0.3843, +0.5103, +0.0555, +0.2557, -0.2810, -0.0016, +0.2774, +0.1998, -0.2768, -0.3266, -0.3404, +0.2155, +0.0193, +0.3186, +0.0729, +0.2436, +0.1745, -0.1795, -0.2552, -0.9459, +0.4166, +0.0442, +0.0434, -0.1687, -0.1794, -0.3971, +0.4327, -0.4028, +0.2954, +0.0494, -0.0953, +0.2842, -0.0374, -0.3217, +0.1724, +0.1249, +0.0641, -0.1462, +0.4803, -0.2048, +0.0251, -0.1623, -0.3777, -0.5728, +0.1280, +0.0597, +0.1503, -0.1340, -0.0378, +0.0261, -0.5590, -0.2668, -0.1524, +0.3065, -0.0374, -0.0692, +0.1520, -0.4180, -0.0488, -0.7730, +0.1127, +0.2032, -0.6233, +0.4527, -0.2019, -0.0933, -0.4223, +0.1502, -0.2655, +0.0123, -0.2330, -0.1848, +0.0627, -0.6064, -0.3355, -0.3527, -0.3417, -0.1368, +0.0545, -0.2194, -0.0615, -0.1130, +0.3267, -0.1764, +0.0686, -0.1893, +0.0566, +0.0097, -0.1705, -0.3254, +0.1268, +0.3298, +0.2485, +0.0625, -0.1229, -0.3688, -0.4070, -0.1600, -0.4408, -0.1673, +0.1722, +0.1500, +0.0929],
-[ -0.3784, +0.2427, +0.2142, -0.1156, +0.3994, -0.1667, -0.0100, +0.3319, +0.1156, +0.0075, +0.4072, -0.1607, -0.4709, +0.1231, +0.2051, +0.1843, -0.1108, -0.1801, -0.0897, +0.2885, -0.1098, +0.1957, +0.1071, -0.2464, +0.7503, +0.6850, -0.1070, -0.0895, +0.0858, -0.0243, -0.2785, +0.0489, +0.0823, +0.1822, +0.0367, -0.4066, -0.0994, -0.2185, +0.1010, -0.5811, +0.0185, +0.0432, +0.0955, -0.3456, -0.2426, -0.2875, -0.1263, +0.1389, +0.0185, +0.2978, +0.3486, +0.0317, +0.0020, -0.0886, +0.3061, -0.8932, +0.4772, +0.1074, -0.0251, +0.0624, +0.0784, +0.4083, -0.0261, +0.4151, +0.0109, +0.3645, +0.0858, -0.0630, -0.4826, -0.3442, -0.1942, -0.1690, +0.1250, -0.1372, +0.1137, -0.0636, -0.0974, +0.0269, -0.0511, -0.4347, +0.1984, -0.5682, -0.2920, -0.0002, -0.7504, -0.4458, -0.2896, -0.1026, -0.7266, +0.1155, +0.4279, -0.2980, -0.1069, +0.2625, -0.1583, -0.3158, +0.2147, +0.1183, +0.3104, -0.1082, -0.3283, -0.2075, -0.0452, -0.2999, +0.5244, -0.2035, -0.1068, -0.1554, -0.2656, -0.3371, +0.5964, -0.4253, -0.0956, +0.2555, -0.3485, +0.0816, -0.1378, +0.2922, -0.1855, +0.1262, +0.1483, +0.0747, +0.4638, +0.1276, -0.1310, +0.2338, +0.3094, -0.2473],
-[ +0.1188, +0.4493, -0.9818, -0.2414, +0.1465, +0.0074, +0.1783, +0.0959, -0.0730, +0.0722, +0.2628, -0.0635, -0.1643, -0.1292, -0.0130, +0.3392, -0.0943, -0.0947, +0.2819, -0.2740, +0.0396, -0.4328, -0.2749, -0.0812, +0.2344, +0.2273, -0.6296, +0.3417, -0.2282, +0.0739, -0.1244, +0.4453, +0.3020, -0.4413, -0.1126, +0.2636, -0.4832, -0.0293, +0.0941, -0.2804, +0.0153, -0.1717, -0.1063, -0.2515, -0.3199, +0.3667, -0.2324, +0.2294, +0.0246, +0.0593, -0.1996, +0.0713, +0.1961, +0.5011, +0.1511, +0.1357, +0.0753, +0.1068, -0.9525, +0.1665, -0.6526, +0.1655, +0.0310, +0.1485, +0.0571, -0.1391, +0.0852, +0.1682, +0.1411, -0.0472, -0.2163, +0.3395, +0.0348, -0.3560, +0.1767, -0.6339, -0.3874, -0.2927, +0.1617, -0.1497, +0.0753, +0.0138, +0.0094, +0.1580, +0.1195, +0.0525, +0.5206, +0.0334, -0.2583, -0.1034, -0.2406, +0.1169, -0.0148, +0.0985, -0.0254, +0.1124, +0.3449, +0.1616, -0.2785, +0.2490, -0.0847, -0.1535, -0.4076, -0.3406, -0.2049, -0.2246, +0.3235, +0.2426, +0.0597, +0.0995, +0.0328, +0.2919, -0.0782, -0.1348, -0.0050, -0.0453, +0.3151, +0.0136, +0.2667, -0.4870, +0.1822, -0.0651, +0.1189, +0.4254, -0.0163, -0.0231, +0.1072, +0.3848],
-[ -0.2626, +0.1906, +0.0159, -0.5722, -0.1372, -0.1161, +0.1322, +0.4720, -0.0829, +0.0818, -0.2520, +0.2281, -0.4011, +0.1927, +0.2289, -0.4195, +0.0081, +0.1158, -0.0402, +0.0950, -0.0919, +0.0801, +0.2395, +0.0689, -0.3084, +0.0268, -0.1748, +0.1271, +0.2266, -0.5446, +0.2666, -0.0929, +0.1289, +0.0600, +0.2130, +0.1434, -0.5269, -0.2001, +0.1484, -0.1686, +0.1465, +0.2128, +0.2418, -0.0679, +0.0942, -0.1425, +0.1829, +0.0297, +0.1505, -0.0156, +0.1377, -0.2170, -0.3740, -0.3405, +0.3630, -0.2488, +0.0566, -1.3841, +0.1982, +0.0943, +0.6569, +0.3589, +0.0511, +0.0752, -0.1480, -0.0214, -0.3318, -0.3824, -0.2357, -0.2268, -0.0264, -0.2861, +0.1390, -0.1438, +0.1137, +0.3078, -0.1841, -0.4639, +0.0032, -0.1726, +0.0795, +0.3248, +0.1505, -0.3801, -0.0616, -0.0979, -0.2185, +0.1893, +0.3569, +0.0229, -0.2571, +0.0186, +0.0936, +0.1646, +0.6127, -0.1860, -0.1712, -0.3706, -0.2717, +0.0496, -0.2094, +0.3110, +0.1764, +0.1597, +0.0294, +0.4132, +0.0404, -0.5775, -0.4119, -0.1210, +0.3285, +0.1140, +0.0009, +0.1166, +0.1456, -0.0536, -0.0209, -0.2326, -0.1501, +0.1628, +0.2322, -0.2931, +0.1086, +0.0664, +0.4100, +0.0828, -0.0044, -0.3212],
-[ -0.2998, -0.0738, -0.1513, +0.1247, +0.1899, +0.0987, -0.1714, +0.0683, -0.1489, -0.1247, +0.1166, +0.1891, -0.2348, +0.0066, +0.4323, +0.1324, +0.0567, -0.0832, +0.3091, -0.0532, -0.0263, +0.2447, -0.4638, +0.1947, -0.2422, +0.0567, +0.0925, +0.0819, +0.2029, +0.6120, -0.1958, +0.2320, +0.4321, -0.4380, +0.1854, -0.1932, +0.3976, +0.0167, -0.3029, -0.2789, -0.1836, +0.3506, +0.1142, -0.3089, -0.0155, +0.2917, -0.0075, -0.2264, -0.1235, -0.4551, -0.0861, +0.3406, -0.1878, +0.0997, -0.1639, -0.4325, +0.2613, -0.0110, -0.2154, -0.1120, +0.1183, -0.0160, +0.0826, -0.2044, +0.1645, +0.2868, -0.3488, +0.1002, +0.1681, +0.1152, -0.1621, -0.0359, +0.1327, +0.1303, -0.0409, +0.2150, -0.0534, +0.0391, +0.0398, +0.0562, -0.0010, -0.2104, -0.7669, -0.0526, -0.6345, +0.1331, +0.2693, -0.2896, -0.1767, -0.0304, +0.2403, -0.0068, +0.0947, +0.1147, +0.0409, -0.2276, -0.0863, +0.0982, -0.0374, -0.3437, -0.2203, -0.2168, -0.4528, +0.0281, +0.1741, +0.0721, -0.4683, +0.3592, -0.4125, -0.2943, -0.0418, -0.3669, -0.0151, +0.2583, +0.0446, +0.0434, +0.2630, -0.1901, +0.1523, -0.1569, -0.0261, +0.2346, -0.0361, -0.0086, -0.0521, -0.3845, +0.1049, -0.1093],
-[ -0.0168, -0.4458, +0.1942, +0.3798, -0.1351, +0.3490, -0.0996, +0.3007, +0.3864, +0.2677, +0.1881, +0.4173, -0.0480, +0.0208, +0.1373, +0.3895, -0.1900, -0.2243, -0.4441, +0.1671, -0.1908, +0.1916, -0.2027, -0.0950, -0.3711, +0.0144, +0.0048, +0.2085, +0.0899, +0.2141, -0.1910, +0.1190, -0.0588, -0.0655, +0.4096, -0.0181, -0.2487, +0.1523, +0.0283, -0.7074, -0.1608, +0.1667, +0.2706, -0.3745, -0.1894, +0.0808, +0.1107, -0.1004, +0.1992, -0.2060, +0.0339, -0.3551, -0.0597, -0.0517, +0.1393, -0.1482, -0.0038, -0.1573, +0.0883, -0.9840, +0.2895, +0.0765, +0.2400, -0.2997, +0.3613, +0.0350, +0.1777, +0.2983, +0.1176, +0.2537, -0.0739, +0.0006, -0.0600, +0.1464, -0.1229, -0.0311, -0.0771, -0.7318, -0.2761, +0.1637, +0.0035, -0.0194, -0.0833, -0.1349, -0.7954, +0.2362, +0.1254, -0.2388, +0.2375, -0.1963, +0.0404, -0.3887, -0.0391, +0.2400, -0.1575, -0.3568, +0.2793, -0.2091, +0.0211, +0.1187, +0.3964, +0.1564, -0.0736, -0.6786, -0.0531, +0.1627, -0.5970, -0.1192, +0.1050, -0.0145, -0.0518, +0.0386, +0.0412, +0.5335, -0.1619, -0.3176, +0.3743, -0.0002, -0.4408, +0.1617, +0.0233, +0.3467, -0.1305, +0.1143, -0.2537, +0.3384, -0.7350, -0.0479],
-[ +0.1792, -0.0538, -0.2786, +0.1202, -0.6593, +0.2724, -0.3845, +0.1834, +0.3114, +0.0188, -0.0799, +0.0130, +0.3213, -0.0154, +0.1247, -0.3229, +0.2813, +0.2138, -0.0917, -0.2363, -0.3678, +0.1511, -0.1976, -0.0504, -0.2789, -0.3925, -0.0762, -0.4634, +0.1507, -0.1855, +0.1760, +0.5578, +0.0665, -0.6775, +0.1183, -0.0891, +0.0081, -0.0551, +0.2224, -0.4622, -1.3207, +0.2661, +0.2669, -0.4883, -0.0982, -0.1005, -0.9165, +0.0882, -0.2453, +0.1193, -0.6679, +0.2242, +0.1134, +0.2089, +0.2412, -0.0726, +0.2932, -0.1572, +0.1877, -0.1134, +0.0212, -0.4043, -0.0081, +0.3070, -0.5104, +0.0023, +0.0509, +0.2641, -0.4226, +0.2353, +0.1801, +0.2648, +0.4037, +0.3656, -0.0902, -0.2083, -0.0644, -0.1504, +0.4869, +0.0089, +0.3296, +0.2200, +0.0874, +0.3023, -0.2181, +0.4218, -0.0435, +0.2051, +0.0916, +0.0242, +0.3354, -0.2871, +0.0763, -0.2531, -0.1972, +0.2802, -0.1290, +0.3825, +0.0606, +0.1270, +0.1836, +0.6563, -0.0714, -0.0703, +0.1128, -0.2506, -0.0631, -0.1636, -0.7413, +0.2609, +0.0319, -0.1291, -0.1161, +0.2079, +0.1388, +0.1157, +0.1809, -0.2323, -0.1051, -0.4299, +0.1876, -0.2504, +0.0617, -0.2639, -0.3319, +0.1634, +0.1862, -0.1007],
-[ -0.0147, -0.0639, +0.1008, +0.4990, +0.1531, -0.9325, +0.0238, +0.2393, +0.2306, +0.0683, -0.1566, +0.3142, +0.2203, +0.2258, -0.2943, +0.3765, -0.2988, +0.3902, +0.0185, +0.0039, -0.5539, +0.2588, -0.6650, +0.1318, +0.2560, +0.3680, -0.4079, -0.3864, -0.4923, +0.4272, +0.2314, -0.0254, +0.0104, -0.0265, +0.0352, -0.1241, -0.1193, -0.1553, +0.2534, -0.3951, +0.0661, -0.1445, +0.3153, +0.2310, -0.1020, +0.0582, +0.2351, -0.1744, +0.0568, -0.0010, -0.1221, -0.1725, +0.2274, -0.1963, -0.1775, +0.2182, +0.1631, -0.2170, +0.2137, +0.1525, -0.0944, +0.2513, -0.0597, -0.1106, +0.0882, -0.3798, -0.0551, +0.0147, +0.4100, +0.2900, -0.1498, +0.1748, -0.0446, -0.0909, +0.1704, -0.0100, +0.1317, +0.2471, +0.0569, +0.0891, +0.0411, +0.0695, +0.5479, -0.4577, +0.1407, -0.5910, +0.4646, -0.1887, -0.3553, -0.0068, -0.1807, +0.2212, +0.3963, +0.3808, -0.2139, -0.1677, -0.1488, -0.0411, -0.0385, +0.1535, -0.1921, +0.2639, -0.0658, +0.1008, +0.0469, -0.5127, +0.2267, +0.0552, +0.1902, +0.1366, -0.0367, +0.1080, +0.2582, -0.1765, +0.0865, -0.0173, -0.1502, +0.1298, +0.1194, -0.0114, +0.5047, -0.6161, +0.1684, +0.1423, -0.0740, -0.0017, -0.4251, +0.1572],
-[ -0.2140, -0.3271, +0.0936, +0.1970, +0.0270, -0.0738, -0.1122, +0.2351, -0.2764, -0.3042, +0.3065, +0.3369, -0.0030, +0.0794, -0.4086, +0.0829, +0.0348, +0.4357, -0.3144, -0.3475, +0.2103, +0.2416, +0.3890, -0.0766, -0.0491, -0.1185, +0.1126, -0.1474, -0.1488, -0.2475, +0.5842, -0.4185, +0.4351, -0.5985, -0.2610, +0.1723, +0.0568, +0.0440, -0.0690, -0.1620, -0.1744, -0.3308, +0.0705, -0.0517, +0.0700, -0.1315, +0.2611, -0.3889, +0.0096, -1.0121, -0.4038, -0.0688, -0.0475, -0.0606, -0.4827, -0.1614, -0.3999, +0.1290, -0.2109, +0.0517, +0.2618, -0.0180, -0.1866, -0.3439, -0.5200, -0.6740, +0.1756, -0.2538, -0.0803, +0.0834, +0.4017, -0.0115, -0.1462, -0.0219, -0.3289, -0.4086, +0.0987, +0.2068, -0.1242, -0.2455, -0.1314, +0.4457, -0.5468, +0.0506, -0.2755, +0.5574, -0.0027, -0.1421, -0.2566, -0.0342, -0.6687, -0.1825, -0.3673, -0.2854, +0.2990, +0.4404, +0.1242, -0.4129, +0.0107, -0.9073, +0.4019, +0.0232, -0.6491, -0.6974, +0.2077, +0.0170, +0.0305, -0.0179, +0.0274, -0.3503, +0.0749, +0.3969, +0.1079, -0.3485, -0.0974, -0.5856, -0.3906, -0.2659, -0.5340, -0.6874, +0.0822, -0.7379, -0.4552, +0.1984, -0.5178, +0.0519, -0.0462, -0.2613],
-[ -0.0990, +0.0647, +0.0344, -0.4416, -0.2603, +0.0360, -0.2100, +0.1608, -0.0658, -0.1921, -0.4526, +0.4287, -0.3017, +0.2185, -0.5238, -0.0081, +0.3877, -0.0125, +0.2629, +0.0482, +0.2608, -0.1868, +0.1154, -0.3084, -0.0315, -0.2967, -0.3124, +0.3164, +0.0632, +0.0385, -0.0028, -0.0044, +0.3284, +0.3250, -0.1464, -0.4270, +0.0371, -0.1594, +0.2852, -0.0357, -0.2120, +0.0183, +0.0538, -0.0239, +0.0921, -0.3313, +0.3179, -0.3367, -0.2236, -0.2502, +0.3334, +0.3626, -0.0926, +0.1143, -0.2168, -0.4905, +0.2027, +0.2457, +0.0761, -0.4009, -0.1845, +0.2317, +0.0458, -0.2172, -0.0563, +0.2718, +0.1883, -0.1079, -0.5020, +0.5858, +0.3020, -0.1742, -0.4436, +0.0164, -0.0947, +0.0592, -0.2733, -0.1155, -0.3387, -0.0347, -0.0076, -0.3443, +0.0917, -0.0111, -0.4430, +0.1455, -0.1546, +0.2988, -0.0642, -0.1858, +0.5505, +0.4235, -0.2500, -0.0868, +0.0040, -0.0055, -0.1632, +0.4762, +0.1038, +0.2019, -0.5454, -0.4380, -0.4388, -0.0981, +0.2046, +0.0618, -0.1465, -0.3141, -0.0221, -0.2583, -0.6180, +0.4901, +0.0557, +0.2242, +0.1174, +0.2609, +0.1025, +0.0762, -0.0803, +0.2245, -0.0595, -0.4999, +0.4982, +0.0145, +0.2611, +0.4816, -0.1663, +0.1402],
-[ +0.1015, -0.2188, -0.0059, -0.0043, +0.3909, -0.0640, -0.0354, +0.2428, -0.0448, -0.1089, -0.2626, +0.0875, +0.2317, +0.0832, +0.3148, +0.3355, +0.1300, -0.2864, -0.2355, -0.0749, +0.1873, -0.2631, -0.1110, -0.1718, +0.1023, -0.0858, -0.0301, -0.4857, -0.2234, +0.1080, -0.0177, +0.0591, +0.0068, +0.3276, +0.4901, +0.2524, -0.0358, -0.4197, -0.2396, -0.4071, -0.0771, +0.0941, +0.1835, +0.5056, +0.1202, -0.2230, -0.0365, -0.5363, +0.0206, -0.2307, -0.0866, -0.0068, -0.4793, -0.1669, -0.1043, -0.0190, -0.1292, +0.1839, +0.4037, -0.0492, +0.0248, +0.0850, +0.2228, +0.2684, +0.0174, -0.0150, -0.2136, +0.0006, -0.1773, +0.3960, -0.1461, -0.3662, -0.0490, +0.4252, -0.0163, +0.0062, +0.2475, -0.0128, +0.1257, -0.3295, -0.1532, -0.2940, +0.0892, -0.3498, +0.5167, -0.1376, +0.1647, -0.0583, -0.0494, -0.0057, +0.2688, -0.3080, -0.2907, +0.0631, +0.1013, -0.2300, -0.0029, -0.0787, -0.2467, +0.2660, -0.2953, +0.1714, +0.1873, +0.0712, -0.2960, +0.0469, -0.3154, +0.0570, +0.1899, +0.1088, +0.2432, -0.1520, +0.4387, +0.0371, -0.1384, -0.1175, -0.3142, -0.0365, -0.0566, -0.0038, +0.3015, -0.4169, -0.0828, -0.3635, -0.0764, -0.8747, -0.0931, -0.0060],
-[ -0.3422, +0.2775, -0.1187, -0.6212, +0.4813, +0.1672, -0.0518, +0.0651, +0.2508, -0.0946, +0.1564, +0.4984, +0.2039, -0.1914, +0.0976, -0.8370, -0.1036, -0.2344, +0.2363, +0.3397, +0.2027, +0.0463, +0.0514, +0.0550, -0.0828, +0.1674, -0.2382, -0.2400, -0.1485, +0.2035, -0.2854, +0.1030, -0.2427, +0.1639, -0.0835, -0.2393, -0.3461, -0.2118, -0.3884, +0.1347, +0.1618, -0.3030, -0.0894, +0.4111, -0.1494, +0.2086, +0.2784, +0.4828, +0.2448, -0.1454, +0.0891, +0.1214, +0.1245, -0.0405, +0.2439, -0.2381, +0.3009, -0.7438, +0.2052, +0.3910, -0.2746, +0.4468, -0.2083, +0.2919, -0.0023, +0.3302, +0.1301, +0.3699, +0.3749, -0.0596, +0.2589, +0.0147, -0.1022, -0.5102, -0.1049, -0.1672, -0.5536, +0.1310, -0.2086, -0.7637, -0.0547, +0.2275, -0.5628, +0.0801, -0.2362, +0.5717, -0.8625, -0.0002, +0.2962, +0.5086, -0.4095, -0.0300, +0.0390, -0.1372, +0.0395, -0.1132, +0.2392, -0.0060, +0.6539, -0.0819, -0.2881, -0.3017, +0.1395, -0.1411, -0.3518, +0.0177, +0.0801, -0.1510, -0.8548, -0.0499, +0.1037, -0.0782, +0.2467, +0.2622, +0.1534, +0.3487, -0.2784, +0.0157, -0.0292, +0.0682, -0.0555, +0.1900, -0.0140, +0.1117, -0.0425, +0.2222, +0.1421, +0.0896],
-[ +0.3215, +0.1030, -0.5264, +0.3126, +0.4631, -0.0905, -0.1420, +0.0617, -0.1247, -0.2717, -0.2152, -0.0178, +0.3707, -0.1003, -0.3412, +0.0482, -0.2545, -0.1400, +0.0013, -0.2387, +0.0183, +0.3234, -0.0895, -0.4326, -0.0078, -0.0021, +0.0602, +0.0094, -0.5288, -0.0352, +0.3186, -0.2452, -0.7510, +0.0166, -0.0443, -0.5046, +0.0900, +0.0308, +0.1221, -0.2926, -0.5428, -0.5815, +0.0009, +0.1007, -0.0257, -0.2028, -0.0313, +0.1233, -0.0253, +0.1077, -0.1430, +0.4582, -0.0574, -0.0861, +0.2536, -0.3528, -0.5794, -0.0742, -0.2056, +0.1496, +0.0894, -0.2854, -0.1345, +0.2715, -0.0201, +0.2340, -0.0941, -0.1626, +0.0095, +0.1054, +0.1596, -0.6335, +0.2332, -0.3196, +0.3785, +0.1697, -0.1321, -0.0227, -0.3515, +0.1661, +0.1890, -0.0586, +0.1805, +0.0600, -0.7643, +0.2405, -0.0662, +0.0525, -0.0916, +0.0225, -0.1066, +0.5072, -0.1718, +0.1307, -0.1050, -0.1172, -0.5932, -0.0769, -0.1079, -0.0396, -0.0203, +0.1204, +0.2182, -0.0285, -0.0734, +0.1621, -0.2796, -0.2511, +0.5154, -0.1256, +0.0575, +0.4053, -0.3265, +0.5537, +0.1468, +0.0024, +0.0659, +0.3903, -0.2981, +0.0748, -0.7142, +0.0211, -0.0084, +0.2114, -0.0336, +0.2062, -0.1641, +0.0345],
-[ -0.1767, +0.4111, +0.0166, +0.1680, +0.3432, -0.1508, -0.3377, +0.1994, -0.2411, -0.5138, -0.1948, -0.4879, -0.0517, -0.5196, +0.4378, -0.1487, +0.1221, -0.0241, -0.0411, -0.3271, +0.0504, +0.4184, -0.2106, +0.0274, -0.2030, +0.0138, -0.3463, +0.4342, -0.3886, -0.1702, +0.0772, -0.6914, -0.1251, -0.5027, -0.2141, +0.1692, +0.0531, -0.0134, +0.1365, -0.0471, -0.5026, -0.5345, -0.0750, -0.6540, +0.4107, -0.0253, -0.4962, -0.0475, -0.0567, -0.0428, +0.1786, -0.1019, -0.0177, -0.3989, +0.0805, -0.6437, +0.0826, -0.0812, +0.2180, +0.0356, +0.1099, +0.1517, -0.2150, +0.2837, +0.3894, +0.0356, -0.1908, -0.0985, -0.1478, -0.0040, +0.0349, +0.3303, -0.1168, +0.0131, +0.1204, +0.0645, +0.1481, -0.0304, -0.0489, -0.2517, +0.1785, -0.4240, +0.3172, +0.0560, -0.0079, +0.3547, -0.0889, -0.3845, -0.1570, +0.0567, +0.2413, +0.3162, -0.5907, -0.1475, +0.0735, +0.1308, +0.0247, -0.2660, -0.7232, -0.1863, -0.3806, +0.0829, -0.2574, -0.0379, +0.0206, -0.2949, +0.1580, +0.2900, +0.0795, +0.0523, +0.0383, +0.0524, -0.0755, +0.0862, +0.3876, -0.0720, -0.2409, +0.0926, -0.3902, -0.5682, +0.0380, -0.0429, +0.0813, -0.2425, +0.3830, +0.0894, -0.3435, -0.0040],
-[ +0.2445, -0.3221, -0.2894, +0.1155, -0.0250, +0.0264, +0.4052, +0.1500, +0.2113, +0.1744, -0.1288, -0.0519, -0.4755, +0.0138, -0.1508, -0.0906, +0.1170, +0.1912, -0.0426, +0.1228, -0.3168, -0.1103, -0.4555, -0.0277, -0.3807, -0.7228, +0.1508, +0.0784, +0.3282, +0.0603, +0.0172, -0.0236, +0.2048, +0.2340, -0.0488, -0.1596, +0.0161, +0.0815, +0.2955, -0.1378, -0.5930, +0.2498, +0.1344, -0.5621, -0.2068, -0.0203, +0.2416, -0.0432, +0.3372, +0.0234, -0.2795, +0.1132, -0.2562, +0.2618, +0.4585, +0.1456, -0.1266, +0.3029, +0.2788, -0.1247, -0.5935, -0.1186, +0.0734, -0.0350, -0.0946, -0.0564, -0.0764, -0.0607, +0.0953, +0.1742, -0.1591, +0.0559, -0.0171, -0.0351, -0.3491, +0.2183, -0.3547, +0.2335, +0.2555, +0.2547, +0.1248, -0.0061, +0.1710, +0.0383, +0.0616, +0.2185, -1.0023, -0.1936, -0.0807, +0.2063, -0.0745, +0.0708, +0.1399, -0.0537, +0.2268, -0.2947, -0.4455, -0.1865, -0.1535, -0.0317, -0.0848, -0.2121, +0.3018, +0.0905, +0.0159, +0.3521, -0.0130, +0.5538, +0.0833, +0.2445, +0.2165, +0.1367, -0.0128, -0.4681, +0.1047, +0.2925, +0.0895, -0.1273, -0.3037, +0.0461, -0.2035, +0.0707, -0.0067, +0.1958, -0.1122, -0.0648, -0.2368, +0.3070],
-[ +0.0332, +0.1108, +0.1055, -0.2215, -0.2207, -0.0961, +0.1551, -0.0297, -0.1572, -0.0777, -0.1128, +0.1579, +0.1274, -0.1284, +0.3304, +0.1920, +0.1354, +0.0697, -0.1628, -0.2876, -0.5614, +0.0893, +0.0028, +0.3967, -0.1001, -0.5001, +0.3025, -0.1845, -0.2045, +0.2131, +0.3582, -0.1054, -0.0401, +0.1481, +0.1523, -0.2040, +0.1310, +0.3809, -0.0179, +0.0166, -0.4429, -0.1629, +0.0148, -0.0044, +0.1835, +0.0591, -0.2337, -0.2281, -0.2868, -0.0554, +0.5748, +0.0107, +0.2273, -0.0109, +0.0614, +0.2047, -0.3292, +0.2108, +0.1956, +0.6115, -0.0865, +0.5195, +0.4667, +0.1747, +0.5170, -0.3925, -0.0643, +0.3511, +0.0903, +0.0125, -0.4273, +0.0862, -0.0428, +0.3079, -0.0357, +0.4272, -0.2383, +0.1451, +0.0454, -0.3505, -0.3626, -0.3535, +0.0587, -0.0526, -0.4949, -0.3365, +0.1256, +0.3631, +0.1206, +0.0588, +0.1959, +0.3120, +0.0314, +0.1693, +0.0071, -0.1606, -0.4374, -0.0889, +0.3226, -0.1604, +0.2967, +0.0151, +0.2558, +0.1964, -0.4702, +0.2784, -0.2398, -0.1751, +0.3346, +0.1903, +0.1093, +0.0678, -0.0278, +0.1809, -0.0615, +0.0831, -0.0425, +0.2375, -0.0217, -0.0493, +0.0006, -0.5245, +0.2295, +0.1216, -0.1974, +0.0019, +0.2227, -0.0325],
-[ -0.0106, -0.1795, -1.0107, +0.1485, +0.0512, +0.1046, -0.0372, +0.1391, -0.0793, +0.0596, -0.1329, -0.4680, -0.0769, +0.3540, -0.0180, +0.1307, -0.2648, +0.0104, -0.2447, -0.4669, -0.3711, -0.1303, +0.3316, -0.4659, +0.0336, -0.3014, -0.0991, -0.1378, -0.0605, -0.1779, -0.1278, +0.1260, -0.0011, +0.4265, -0.3470, +0.2697, +0.2172, -0.0653, +0.4049, +0.1824, -0.1354, -0.2110, +0.0009, +0.3092, -0.5611, +0.0180, +0.1930, +0.0349, +0.1076, +0.1885, -0.1494, -0.3548, -0.5295, +0.1498, +0.1237, -0.0220, -0.3594, -0.3349, +0.1907, -0.4955, -0.0173, +0.4271, +0.1763, +0.2866, -0.2870, +0.0845, +0.4142, -0.2350, -0.1335, -0.1367, +0.1219, +0.2963, -0.2772, +0.1208, -0.2441, +0.2727, -0.0634, -0.0623, +0.1754, -0.2124, -0.0798, -0.2362, -0.0698, -0.0271, +0.2826, +0.0072, -0.1003, -0.2082, -0.3241, -0.1478, +0.3451, +0.4445, +0.0610, -0.3286, +0.0459, +0.1432, -0.2174, -0.1884, -0.6035, -0.4182, -0.0975, -0.4158, -0.6764, -0.0864, -0.2861, -0.1959, +0.3165, -0.2087, -0.2985, -0.1759, +0.7873, -0.1147, +0.0419, +0.0908, -0.4405, -0.1625, +0.1020, -0.0612, +0.1512, +0.1949, -0.4173, -0.0379, -0.2300, +0.0369, -0.8316, +0.4121, -0.2343, +0.2659],
-[ +0.1448, -0.1895, -0.5758, +0.2787, -0.4682, -0.3342, +0.0381, +0.0380, -0.0829, -0.0685, +0.4234, -0.0387, -0.3712, -0.3754, +0.1963, +0.2970, +0.0013, +0.1070, +0.1149, -0.2418, -0.6026, +0.0593, -0.4548, +0.1573, +0.2813, -0.0247, +0.1728, +0.1163, -0.2966, -0.1769, +0.4794, +0.4870, +0.3165, -0.4123, -0.5271, -0.2275, -0.1985, +0.2085, -0.1278, -0.1492, +0.2016, +0.2230, -0.5315, +0.3724, -0.2279, +0.3739, -0.2783, +0.2231, +0.2948, +0.4648, -0.0578, -0.0601, +0.1040, +0.0309, -0.2686, +0.1441, -0.0070, -0.1436, +0.0716, -0.7209, -0.1215, +0.1427, -0.1684, -0.5173, -0.5214, +0.1143, +0.3508, +0.4406, +0.3437, +0.0705, -0.2436, -0.3793, +0.2907, -0.2979, +0.0523, -0.3974, -0.2396, +0.2500, +0.1000, +0.0783, -0.1054, -0.3239, -0.4000, -0.1940, +0.2530, -0.0669, +0.4804, +0.1698, +0.2403, -0.1348, -0.1391, +0.2299, -0.2724, +0.2885, -0.1325, -0.2227, +0.3584, -0.1698, -0.0972, +0.5424, +0.0150, -0.1798, -0.3112, +0.3349, -0.2409, -0.7392, +0.4496, +0.0811, +0.1761, -0.3272, -0.4055, -0.3795, -0.1939, +0.2573, -0.0481, +0.4074, +0.0931, +0.0257, -0.0308, +0.0334, +0.0584, -0.1926, +0.2368, +0.0248, -0.0502, +0.1326, +0.1125, +0.0755],
-[ -0.0107, -0.2142, -0.2136, -0.0900, +0.1327, -0.4218, +0.1241, -0.0774, -0.3471, -0.2286, -0.1076, +0.3155, +0.0430, -0.2002, +0.0599, +0.2265, -0.1557, +0.1386, +0.0237, +0.0503, +0.0536, -0.0295, -0.1443, -0.3330, +0.1421, +0.1977, -0.4083, -0.0982, -0.3459, -0.0667, +0.0876, -0.0609, +0.1196, -0.0744, -0.2453, +0.2029, +0.4330, -0.0031, -0.1952, +0.3225, -0.1235, -0.2048, +0.1982, -0.2002, -0.1531, -0.0925, +0.5035, +0.0646, +0.0497, +0.2475, +0.3087, -0.2175, -0.3011, +0.2460, +0.1380, -0.1187, +0.1174, +0.0075, +0.0148, +0.0186, +0.3429, -0.0175, +0.2382, +0.0246, +0.1629, +0.0974, -0.0822, -0.0381, +0.0131, +0.0314, +0.1902, -0.0336, -0.0286, +0.3354, +0.0584, -0.1462, -0.0521, +0.0856, +0.5001, +0.5584, -0.3181, +0.1374, +0.0173, +0.1763, +0.0470, +0.0321, +0.0882, -0.6272, -0.0242, +0.1606, -0.1326, +0.2423, +0.2048, +0.0627, +0.4490, -0.0008, -0.0345, -0.1498, -0.0128, -0.0674, +0.0725, +0.0137, -0.0963, +0.2060, -0.1878, -0.3905, -0.1744, -0.2246, +0.0068, +0.4614, +0.3251, -0.3699, -0.0626, -0.3641, -0.2819, +0.4233, +0.1520, +0.2650, -0.0881, -0.0252, +0.1102, -0.0721, -0.0903, +0.1662, +0.0963, -0.2380, -0.1902, -0.2317],
-[ +0.1042, +0.0129, +0.0591, +0.1099, +0.0746, -0.3372, -0.1807, -0.1851, +0.1693, -0.1435, -0.0469, -0.1883, +0.2842, -0.1832, +0.2719, -0.1084, -0.6379, -0.0003, -0.2695, +0.2047, +0.1416, -0.2237, +0.0454, -0.4013, -0.0354, +0.1184, -0.0375, -0.1689, +0.0844, -0.2277, -0.0154, -0.1369, +0.2907, -0.1738, -0.0193, +0.6037, +0.0534, -0.0553, -0.0678, +0.1018, -0.3696, +0.2454, -0.4718, -0.0576, +0.2242, -0.4343, +0.1482, -0.2811, +0.1014, +0.3586, -0.0633, -0.7224, -0.5258, +0.2335, -0.0151, -0.1089, -0.1031, -0.1024, -0.3131, +0.1387, -0.4169, -0.0255, -0.0380, +0.2975, +0.0797, -0.1790, -0.0312, -0.2449, +0.0739, -0.1094, +0.1020, -0.3045, -0.0331, -0.1971, -0.2380, -0.2288, -0.0653, +0.1428, +0.1224, +0.1660, +0.1744, -0.3307, -0.2782, +0.2870, +0.0958, -0.3593, -0.1365, -0.1877, -0.2087, -0.2748, -0.2107, +0.1078, +0.0981, +0.0487, +0.3310, +0.2330, +0.1792, -0.2385, +0.0179, -0.4904, -0.4892, -0.2479, +0.0317, -0.0302, +0.1790, +0.1996, +0.3029, +0.4338, -0.2445, -0.3634, -0.0027, +0.0235, +0.0697, -0.2882, -0.6100, +0.0349, +0.1505, -0.0612, +0.2060, +0.1764, +0.1363, +0.1618, +0.0997, -0.0475, -0.3545, -0.2044, -0.2669, +0.1903],
-[ -0.6690, -0.4061, +0.3611, -0.0323, -0.1826, +0.1533, +0.4289, +0.4041, -0.0787, +0.1813, -0.2523, -0.2508, -0.1368, +0.2832, +0.2357, +0.0674, +0.2526, -0.0948, +0.0302, -0.2113, -0.0810, -0.1121, +0.0445, -0.3236, +0.1171, -0.2315, -0.1339, +0.3387, +0.0430, +0.4383, -0.1667, +0.1842, -0.3316, +0.0995, -0.0591, -0.2052, -0.0729, -0.1248, -0.1520, -0.0145, +0.4185, +0.2712, +0.2678, -0.4791, +0.3847, +0.1647, +0.1293, -0.2229, -0.0904, +0.1532, +0.1299, +0.3114, -0.5892, -0.0975, -0.0179, +0.1936, -0.7019, -0.5316, +0.1220, +0.0368, +0.2585, +0.2070, +0.0252, -0.3224, -0.1460, -0.0624, +0.4077, +0.0120, -0.1081, +0.3095, -0.0344, +0.4012, -0.1926, -0.2384, +0.1148, +0.2245, -0.3863, -0.0477, -0.0072, -0.1912, -0.2179, +0.1650, -0.1340, +0.1677, -0.1649, -0.1423, +0.2822, -0.0503, -0.2050, -0.1846, -0.7356, +0.0478, -0.0624, +0.0528, -0.1191, -0.1598, +0.2577, -0.0716, +0.0590, +0.1427, -0.1972, -0.3610, -0.3062, -0.0018, +0.0144, +0.1937, +0.1316, +0.0844, -0.3294, +0.0496, -0.0912, -0.0461, -0.4000, -0.6219, -0.0409, +0.4040, -0.1048, -0.3856, +0.0791, +0.2092, +0.0674, +0.0472, +0.0275, -0.4645, +0.1749, +0.2235, -0.3431, -0.1454],
-[ -0.0879, -0.0935, -0.1936, +0.5197, -0.1219, +0.3352, -0.0133, -0.0712, +0.3519, -0.0763, -0.3465, -0.3300, +0.1453, -0.0745, -0.0164, -0.3817, -0.1034, +0.0888, -0.2118, -0.0584, +0.3611, -0.2505, +0.2527, +0.1162, +0.3649, +0.4534, -0.4969, +0.3260, -0.1154, -0.0981, -0.1811, -0.5510, -0.0919, +0.3503, +0.4335, -0.0208, +0.1106, -0.3258, -0.0314, +0.3403, -0.3097, +0.0929, -0.1616, +0.0126, +0.0622, -0.5417, -0.1849, +0.1308, +0.3605, +0.2931, -0.2155, -0.4689, +0.2639, +0.2679, -0.5587, -0.4971, +0.2446, +0.6374, -0.5243, -0.3544, +0.3024, +0.0500, +0.0144, -0.6006, +0.3731, -0.3271, +0.1171, -0.2156, -0.6001, +0.1787, +0.1919, +0.0786, +0.0515, -0.2108, -0.0592, +0.0262, -0.0166, +0.3152, +0.1522, +0.0947, +0.4798, -0.2640, +0.0736, +0.3035, -0.0324, -0.1794, -0.0064, +0.5053, -0.0685, +0.0393, +0.6935, -0.5272, -0.0964, +0.2572, +0.0731, -0.1272, -0.6316, -0.3586, -0.0719, -0.0145, -0.1083, +0.0464, -0.2846, +0.2393, -0.2754, -0.0077, -0.0043, +0.2452, -0.7249, -0.2202, +0.2876, -0.1782, +0.1292, +0.3699, +0.3619, -0.0287, +0.3014, -0.2317, +0.1422, +0.3546, +0.2010, +0.4777, +0.0428, -0.5397, -0.1933, -0.1243, -0.1496, +0.0371],
-[ -0.0777, +0.0994, +0.0355, +0.0499, +0.0912, -0.4674, +0.2269, +0.0750, +0.2211, -0.2368, +0.1482, -0.1467, +0.4354, +0.0821, +0.1812, -0.1193, -0.0613, +0.0097, +0.2792, +0.0710, -0.1106, +0.1912, +0.2040, +0.2364, -0.2097, +0.0622, -0.2466, -0.4281, +0.2414, +0.2629, +0.0371, -0.1220, -0.1557, +0.0406, +0.0109, +0.0814, -0.1393, +0.1957, +0.0884, +0.0513, +0.2586, +0.1415, -0.0214, -0.1080, -0.0189, -0.0288, -0.0338, -0.1389, -0.0299, -0.2894, +0.2674, -0.4489, -0.9645, -0.3974, +0.1226, -0.6343, -0.1116, +0.0569, +0.1864, -0.3531, -0.0256, -0.0620, -0.1864, -0.0002, +0.1601, -0.1476, +0.0685, -0.7779, +0.0333, +0.0839, +0.0528, -0.0343, +0.0053, -0.0560, +0.1991, +0.2184, +0.3194, +0.2558, +0.1077, +0.2000, +0.2533, +0.7330, -0.0616, -0.0165, -0.7192, +0.1282, +0.0961, -0.2649, -0.1855, -0.1103, +0.0819, +0.0470, -0.1331, -0.0771, +0.0484, -0.0178, +0.2832, +0.2894, +0.1649, +0.1913, +0.2145, +0.1483, -0.1606, +0.1300, -0.8030, +0.1443, -0.1876, +0.1261, +0.0714, -0.0429, +0.3861, +0.1758, +0.0043, -0.0500, +0.0689, +0.3115, +0.0667, -0.2230, +0.1086, +0.2952, -0.3109, -0.3093, +0.0554, -0.0245, -0.0397, +0.2274, -0.2004, +0.3354],
-[ +0.3834, -0.2970, +0.0693, -0.0619, -0.2312, +0.0044, +0.1783, -0.0599, +0.0585, +0.0275, +0.4338, -0.0722, -0.0090, -0.0405, -0.3517, +0.1827, +0.1690, -0.2387, +0.0735, -0.5833, -0.0576, -0.0895, -0.1242, +0.1094, +0.1448, +0.0156, -0.2802, -0.2083, +0.1598, -0.2769, -0.3661, +0.1990, -0.3264, -0.8629, +0.1671, -0.1886, -0.0530, -0.0574, -0.1298, +0.2935, -0.4790, -0.5351, -0.1290, +0.3031, +0.2099, -0.1599, -0.3362, -0.2019, +0.3001, +0.2095, -0.2143, -0.3300, +0.0041, +0.0362, -0.1581, +0.2439, -0.0697, +0.2571, -0.0095, -0.0982, +0.0056, -0.1928, -0.4881, -0.0052, -0.3691, +0.0098, -0.2662, -0.1979, -0.0825, -0.2171, -0.2089, +0.0930, +0.3293, +0.1200, -0.5116, -0.2453, +0.2801, -0.1298, +0.0679, -0.0766, -0.2082, +0.2169, +0.2892, +0.3407, -0.1135, +0.4344, +0.2666, +0.0543, -0.1126, -0.0424, +0.2620, +0.4735, -0.1789, +0.0870, +0.3178, +0.5883, +0.2862, +0.0072, -0.0330, +0.0150, +0.1277, -0.3052, -0.1006, +0.1095, -0.5257, -0.0278, -0.0217, +0.4799, -0.1704, -0.0741, +0.4283, +0.0792, +0.2134, -0.0473, +0.1116, -0.1416, -0.0489, -0.1338, +0.1532, +0.0737, -0.0105, -0.4169, -0.1468, +0.0573, -0.7244, -0.0113, -0.0027, -0.0978],
-[ +0.5952, +0.3408, +0.0172, +0.2719, -0.0426, +0.4306, -0.2634, +0.1054, -0.0128, -0.2360, -0.2531, -0.2114, -0.3016, -0.1541, +0.4044, +0.1914, -0.2081, -0.2766, -0.1250, -0.4496, -0.0649, +0.1175, -0.1754, +0.0928, +0.0995, -0.1906, +0.1887, -0.1689, -0.2972, -0.4089, +0.0109, +0.1868, +0.3658, +0.1497, -0.3773, -0.1926, -0.1043, +0.3018, -0.1868, +0.0769, -0.1214, +0.2259, +0.1076, -0.3811, +0.3021, -0.0662, -0.1938, +0.0730, -0.0141, +0.0559, -0.5150, +0.0252, +0.2179, -0.1829, -0.1317, -0.0134, +0.3307, +0.1064, -0.2619, -0.0376, -0.2149, -0.1717, -0.1534, -0.1198, -0.3179, +0.1305, -0.2788, +0.0140, +0.0286, +0.1083, -0.0183, +0.2554, -0.0158, +0.0695, +0.2224, +0.0491, -0.3450, +0.0567, +0.1413, +0.4495, +0.3825, +0.3585, +0.3753, -0.0599, -0.0589, -0.1657, +0.1589, +0.0386, +0.1114, -0.1198, -0.0319, +0.1412, -0.2602, -0.3174, +0.0411, -0.4132, -0.4969, +0.0281, +0.1082, -0.2284, -0.2720, -0.0416, +0.0901, +0.0221, -0.0072, -0.1729, +0.0065, -0.0727, -0.2902, -0.0596, +0.3046, -0.2508, +0.2946, +0.1691, +0.1094, -0.0917, -0.3400, +0.3388, +0.2042, -0.4066, +0.0417, +0.3045, +0.2068, -0.2250, +0.6056, +0.2218, +0.0393, +0.4209],
-[ -0.2163, -0.6735, +0.0472, +0.1662, -0.5386, -0.0774, +0.3303, -0.3197, -0.2423, +0.0745, -0.0520, -0.1698, +0.2596, +0.2897, +0.2793, -0.0700, -0.5526, -0.0755, -0.1457, +0.1181, -0.2148, +0.1500, +0.2115, +0.1809, -0.0527, +0.0106, +0.2840, -0.1520, +0.0891, +0.3374, -0.1232, -0.3531, -0.0097, +0.2622, -0.2089, -0.2767, -0.0589, +0.2649, -0.0973, +0.2521, -0.4166, -0.0252, -0.1418, -0.2941, -0.1256, +0.1203, -0.8522, +0.2147, -0.4110, -0.1044, -0.1519, -0.0206, -0.0897, +0.2957, +0.0209, +0.2436, -0.4134, -0.4883, +0.1503, -0.4706, -0.3203, +0.2962, -0.3609, -0.1774, -0.0657, +0.4048, +0.2880, -0.2606, -0.1999, -0.3142, -0.2496, +0.0014, -0.2788, -0.2473, -0.1292, -0.3910, -0.1895, +0.2267, +0.2975, -0.1391, -0.0612, -0.3902, -0.2660, -0.2387, -0.1752, +0.0437, -0.5681, -0.1894, -0.1217, +0.0587, -0.3576, +0.0542, -0.1070, +0.0588, +0.0074, -0.2412, -0.1207, +0.1427, +0.0138, +0.2233, -0.2847, -0.5626, +0.1141, +0.0012, -0.1819, -0.5993, -0.1351, -0.3189, -0.0335, +0.2624, -0.2439, -0.0997, -0.0933, -0.0714, +0.2292, +0.2202, +0.1539, -0.0646, -0.1718, +0.2672, +0.0056, +0.2323, +0.1605, +0.1107, +0.1549, +0.0173, -0.4915, -0.0520],
-[ -0.2395, +0.1082, -0.2151, -0.2240, -0.2508, +0.0407, +0.1677, -0.0084, +0.2400, -0.2400, -0.2007, -0.5287, -0.0877, +0.0286, -0.1740, -0.2005, -0.2105, -0.1344, +0.1480, -0.2683, +0.2106, -0.2851, -0.1725, -0.2883, -0.0091, +0.0635, -0.0457, -0.0655, +0.0114, -0.1064, +0.0256, -0.4652, +0.0746, -0.1420, +0.0475, -0.3308, -0.0352, -0.2817, +0.2106, -0.4369, +0.0512, +0.1639, -0.0393, +0.0127, -0.1861, +0.3706, -0.1326, -0.3111, -0.1802, +0.0468, -0.8695, -0.3946, +0.2512, +0.2067, -0.0320, +0.1788, +0.1295, +0.1133, -0.1315, +0.1520, -0.0059, +0.0645, +0.1516, -0.0698, +0.1031, +0.3508, +0.0518, +0.0838, -0.0202, +0.0608, +0.1026, -0.2504, -0.3488, +0.0680, +0.0823, -0.0485, -0.2392, +0.1838, +0.2340, +0.0864, -0.8238, -0.0096, -0.7539, -0.6396, -0.0508, -0.2817, +0.0456, +0.2159, -0.0016, +0.0315, -0.0073, +0.0620, +0.1535, -0.1015, +0.0306, +0.0454, -0.3272, -0.0547, -0.1030, -0.5685, -0.2921, +0.3394, -0.2310, +0.2159, -0.3338, -0.0358, +0.0009, -0.0201, +0.0131, -0.0974, -0.1829, +0.1706, -0.2684, -0.0444, +0.1660, +0.3105, -0.2563, -0.0454, -0.0842, -0.1093, -0.0536, +0.0302, -0.0972, -0.2005, +0.0107, +0.0732, -0.0438, +0.0663],
-[ +0.0686, -0.1319, +0.1578, -0.3115, -0.1053, +0.1549, +0.2026, +0.3332, -0.1355, +0.2737, -0.0735, +0.1123, +0.4531, +0.2477, -0.0257, +0.1564, -0.3674, -0.1256, +0.1678, +0.2737, +0.3228, +0.2598, +0.3361, -0.1607, -0.5808, -0.1166, +0.2046, +0.1681, +0.2143, -0.0169, +0.1161, -0.2318, +0.0337, +0.1461, +0.0441, +0.2919, -0.4899, -0.0727, +0.0982, +0.2526, +0.0552, +0.6004, +0.5736, -0.2223, -0.5650, +0.1801, +0.3024, -0.3968, +0.1984, -0.2853, -0.0482, -0.1149, -0.0921, +0.0218, +0.0841, +0.2279, -0.1176, -0.3152, -0.1646, -0.1158, -0.1729, +0.0370, -0.3291, -0.5383, +0.0670, -0.3762, -0.6796, -0.0860, +0.1358, +0.1148, +0.3606, -0.1959, -0.1589, -0.0206, -0.1312, -0.4897, +0.3045, -0.1620, +0.2109, -0.3497, -0.1020, -0.8788, -0.1518, -0.2748, +0.2034, +0.0852, -0.3075, -0.4856, -0.2341, -0.2566, +0.1598, +0.0043, -0.3940, -0.3725, -0.0530, -0.1074, +0.2087, -0.2613, -0.0982, -0.0016, -0.0411, +0.2699, +0.2735, -0.2934, -0.1908, +0.4955, -0.1301, -0.1888, -0.4906, +0.1670, +0.1018, +0.0266, +0.1781, +0.0031, -0.1535, -0.2982, -0.0919, +0.1921, -0.1798, -0.0400, +0.0564, +0.1094, -0.0851, -0.3558, +0.2266, +0.1664, -0.4936, +0.1331],
-[ -0.0829, +0.2182, -0.2100, -0.3694, +0.2186, -0.4523, -0.1754, -0.0425, -0.0305, -0.2166, -0.0025, -0.2198, -0.1057, -0.6204, -0.1104, -0.2452, -0.0211, +0.5433, +0.2327, +0.1093, -0.5577, +0.3080, +0.1366, -0.1060, -0.0860, +0.0222, -0.5332, +0.0402, -0.0464, -0.2748, +0.3140, -0.2646, -0.2442, -0.0596, +0.0979, +0.0090, +0.4731, -0.1337, -0.0610, +0.3120, +0.0909, +0.0894, -0.0416, -0.1903, +0.2731, +0.1343, -0.0011, +0.2264, +0.2334, -0.0798, -0.2831, -0.4700, +0.0756, +0.0981, -0.0202, -0.8060, -0.0174, -0.3160, -0.1816, -0.3639, -0.5384, -0.1215, +0.1117, +0.0785, +0.1101, +0.0604, -0.4289, +0.0027, +0.4064, +0.0620, +0.0758, +0.1001, +0.4822, -0.0900, +0.3217, +0.1433, -0.2441, +0.0867, -0.2211, +0.2055, +0.0874, -0.3285, -0.3667, -0.3910, +0.0201, +0.0028, -0.0189, -0.0373, -0.4464, -0.2321, +0.1192, +0.0026, +0.0681, -0.0103, -0.4804, +0.0796, -0.1562, +0.3017, -0.1060, -0.1943, +0.1367, -0.1407, -0.0056, -0.1167, +0.3077, +0.2067, +0.1155, -0.0106, +0.0584, +0.1148, -0.0285, +0.2770, +0.2312, +0.0976, +0.1672, +0.1084, +0.0535, +0.2593, +0.1339, -0.2000, -0.1449, -0.1224, -0.3657, +0.0403, +0.0104, +0.0909, -0.0858, -0.1809],
-[ +0.2250, -0.0840, -0.1109, +0.4521, -0.1736, -0.4552, -0.4446, -0.2480, +0.2552, +0.1624, +0.3405, -0.3831, +0.0898, +0.3713, -0.0383, +0.0324, +0.0093, -0.0135, +0.4027, +0.1250, -0.4553, +0.4680, -0.1777, -0.2760, -0.0973, +0.0846, +0.2103, -0.1712, +0.2130, -0.2609, -0.1162, -0.5625, +0.3581, -0.1252, +0.0018, -0.1454, +0.0153, +0.0041, -0.8839, +0.3062, -0.0624, +0.3578, +0.1142, -0.6404, +0.1066, +0.1546, -0.1064, -0.1424, -0.2725, +0.2147, -0.4004, +0.1040, -0.0824, +0.0742, +0.0688, +0.0577, -0.2756, -0.3082, +0.0641, -0.0017, -0.0118, -0.3003, -0.3433, +0.2483, -0.2644, +0.1392, -0.0649, +0.0865, +0.2920, -0.1501, -0.0798, -0.1315, -0.2475, -1.0970, -0.2964, +0.0029, +0.1222, +0.1754, +0.3431, +0.2812, -0.2805, +0.1654, +0.1724, +0.1199, +0.1651, +0.2226, +0.2878, -0.1049, +0.0502, -0.0128, +0.1162, +0.0814, +0.0784, -0.1172, -0.0458, -0.0220, +0.2004, +0.0171, -0.3293, -0.3714, +0.2733, -0.4124, +0.1587, -0.2548, -0.2213, -0.2156, +0.1612, +0.0821, +0.1077, -0.0277, -0.2058, +0.1690, +0.0936, -0.1400, -0.3448, -0.3278, +0.2127, -0.0748, +0.0359, -0.1594, +0.2732, +0.3175, +0.0153, -0.5548, -0.1313, +0.1161, +0.6082, -0.6926],
-[ -0.0732, +0.2253, +0.0032, -0.0549, -0.2564, +0.3007, +0.3424, +0.0831, -0.1338, -0.3387, -0.0127, +0.0345, -0.0145, -0.1680, +0.1195, +0.0837, -0.0707, -0.0937, +0.2572, -0.0441, -0.0152, -0.4240, -0.3129, -0.0871, +0.0003, -0.3298, -0.2884, +0.1462, +0.2674, -0.2651, -0.2476, +0.0750, +0.1392, -0.3641, +0.2545, +0.0877, +0.3429, +0.1779, -0.1412, -0.1485, -0.0703, +0.1189, +0.0306, +0.1297, -0.0944, -0.1656, +0.0831, -0.1307, +0.1673, +0.3148, -0.2151, -0.1995, +0.1090, +0.1548, -0.3994, +0.2153, +0.1078, +0.1781, -0.0598, -0.4006, -0.5840, +0.0388, +0.0068, +0.1585, +0.0454, -0.2677, -0.0196, -0.0652, -0.0635, -0.0819, +0.4911, +0.2954, +0.1933, -0.0785, +0.0523, -0.0260, -0.2621, +0.0674, +0.1783, +0.1606, -0.0044, +0.0092, -0.1628, +0.5500, -0.4279, -0.5668, +0.3769, +0.0797, -0.0083, -0.2193, -0.3738, -0.2367, +0.0116, -0.2397, +0.0234, +0.2543, -0.1666, +0.2266, +0.4588, -0.0574, +0.3247, -0.4261, -0.0089, +0.4571, +0.0313, -0.4023, -0.0465, -0.0825, +0.0458, +0.1550, -0.3583, +0.0507, +0.2776, -0.0226, -0.1508, -0.6477, +0.1156, +0.1034, +0.2133, +0.1774, +0.4070, +0.0463, -0.0209, +0.0353, -0.4120, +0.0919, -0.0687, -0.0749],
-[ -0.2686, -0.0329, +0.2912, -0.1666, -0.2764, +0.3305, -0.0058, -0.4653, +0.1527, +0.1564, -0.4896, +0.0291, +0.3071, -0.7088, -0.3624, -0.2830, +0.0256, -0.3474, -0.3822, -0.2457, -0.4814, -0.2442, -0.3495, -0.2978, -0.4703, +0.3340, +0.3642, -0.0408, +0.0182, -0.1530, -0.1611, +0.0198, -0.0378, +0.2289, +0.0803, -0.5098, +0.1630, +0.3059, +0.4614, -0.0014, -0.3160, +0.0719, +0.0972, -0.2106, -0.0173, -0.0813, -0.4421, -0.2463, -0.7197, -0.5828, -0.0493, -0.0797, +0.3699, -0.0639, +0.1526, +0.2862, -0.7293, -0.2326, +0.0791, +0.2545, +0.0515, -0.7931, -0.3388, +0.1758, +0.3957, -0.1495, +0.0333, -0.3643, +0.0482, -0.0024, +0.0111, -0.2663, +0.4862, +0.1918, -0.4241, +0.2587, -0.0027, -0.0372, +0.3184, +0.3913, +0.0524, -0.3319, -0.0694, +0.2023, -0.2400, +0.1287, -0.2312, -0.0678, -0.1319, +0.2564, +0.0159, -0.0392, +0.0918, +0.1219, -0.2442, +0.0310, -0.0213, -0.2321, +0.1482, +0.1481, -0.2212, -0.1167, -0.1511, +0.3179, +0.2984, -0.0132, -0.3760, +0.2300, -0.2227, +0.0670, -0.2268, +0.1566, +0.0284, +0.2196, -0.0754, -0.1894, -0.5378, -0.2590, +0.0665, -0.0787, -0.0238, +0.0843, +0.0179, +0.0325, +0.1260, +0.0748, +0.3066, +0.2551],
-[ +0.2968, -0.2520, +0.2843, -0.6742, +0.1921, +0.0292, -0.1531, -0.0155, -0.5983, -0.1721, -0.2882, -0.0314, +0.1263, -0.2607, -0.3498, +0.1108, +0.0609, -0.0140, -0.0950, -0.0512, -0.0920, +0.0698, -0.5251, +0.3910, +0.0909, +0.1045, -0.2000, -0.1434, -0.4206, -0.0071, +0.2461, +0.0603, -0.2128, +0.0181, +0.1641, +0.2612, +0.2315, -0.3620, +0.0315, -0.3138, +0.2062, -0.0888, -0.3100, -0.3093, +0.0671, +0.1117, +0.1244, -0.2791, +0.3243, +0.1450, -0.2218, +0.1180, +0.0675, -0.1432, +0.1664, -0.0586, +0.1428, -0.0584, +0.2146, -0.0220, +0.2256, -0.0408, -0.4546, -0.4819, +0.0717, +0.5182, +0.1655, -0.1134, +0.1405, +0.0945, -0.0972, -0.0684, -0.2629, +0.1064, -0.1235, +0.3470, -0.3405, -0.1843, +0.2565, +0.1616, +0.3482, +0.1659, +0.0035, -0.1445, +0.2763, -0.5614, +0.1946, +0.0868, +0.1259, +0.1728, +0.0006, -0.3359, -0.5973, +0.2830, +0.0261, +0.3082, +0.0400, -0.0577, -0.0499, -0.0597, -0.3174, +0.0512, -0.0551, +0.3253, -0.1913, -0.0550, -0.0718, -0.1346, -0.4629, +0.3681, -0.1247, +0.0814, -0.0478, -0.0722, -0.4642, +0.2460, +0.0200, -0.2498, +0.1885, +0.0868, -0.0035, +0.1116, +0.3947, -0.2608, +0.0356, -0.0511, +0.5914, +0.0289],
-[ -0.0472, +0.0291, -0.2015, -0.3400, -0.0293, +0.1229, -0.1336, +0.2527, +0.0665, +0.2563, +0.3501, -0.0805, +0.1462, -0.6395, -0.2547, -0.1008, -0.3647, +0.2239, -0.2914, -0.1160, -0.6349, +0.0306, -0.5290, -0.3486, +0.0615, -0.4155, -0.0256, -0.0700, +0.0291, +0.0889, -0.0647, +0.1953, +0.0807, +0.1264, -0.1552, +0.1852, +0.2415, +0.1817, +0.1409, +0.0679, -0.1280, -0.0297, +0.2072, -0.0792, -0.1122, -0.2793, -0.0724, -0.2612, +0.0395, +0.0733, -0.2032, +0.1459, -0.2105, +0.0847, -0.0401, +0.0033, -0.1316, +0.0334, -0.1861, -0.0395, -0.2530, -0.0225, -0.1109, -0.0984, +0.0103, -0.1257, -0.3871, -0.1836, +0.0309, +0.1372, -0.0636, -0.0293, +0.1551, -0.5412, +0.0332, -0.2848, -0.2884, -0.0788, -0.2465, -0.0299, -0.0706, -0.3344, -0.2211, -0.0945, +0.2794, +0.2708, -0.4605, -0.1758, +0.4140, -0.0400, -0.2299, -0.1933, +0.3417, -0.1830, +0.1497, -0.2801, +0.2764, +0.1630, -0.1395, -0.1100, -0.0719, -0.3203, -0.1424, -0.2747, +0.1537, -0.0182, +0.1668, -0.0978, +0.2400, -0.1709, -0.6090, +0.1737, +0.2128, -0.4995, +0.3784, -0.3555, -0.0216, +0.3171, +0.0818, +0.1288, +0.1428, -0.2269, -0.4011, -0.1041, -0.4746, -0.0047, +0.4549, -0.0321],
-[ -0.1855, +0.1624, +0.3269, -0.0836, +0.0791, +0.2012, -0.1678, -0.2719, -0.0091, -0.0395, -0.1173, +0.2669, -0.1938, +0.2195, -0.0345, -0.1397, -0.7391, -0.0199, -0.2329, -0.1489, +0.0571, +0.2921, -0.1523, +0.1569, -0.2668, -0.5009, -0.2381, +0.0651, -0.3336, -0.2194, -0.3238, -0.5012, +0.1450, +0.1525, -0.0115, -0.5428, +0.3294, +0.2525, -0.3526, -0.4212, -0.1837, +0.2515, +0.4614, -0.1264, -0.3103, +0.1074, +0.0827, -0.1964, +0.2053, +0.2600, +0.0388, -0.2054, +0.1345, +0.0519, -0.1489, +0.6301, -0.9479, +0.2510, -0.0498, -0.0527, +0.2920, -0.0529, -0.1293, +0.2472, +0.1368, -0.0785, -0.6581, +0.2106, -0.2905, -0.3379, +0.3484, +0.1134, -0.1174, +0.2157, -0.2320, +0.1710, +0.4458, +0.2454, -0.0388, +0.3026, -0.1289, -0.3110, +0.1891, +0.1288, +0.1204, +0.0897, +0.2136, -0.0600, +0.0676, +0.0901, +0.4644, -0.3749, +0.3909, -0.0519, +0.2061, -0.1888, -0.0771, +0.0332, -0.0471, -0.1393, +0.0479, +0.0953, -0.2018, -0.0382, +0.5181, +0.5044, -0.2500, +0.3214, +0.3163, +0.1999, -0.0691, +0.1075, +0.1390, -0.1640, -0.1320, -0.0301, +0.3794, +0.3905, +0.0873, +0.1993, -0.0542, +0.0399, -0.2078, -1.0854, +0.1759, +0.1768, -0.0782, -0.6677],
-[ +0.4761, -0.0663, +0.2249, +0.4687, +0.4725, +0.2613, +0.1594, +0.1505, +0.4235, +0.6645, -0.2783, -0.0612, -0.1099, -0.1565, -0.2852, -0.1671, -0.3037, +0.0379, -0.3604, -0.1752, +0.2092, -0.2202, +0.0912, +0.0729, -0.3226, +0.2457, +0.3629, -0.1730, +0.1914, -0.3294, -0.2261, +0.2895, +0.1302, -0.1379, -0.4952, -0.1735, +0.1255, +0.1457, -0.2376, +0.4720, -0.1775, -0.2509, -0.0624, -0.3632, -0.1322, -0.2055, +0.2150, -0.0768, -0.2688, +0.0285, +0.2131, -0.0390, -0.1769, +0.0622, -0.5151, -0.2979, -0.1739, -0.0890, -0.5254, -0.1478, +0.1088, +0.0856, +0.1429, -0.1501, -0.1204, +0.0028, +0.1770, +0.1505, +0.1766, -0.2425, +0.0513, +0.1667, -0.1476, +0.0032, +0.2798, +0.2076, -0.2384, -0.2674, -0.0056, -0.3287, +0.1107, -0.2459, +0.3851, +0.1876, -0.7106, +0.1685, -0.0777, -0.0396, +0.0233, -0.3481, -0.0286, +0.0261, +0.2921, +0.1093, +0.5630, -0.2347, -0.0734, +0.0249, -0.1631, -0.1040, -0.1983, +0.0782, +0.0169, -0.0628, +0.3248, -0.1194, -0.0962, +0.0759, +0.0300, +0.2348, -0.1425, +0.2524, -0.0761, +0.3306, -0.3798, +0.4838, -0.1037, -0.2962, +0.1173, +0.1771, -0.0053, -0.0782, +0.2047, -0.4244, -0.5660, -0.2483, -0.0742, +0.1371],
-[ -0.7837, +0.3095, -0.1549, +0.4699, +0.2115, -0.0081, +0.0906, -0.5313, +0.0900, +0.1685, -0.0934, +0.2521, +0.0657, +0.0308, +0.3482, +0.2503, -0.2744, -0.3240, -0.0740, +0.1500, -0.2711, -0.8182, +0.1058, -0.6611, +0.1644, +0.2737, -0.1406, +0.3843, +0.1629, -0.2753, +0.1177, -0.0826, +0.0228, -0.3950, +0.0955, +0.1949, -0.0512, -0.4978, +0.6406, +0.4895, -0.0706, +0.0241, +0.0077, +0.2287, -0.2623, -0.0209, -0.4220, +0.0309, -0.4720, +0.0209, -0.1377, +0.0795, -0.1714, +0.3406, +0.0194, +0.2401, +0.0310, -0.1351, -0.3521, +0.0880, +0.0080, -0.0377, +0.0105, +0.0208, +0.4825, +0.2324, -0.2039, -0.1672, +0.1403, -0.2034, -0.1150, -0.3834, +0.2307, -0.2626, +0.3508, +0.0194, +0.0509, +0.0261, -0.0052, +0.3438, +0.3812, -0.3947, +0.1851, -0.2038, +0.2409, +0.0487, +0.1921, -0.0589, -0.0823, -0.1547, -0.0094, +0.2807, -0.1863, +0.2581, -0.5180, +0.2735, +0.0679, -0.0425, +0.2492, +0.0626, -0.2417, +0.1224, -0.4576, +0.0019, -0.2846, +0.1742, +0.0963, +0.0151, +0.0683, -0.0064, -0.2868, -0.5366, +0.2815, -0.4247, -0.0912, -0.3046, +0.2440, -0.1965, +0.3091, -0.0060, -0.2051, -0.1130, -0.5411, -0.0762, -0.1445, -0.1454, +0.5050, +0.1822],
-[ +0.3144, +0.3819, +0.2419, +0.0922, +0.0429, -0.3290, +0.1856, +0.4736, -0.1334, -0.0262, +0.3854, +0.4328, -0.3297, +0.0124, +0.3946, -0.2004, -0.1335, -0.3736, -0.0125, +0.2646, +0.0420, +0.1566, +0.4801, +0.1118, +0.2162, +0.1331, +0.3887, +0.0611, +0.0682, -0.1750, +0.0144, -0.5737, +0.2758, +0.5027, -0.1053, +0.0747, +0.2747, -0.5884, +0.1063, +0.1297, +0.2853, -0.2151, +0.0384, +0.1121, +0.1156, -0.3261, -0.2196, -0.2840, +0.2635, -0.2653, +0.2610, +0.3597, +0.2027, +0.3429, +0.1128, +0.2219, +0.0890, -0.9434, -0.4802, +0.0291, +0.1028, -0.2123, -0.7981, -0.0337, +0.1043, -0.1856, -0.1165, -0.7604, +0.4207, +0.1316, -0.1630, -0.1340, +0.2341, +0.0638, +0.0082, +0.4444, -0.0889, +0.2510, -0.1293, +0.1636, +0.1292, +0.1792, +0.5046, +0.3834, +0.3265, -0.2243, -0.0312, +0.5578, +0.0375, +0.1042, +0.6282, +0.2495, +0.0827, -0.0625, -0.3792, +0.2411, -0.3971, +0.1935, -0.0277, +0.0583, +0.0248, +0.0072, -0.0745, +0.1451, +0.4696, -0.2705, -0.3263, -0.1435, +0.0060, +0.2168, +0.0691, +0.1550, -0.0545, -0.4145, -0.1294, -0.1860, +0.0599, +0.0933, +0.3489, -0.0588, -0.6730, -0.0014, -0.1882, -0.0109, +0.3134, +0.0732, +0.2342, -0.0701],
-[ -0.4699, +0.1514, -0.0154, -0.3478, +0.0343, -0.0497, -0.0152, +0.0470, -0.2834, +0.2245, +0.2150, +0.2684, +0.1975, +0.1795, +0.0021, -0.1774, -0.2690, -0.1259, +0.0359, +0.2673, +0.2466, -0.6775, +0.1818, -0.2542, -0.0860, +0.0557, -0.0839, +0.1314, +0.4670, +0.0573, -0.4284, +0.0683, +0.0504, -0.2500, +0.0094, +0.1884, -0.0390, +0.0074, +0.1370, +0.1728, -0.1499, +0.2658, +0.1145, +0.4719, -0.0818, -0.0320, -0.4460, +0.0367, +0.0119, -0.2110, +0.2144, -0.3712, +0.0372, -0.3181, +0.0912, +0.4061, -0.3131, -0.1783, +0.2388, -0.1973, +0.4523, -0.2634, +0.1795, -0.4581, +0.1947, -0.0949, +0.3675, -0.1383, -0.1664, +0.0202, +0.1948, +0.2591, +0.2297, -0.0015, +0.0871, +0.0261, +0.4011, -0.1088, +0.0393, +0.4041, +0.0308, +0.0876, +0.2043, -0.2669, -0.0601, -0.4393, +0.3183, -0.3609, -0.0744, -0.2842, -0.1721, -0.3318, -0.4258, +0.1342, -0.0367, +0.1849, -0.0477, -0.0253, -0.0246, +0.5795, +0.2513, -0.1796, +0.0389, -0.2756, -0.2147, -0.1793, -0.3558, +0.1717, -0.5249, -0.2464, -0.2796, +0.0084, -0.4634, -0.4674, +0.0974, -0.6623, -0.1960, -0.3836, +0.3861, +0.0189, +0.0154, +0.0476, -0.2305, +0.5758, +0.2525, -0.0329, +0.1363, +0.0140],
-[ +0.1584, -0.2431, -0.4291, -0.0556, -0.0026, -0.0591, +0.0079, +0.2857, +0.5122, -0.0429, +0.0946, -0.0176, -0.1437, -0.4700, -0.1170, -0.0089, -0.9586, +0.0163, -0.1208, -0.0524, -0.5580, -0.0817, +0.2039, +0.0742, +0.1551, +0.1373, +0.2931, +0.1389, +0.0872, +0.4183, +0.2291, -0.1455, -0.0433, +0.0148, -0.0700, -0.1430, +0.2038, +0.0410, +0.2482, +0.0350, -0.1243, +0.4496, -0.4407, -0.0929, -0.2963, +0.0717, -0.4156, +0.1121, -0.1748, -0.1919, +0.0048, +0.2755, +0.0206, +0.1184, -0.0737, -0.0412, +0.2178, +0.2808, +0.1509, +0.1811, +0.4659, -0.1062, +0.1664, -0.2212, -0.0014, -0.1563, -0.1154, +0.1744, +0.3064, -0.1688, +0.1446, -0.0575, -0.0905, -0.3147, -0.0151, +0.0908, -0.2138, -0.0062, -0.4875, +0.1172, -0.4038, -0.0998, -0.4557, -0.2347, -0.2588, +0.4226, -0.0394, -0.3219, -0.1141, -0.0317, +0.4031, -0.0246, -0.1727, +0.3119, -0.0216, -0.0531, -0.5102, +0.3536, -0.0753, -0.0344, -0.0014, +0.1370, +0.2231, -0.1346, +0.1867, +0.0349, +0.5278, -0.1242, +0.2596, +0.0785, -0.0118, -0.5340, -0.2786, +0.3199, +0.5706, -0.0367, -0.1211, +0.1921, -0.0304, -0.0165, -0.7356, -0.0265, -0.0345, -0.0259, -0.1789, +0.2872, +0.0105, +0.0023],
-[ -0.0948, -0.6136, +0.1338, +0.2859, +0.2843, +0.1589, +0.3171, +0.1116, +0.0251, -0.3971, +0.1193, -0.0195, +0.1007, -0.0852, -0.4118, -0.6561, +0.1210, -0.3247, -0.1158, +0.2462, +0.0070, +0.7074, -0.1219, +0.3642, -0.1473, +0.0770, -0.2086, +0.0595, +0.2505, +0.1809, -0.2073, -0.2064, -0.0406, -0.1938, +0.5908, +0.2508, +0.0160, -0.3687, -0.1630, -0.0886, -0.1468, +0.1621, -0.3309, +0.0106, -0.1562, -0.3625, -0.1486, +0.0956, -0.1234, +0.2483, +0.1274, -0.0325, -0.5725, -0.1404, +0.2292, +0.1529, +0.1485, -0.6426, -0.1224, -0.7842, -0.6767, -0.2635, +0.2111, -0.1074, -0.0401, +0.2259, -0.2166, -0.0548, -0.5997, +0.1720, +0.3251, -0.3682, -0.5274, +0.3112, +0.1504, +0.1655, -0.1621, +0.3063, -0.0267, +0.0948, +0.1665, +0.0362, -0.2802, +0.1145, -0.2702, +0.1772, -0.0679, -0.0066, +0.1101, -0.3134, +0.0609, -0.3491, -0.3556, -0.0979, +0.1742, +0.1731, -0.1578, -0.1343, +0.2913, -0.2018, -0.0909, +0.1385, -0.2056, +0.3355, -0.1970, -0.5646, -0.1139, -0.2043, -0.2269, -0.0852, +0.0780, -0.4946, -0.0939, -0.1656, +0.1789, -0.1628, -0.1001, -0.1311, -0.2221, +0.1109, -0.0267, -0.1764, +0.0130, +0.1221, +0.0218, +0.1728, -0.1723, -0.0075],
-[ -0.2605, +0.0353, +0.2466, -0.1899, +0.3099, -0.1404, -0.0830, -0.3665, -0.0910, -0.2279, -0.2234, +0.0620, -0.0908, +0.1768, -0.2442, -0.0961, +0.4299, +0.5436, -0.0917, +0.1503, -0.4064, -0.1430, +0.3162, -0.1345, -0.2937, -0.2846, -0.0193, -0.4533, -0.2261, -0.1222, -0.1129, -0.3290, -0.7750, -0.7098, -0.2727, -0.4024, -0.3958, -0.1634, +0.2665, +0.2756, +0.3278, +0.1937, +0.1005, +0.0523, -0.4366, -0.4162, -0.4772, -0.6068, +0.1382, -0.2529, +0.1909, +0.2588, -0.1264, -0.1671, +0.1244, -0.2088, -0.2605, -0.2164, -0.1077, +0.2208, -0.2664, -0.1563, -0.1458, +0.2787, -0.2938, +0.0286, -0.2725, -0.2118, -0.8733, -0.0993, +0.0586, -0.1400, -0.0703, -0.4281, -0.1749, +0.0300, +0.0037, +0.1338, -0.1955, -0.0700, +0.1824, -0.0540, -0.5073, +0.0921, -0.2120, -0.2902, +0.0384, +0.0185, -0.1626, -0.1056, -0.1276, -0.4195, -0.0912, +0.1371, -0.0623, -0.2995, -0.4663, +0.0512, -0.0026, -0.4283, -0.2461, -0.3679, -0.2999, -0.1748, +0.3672, -0.1192, -0.3204, -0.4311, -0.5912, +0.2561, -0.1581, +0.1043, +0.0342, +0.1055, +0.3497, -0.0382, -0.2530, +0.1865, -0.1179, -0.0760, +0.1321, -0.0716, -0.0144, -0.8554, -0.3417, -0.1275, -0.6589, -0.4030],
-[ -0.1494, +0.2796, +0.6247, -0.1217, -0.5509, +0.1932, -0.3013, +0.2302, -0.2809, +0.4553, +0.8404, +0.6199, +0.1385, +0.0331, +0.0042, -0.3285, +0.7295, -0.0294, -0.2949, +0.2366, -0.1214, -0.2502, +0.1027, -0.1812, +0.0601, +0.0918, +0.0842, -0.2180, +0.1772, +0.1091, +0.0319, +0.1944, +0.3898, +0.0086, -0.0401, +0.3614, +0.1588, -0.0477, +0.0817, -0.2710, +0.1184, +0.3287, +0.0520, +0.0873, -0.0546, +0.2455, -0.3417, +0.1815, +0.1621, +0.4219, +0.2716, -0.2428, -0.1344, -0.1576, -0.0302, +0.5591, -0.0856, +0.0391, -0.0706, +0.1696, -0.1670, +0.2060, -0.1463, -0.2110, +0.0190, -0.2716, -0.0083, -0.0410, +0.3671, +0.0815, +0.0396, +0.0587, -0.5697, -0.2391, -0.0851, -0.2115, -0.3303, -0.2223, +0.0156, -0.0134, +0.1195, -0.3392, +0.3763, +0.2745, +0.2823, -0.1685, -0.2651, -0.5157, +0.0531, +0.2002, -0.1954, -0.5074, +0.0382, -0.2447, +0.2179, -0.0397, -0.1100, -0.1513, -0.5015, +0.1645, -0.1978, -0.1060, +0.1523, -0.0885, +0.5535, +0.1233, -0.0542, -0.1614, +0.0226, -0.3105, +0.2335, +0.1445, +0.2908, +0.3610, -0.1125, +0.1442, -0.5119, -0.4982, -0.0518, -0.0982, +0.0628, -0.2149, +0.1120, -0.3184, +0.0706, +0.2166, -0.0593, +0.2342],
-[ -0.4702, +0.2855, +0.2377, +0.4376, +0.3679, -0.3997, -0.6166, -0.3178, -0.2796, +0.2986, +0.2720, -0.4592, +0.0554, -0.1440, +0.0894, +0.1256, +0.1074, -0.0987, +0.0614, -0.0554, +0.1557, +0.2701, +0.2058, -0.3176, -0.1309, +0.1015, +0.3681, -0.0635, -0.3277, -0.4017, +0.1520, +0.0121, +0.0391, +0.4677, -0.3155, +0.2477, -0.0688, -0.0943, -0.1454, -0.1356, -0.0908, -0.0301, -0.0320, -0.0458, +0.2653, +0.0690, -0.2753, -0.1739, +0.1913, -0.1664, -0.1362, +0.1426, -0.0177, -0.6053, -0.0134, +0.0343, +0.4409, -0.1975, -0.1725, +0.3437, -0.0083, +0.1510, -0.3973, -0.3923, +0.1405, -0.4148, +0.0643, +0.0743, +0.0900, -0.0314, +0.3553, -0.2868, -0.5054, -0.4221, -0.2862, +0.3371, +0.0124, -0.3379, -0.3411, +0.0120, -0.4792, +0.0782, +0.0266, -0.2176, -0.1019, -0.1444, +0.2339, +0.2821, -0.1225, -0.6002, -0.1393, +0.0344, +0.0794, -0.1954, +0.1310, -0.1781, +0.1504, -0.5873, +0.0662, +0.2200, -0.3643, +0.1428, +0.1181, +0.2227, +0.0351, +0.3137, -0.0639, +0.2621, +0.0867, -0.4185, +0.4271, -0.2175, +0.3637, +0.0762, +0.3777, +0.0536, -0.4615, +0.1710, -0.1355, -0.2227, -0.2198, +0.4569, +0.2799, +0.1827, +0.0663, -0.2756, -0.2490, +0.0575],
-[ -0.3158, -0.2890, -0.4563, +0.2022, +0.2738, -0.0046, +0.1538, +0.1298, +0.0805, -0.3854, +0.2968, -0.0891, +0.1086, -0.1544, -0.1091, -0.0038, +0.2394, +0.1428, +0.1451, +0.1642, +0.0884, +0.1361, +0.3659, +0.0653, -0.3340, -0.1729, -0.2188, -0.1349, -0.6069, +0.2593, +0.2640, +0.1862, -0.0958, -0.3917, +0.0204, -0.0919, -0.3527, +0.1264, +0.2719, -0.1150, -0.0379, -0.1760, +0.1280, +0.1394, -0.2072, +0.1258, +0.0038, +0.2749, -0.1239, -0.2301, -0.2318, -0.1367, +0.1408, -0.4113, -0.1182, +0.2907, -0.2517, +0.4406, -0.5794, +0.5441, +0.0836, +0.3771, -0.3604, -0.1408, +0.1624, +0.0721, -0.0188, -0.0591, +0.1975, +0.2387, +0.1724, -0.1423, -0.2921, +0.1689, -0.0011, +0.1190, +0.3210, -0.2240, -0.2403, +0.0686, +0.2049, +0.2141, +0.1355, -0.0492, +0.3084, +0.2674, +0.2580, -0.0334, -0.0380, +0.0609, +0.0727, -0.0208, -0.3951, -0.0971, -0.0746, +0.1689, -0.2867, -0.0426, -0.0759, +0.0607, -0.0946, -0.1379, +0.1288, +0.2070, +0.1780, +0.0318, +0.0791, +0.2944, +0.1643, -0.1279, +0.1636, -0.2282, +0.3231, +0.1229, +0.0527, -0.0999, +0.4245, -0.1590, -0.1847, -0.2990, +0.0007, -0.4040, +0.2940, -0.1194, -0.1485, +0.1357, -0.0388, +0.1547],
-[ +0.2944, -0.0848, +0.2579, -0.0769, +0.0367, -0.1508, -0.0799, +0.1506, -0.5360, -0.5105, -0.2680, +0.3761, -0.0984, -0.1279, -0.0854, -0.4862, -0.1900, +0.0773, +0.2905, -0.3772, +0.0393, +0.0788, +0.3949, -0.0481, -0.0241, +0.0634, -0.1031, +0.3015, +0.0363, -0.2645, +0.1064, +0.0839, -0.1983, -0.0033, +0.0028, -0.2902, +0.0515, +0.5166, -0.1934, +0.5010, -0.1492, +0.0573, -0.5875, +0.2650, -0.0200, +0.0005, -0.1724, +0.2043, +0.1789, +0.3558, +0.3493, -0.5738, +0.0967, -0.2975, -0.1559, -0.3763, +0.1093, -0.2211, -0.6357, -0.3903, -0.2948, -0.0557, -0.1826, +0.2398, -0.1994, -0.1868, +0.1089, -0.1865, -0.3610, -0.0968, +0.4419, -0.3118, -0.2249, +0.0200, -0.0137, +0.0620, -0.0263, -0.0354, -0.3181, +0.0951, -0.1742, +0.0410, +0.0277, +0.2432, -0.1072, -0.8202, +0.1892, +0.0147, +0.0294, -0.0535, -0.1385, +0.2784, +0.1882, -0.1426, -0.3074, +0.1407, -0.1039, -0.1103, +0.3239, -0.4395, -0.1791, -0.7191, -0.3185, +0.2656, +0.1225, -0.6429, -0.0387, +0.1237, +0.1838, +0.0711, +0.2533, -0.1331, -0.1134, -0.2910, +0.2044, -0.0388, +0.0626, +0.1412, +0.1137, +0.2226, -0.2584, -0.0146, +0.2596, +0.1135, +0.0691, +0.3466, +0.2905, -0.0696],
-[ -0.1760, -0.1217, -0.3795, -0.2323, -0.3084, -0.3339, +0.0679, -0.2687, -0.1492, -0.0599, -0.1726, -0.3135, -0.3037, +0.1118, +0.2548, +0.3155, +0.1431, -0.2431, -0.1661, -0.0699, -0.9992, +0.2107, +0.3735, -0.2927, -0.1955, -0.3139, -0.2026, +0.1920, -0.6132, -0.4711, -0.0742, +0.1080, -0.0416, +0.0951, +0.1098, -0.2020, +0.1225, -0.0162, -0.0274, -0.1246, +0.2805, +0.1266, -0.0951, +0.0442, -0.2731, +0.0854, +0.1064, +0.3674, +0.1202, -0.1633, -0.2323, +0.0118, +0.1668, +0.2000, -0.0074, -0.2767, +0.2407, +0.2778, +0.0913, -0.4847, -0.2661, +0.0978, -0.0287, -0.2928, +0.2952, +0.2562, +0.3024, -0.1540, -0.1158, +0.0737, +0.1926, -0.2975, -0.0198, -0.1989, +0.5044, +0.2622, -0.2509, -0.0482, -0.3922, -0.2320, +0.2627, -0.5306, +0.1435, -0.1229, +0.0975, -0.2044, +0.3711, +0.5703, -0.2517, +0.2023, -0.1297, -0.0668, +0.2527, -0.3172, -0.0962, +0.2348, -0.0926, -0.1353, -0.2692, -0.0836, -0.1542, -0.6537, -0.3239, -0.0091, +0.0764, +0.1303, -0.1943, +0.1143, -0.0766, +0.2083, +0.2246, +0.1451, +0.0498, +0.5236, -0.1377, +0.1596, +0.2191, -0.0597, -0.0479, -0.1694, -0.0409, +0.2463, -0.0010, +0.1896, -0.2039, -0.0561, +0.1272, +0.0267],
-[ +0.0824, +0.2985, -0.1818, +0.0165, +0.0263, -0.5175, +0.2023, -0.1214, -0.0877, -0.0604, -0.3464, -0.0074, -0.4014, -0.4151, -0.3583, +0.2385, +0.2991, -0.0496, -0.0716, +0.3102, +0.4009, -0.2886, +0.1585, +0.3956, +0.1316, -0.1330, +0.0819, -0.8692, +0.0305, -0.0919, +0.1576, -0.1164, -0.1979, +0.1581, -0.4819, -0.3179, +0.0952, +0.0742, -0.0756, -0.1220, +0.2545, +0.1710, +0.2293, +0.1042, -0.1671, +0.2841, +0.2452, -0.0069, -0.1438, +0.2662, +0.2906, -0.5143, +0.0832, +0.0869, +0.0342, +0.1816, +0.1987, +0.1581, -0.2079, -0.2572, -0.0307, +0.0320, +0.0527, +0.0727, -0.1465, +0.1661, +0.3956, +0.2894, +0.3917, -0.3396, +0.1105, -0.1391, +0.0012, +0.0047, +0.1477, -0.0037, +0.0068, -0.0856, -0.0221, -0.0400, +0.0016, -0.2696, -0.0206, +0.3180, +0.0199, -0.4817, +0.2159, -0.1470, -0.0328, -0.2933, -0.2309, -0.0132, -0.5960, +0.1896, -0.3994, +0.1314, -0.0203, +0.1437, +0.0735, -0.4605, -0.3787, +0.1167, -0.1250, +0.4293, +0.1606, +0.0700, +0.1333, +0.1119, +0.1243, +0.5194, -0.2171, +0.2917, -0.0548, +0.0077, -0.0448, +0.2492, +0.0562, +0.0089, -0.1307, +0.1116, +0.2347, +0.0543, -0.3370, +0.1276, +0.3027, +0.3021, -0.0860, -0.0131],
-[ +0.2947, +0.4664, -0.1349, +0.1488, +0.4577, +0.0345, +0.1262, -0.1107, -0.0102, +0.3115, -0.2085, -0.0483, -0.0688, -0.2319, +0.3405, -0.1426, +0.0672, -0.0733, +0.1650, -0.0575, +0.0016, -0.3747, -0.1244, +0.0266, +0.5940, -0.2003, -0.4178, -0.0582, -0.2234, +0.0603, +0.3361, +0.2174, -0.3606, -0.3432, +0.0885, +0.0415, -0.0098, -0.0425, -0.6034, -0.2420, -0.1222, +0.0111, +0.0947, +0.2406, -0.0548, +0.3810, +0.3556, +0.0501, -0.3077, +0.0226, -0.0411, +0.0700, -0.0193, +0.2049, +0.0679, -0.3123, -0.1020, +0.3252, +0.1818, +0.0001, +0.1062, -0.1898, +0.2527, -0.1705, -0.0496, +0.1033, +0.2974, +0.3670, -0.3341, +0.4862, -0.0519, -0.3752, +0.1897, +0.3296, +0.0165, -0.0893, -0.2605, +0.3128, +0.3071, -0.0489, +0.0398, -0.0809, +0.1974, -0.0703, -0.3026, +0.0867, +0.0182, +0.0037, +0.0997, -0.2375, -0.2754, +0.2210, +0.0194, +0.1234, -0.4653, +0.3221, -0.2906, +0.0797, +0.1010, +0.2052, -0.1877, +0.3158, -0.0343, +0.0848, -0.0680, -0.0419, -0.3498, -0.0545, -0.3220, +0.1888, -0.4147, +0.1408, -0.0431, +0.1205, +0.1096, -0.1536, +0.3244, -0.2722, +0.2300, +0.2949, +0.1560, -0.3925, -0.2552, +0.0259, -0.1633, -0.1839, -0.0563, +0.1257],
-[ +0.2148, +0.0047, -0.5010, -0.1166, +0.0344, -0.2950, -0.0669, +0.2197, +0.0749, +0.2859, -0.0708, +0.3323, +0.4038, -0.1302, +0.0795, +0.3921, -0.0013, -0.2661, -0.2596, -0.1604, -0.1498, +0.0585, +0.4799, -0.1394, -0.2289, +0.2356, -0.3931, -0.2290, -0.0818, +0.2484, +0.1705, -0.3872, -0.0328, +0.0271, -0.0874, -0.0768, -0.7135, +0.0105, +0.1771, -0.2271, -0.0836, -0.1756, +0.0977, -0.0529, -0.0650, +0.0444, -0.2159, +0.3083, +0.2212, +0.0188, -0.0080, -0.1380, +0.1597, +0.2834, +0.1947, +0.1630, -0.2205, +0.0559, -0.2156, -0.2409, +0.0107, -0.2687, +0.1016, -0.2704, +0.3349, +0.2165, -0.1543, +0.0014, -0.0324, +0.3259, -0.0701, +0.1057, -0.0211, -0.1465, +0.4340, -0.1941, +0.0097, -0.1941, -0.2310, +0.1882, +0.0257, +0.3041, -0.5347, +0.1756, +0.2526, +0.2409, +0.3229, +0.1697, +0.6469, +0.1586, -0.4125, +0.2139, -0.5680, -0.1800, +0.1256, -0.0353, +0.4003, +0.0268, +0.0944, -0.1399, +0.1552, +0.0373, -0.1222, +0.0031, +0.2078, +0.3396, -0.2205, +0.2581, -0.5238, -0.4429, -0.0474, -0.5244, -0.4636, +0.2577, -0.0144, -0.0862, +0.2369, +0.3335, -0.3155, +0.0177, -0.3951, +0.2018, +0.0872, -0.0961, -0.2180, -0.0140, +0.4505, -0.1433],
-[ -0.1068, -0.0263, -0.1388, -0.1157, -0.1234, +0.0694, -0.0963, +0.3236, -0.0838, -0.4470, +0.1331, +0.2199, +0.0891, +0.4354, -0.3252, -0.0962, -0.1358, +0.1375, -0.3047, -0.3211, -0.1624, +0.2874, -0.3383, -0.2534, -0.0498, +0.1309, -0.0004, -0.4051, -0.1960, -0.3383, -0.2622, -0.2444, -0.2500, +0.0469, -0.4247, -0.0853, -0.1119, -0.1316, +0.0171, -0.0362, +0.0522, -0.2861, +0.0766, +0.0506, -0.1964, -0.0899, +0.2697, -0.3270, +0.5962, -0.2216, +0.1118, +0.1582, -0.3296, +0.0793, +0.2890, -0.4065, +0.0924, -0.0746, +0.2517, +0.2001, -0.0501, -0.1863, +0.1175, -0.2080, +0.0020, -0.0169, -0.1251, -0.0714, +0.3016, -0.1755, +0.2065, +0.1221, +0.0706, +0.2269, -0.2703, -0.3755, +0.0792, -0.2415, +0.1048, -0.3250, +0.2936, -0.4018, -0.1319, -0.3685, +0.0964, +0.2001, -0.0373, +0.1277, -0.0891, -0.4724, +0.0329, +0.3696, +0.1104, -0.1315, -0.1854, -0.0938, -0.3303, -0.0011, +0.3145, -0.5522, +0.1904, -0.2422, +0.1405, -0.1609, +0.1170, +0.1209, +0.2885, +0.1152, +0.1770, -0.0836, -0.3173, -0.1085, -0.1493, +0.0094, +0.2494, +0.0030, +0.0778, +0.1527, -0.1594, -0.1341, -0.0434, +0.1502, -0.2476, -0.2058, +0.2545, +0.2769, +0.1098, -0.0083],
-[ +0.2106, -0.1300, +0.0485, -0.7346, +0.0840, -0.0914, +0.1989, +0.4280, +0.4626, +0.3009, -0.0244, +0.0138, -0.0378, -0.0385, -0.1281, -0.3317, -0.2086, -0.2537, -0.2534, -0.6887, +0.0834, -0.2205, +0.3126, -0.3583, +0.2112, +0.0573, +0.1206, +0.1378, +0.1218, -0.4811, +0.1413, -0.2197, -0.0216, +0.0774, -0.2460, +0.2520, -0.3548, -0.3999, +0.2720, +0.0545, +0.3093, -0.7499, -0.2457, +0.3429, +0.2207, -0.3214, -0.2397, -0.0006, -0.3268, +0.0159, +0.1594, -0.0966, +0.2911, -0.1839, -0.1116, +0.0606, +0.0206, -0.0959, -0.3201, -0.1717, +0.0481, +0.1382, -0.1964, +0.4383, -0.1060, -0.3150, -0.1749, -0.7198, +0.5017, +0.3316, -0.4407, -0.4595, -0.4555, -0.3972, +0.3232, -0.4576, -0.0748, +0.0102, +0.2671, +0.2561, +0.1418, +0.2160, -0.0213, -0.2403, +0.1480, +0.3040, -0.0377, +0.3424, -0.2381, +0.0744, -0.4117, -0.0661, +0.2971, +0.5014, -0.9249, +0.0502, -0.3293, +0.1345, -0.4735, +0.1441, +0.0026, -0.0259, -0.9353, -0.5167, +0.1392, -0.3059, -0.1233, -0.2771, +0.2003, +0.3982, +0.0078, +0.1673, -0.4770, -0.4842, -0.2908, +0.0975, -0.0728, +0.3615, +0.1398, +0.0180, +0.3402, +0.1516, -0.0569, -0.0071, +0.1601, -0.0516, +0.2392, -0.5066],
-[ -0.8802, +0.1699, +0.1054, +0.0240, +0.1706, +0.1335, -0.1155, -0.3890, +0.0630, -0.1447, +0.3381, -0.1320, +0.1034, +0.2878, -0.0441, -0.1470, +0.3491, +0.3904, -0.1225, -0.1650, -0.1266, -0.1012, +0.3379, -0.3566, -0.3020, -0.5177, +0.0250, +0.1512, +0.2122, -0.3095, -0.0402, -0.2094, +0.3877, -0.1007, -0.0152, -0.1819, +0.0907, +0.2006, -0.0020, -0.1510, +0.1542, +0.0429, -0.3614, +0.0143, +0.0544, -0.0749, -0.0547, +0.2007, +0.0829, -0.2418, +0.2694, -0.1332, -0.0991, -0.1609, +0.2025, -0.4393, +0.0703, +0.1062, +0.2181, -0.1352, -0.3935, +0.4110, -0.0509, +0.0621, +0.2605, -0.0382, +0.3192, -0.1091, +0.0318, -0.1395, -0.1186, +0.1220, +0.2714, -0.0848, -0.0499, +0.0187, -0.1677, -0.2008, -0.0645, -0.2873, -0.0607, -0.1093, -0.0814, -0.1771, -0.2174, +0.3143, +0.0269, -0.5732, -0.0363, -0.1689, +0.1948, +0.0059, -0.0279, +0.2271, +0.1691, -0.0134, +0.0548, +0.0756, +0.0620, -0.3728, +0.3562, -0.5897, -0.3423, +0.0185, +0.0146, +0.2151, -0.3176, -0.2987, +0.0348, +0.0252, -0.1359, +0.1920, -0.2293, +0.2033, +0.0593, +0.0956, -0.3218, -0.0207, -0.2550, +0.1762, +0.0230, -0.0570, -0.0746, +0.1369, -0.0651, -0.2736, -0.0851, +0.0131],
-[ -0.8832, -0.1124, +0.3068, -0.2348, -0.0845, +0.1651, -0.0848, -0.3490, -0.3582, -0.8653, +0.1148, -0.5777, -0.0275, +0.1159, +0.3220, -0.4598, +0.2011, +0.0046, +0.2821, -0.2998, -0.1787, -0.1737, +0.3377, +0.0090, -0.4418, -0.1343, +0.0606, -0.3029, -0.3504, -0.3433, -0.3918, +0.1668, +0.2931, -0.2543, -0.0114, -0.3211, -0.3044, +0.1758, -0.3798, -0.2485, -0.1906, -0.2615, +0.1321, -0.2962, +0.1544, +0.2058, +0.3810, +0.3139, +0.0916, -0.0725, +0.2238, +0.2081, -0.4715, -0.0871, -0.0508, -0.3160, -0.0327, -0.0550, -0.1204, -0.9481, -0.1351, -0.1102, -0.0333, -0.0181, -0.1707, +0.0076, -0.0827, -0.2646, -0.2107, -0.4914, -0.1390, -0.0170, -0.4054, -0.0107, +0.2280, -0.0472, +0.4655, +0.2280, +0.3590, +0.0616, -0.3474, +0.1742, -0.1811, -0.1085, -0.3157, -0.6880, +0.0180, -0.0004, -0.2667, -0.0929, -0.0167, -0.1256, +0.0701, -0.3705, -0.4304, +0.3143, -0.2352, +0.1948, -0.0775, -0.0602, -0.1135, +0.1950, +0.0860, -0.2415, +0.1209, -0.5315, +0.2986, +0.0702, +0.0776, -0.2087, -0.1640, -0.5140, -0.1156, -0.3753, -0.3619, +0.1426, -0.0180, -0.4435, +0.3894, -0.0649, +0.0194, +0.2156, -0.0400, -0.0441, -0.3793, -0.2438, +0.1116, -0.2393],
-[ -0.0564, -0.2013, +0.3803, -0.1042, -0.0933, -0.0053, -0.3388, +0.2630, -0.4021, -0.2141, +0.0750, +0.3583, +0.0882, +0.2297, -0.0828, -0.3131, -0.1735, +0.3028, -0.7214, +0.0045, -0.1908, -0.0893, -0.3378, -0.3102, -0.0531, -0.4406, -0.3636, -0.3734, -0.3279, -0.0664, +0.0979, -0.2246, +0.0568, +0.0598, +0.1435, -0.2430, -0.4036, +0.2383, +0.2321, +0.3876, -0.0346, +0.0722, -0.2538, -0.2412, +0.0604, -0.1563, -0.4940, +0.2605, +0.2478, -0.2374, -0.2984, +0.0057, -0.2369, +0.1294, +0.0174, +0.5807, -0.0718, -0.3781, -0.3258, -0.5421, -0.0009, +0.0742, -0.0556, -0.0871, +0.0130, -0.4105, -0.8956, +0.1436, +0.1205, -0.0754, -0.1488, +0.2092, -0.7182, -0.0507, -0.0535, +0.3105, +0.1438, -0.2952, +0.0385, +0.0672, +0.0364, +0.0696, -0.1960, +0.2819, +0.0306, -0.0762, +0.3345, -0.1293, -0.1608, -0.1541, -0.0351, -0.4728, -0.3493, -1.1941, -0.1454, +0.3901, +0.1090, -0.1694, -0.2511, +0.1375, +0.0238, +0.1331, -0.0784, -0.3095, -0.3079, -0.4227, -0.2915, +0.0166, +0.1902, -0.0587, -0.2205, +0.1881, -0.3936, -0.1078, -0.2047, -0.0764, +0.3708, +0.3702, -0.1016, +0.0040, -0.1311, -0.3788, -0.2263, +0.3114, -0.3604, +0.0038, -0.1860, +0.1821],
-[ +0.3922, +0.0453, +0.5451, -0.2539, -0.3151, -0.0529, -0.0315, +0.0386, +0.3905, +0.0847, +0.0692, -0.1342, +0.2468, -0.0541, +0.3193, -0.0176, +0.0102, +0.1388, +0.1445, -0.2237, +0.1713, +0.1079, -0.1579, +0.1329, -0.3138, -0.0993, +0.2535, +0.2280, +0.1970, +0.5129, -0.3800, +0.4691, -0.4482, -0.0378, +0.3220, -0.0184, +0.0875, -0.1760, +0.5265, -0.2199, -0.1342, -0.3460, +0.1824, -0.3727, +0.2315, -0.0991, -0.1387, -0.1143, -0.0743, -0.1338, -0.0654, +0.3019, -0.1920, +0.0478, +0.0189, +0.1041, +0.5841, -0.2401, -0.4096, +0.2503, -0.0746, +0.0600, -0.0135, -0.0188, -0.4462, -0.0420, -0.0338, +0.0796, -0.0532, -0.1258, -0.1273, -0.1757, +0.1009, -0.0217, +0.0317, +0.2119, -0.4266, -0.2404, +0.2424, -0.3341, -0.0366, -0.5047, -0.5699, -0.0441, -0.0389, -0.0268, -0.5898, +0.0766, +0.0640, -0.0788, +0.0573, +0.1757, +0.1714, +0.3059, +0.0664, +0.2298, -0.0712, +0.0755, -0.1056, +0.2291, +0.1614, +0.3680, +0.0709, -0.0690, -0.0891, +0.0240, +0.2207, +0.1425, +0.7755, +0.1882, -0.6451, -0.0345, +0.1063, -0.0540, -0.0989, -0.5350, +0.1494, +0.2128, +0.1890, -0.1394, -0.0377, -0.2619, +0.4138, -0.1444, -0.4859, -0.2464, -0.3172, -0.1692],
-[ -0.0923, -0.4212, -0.2414, -0.4825, +0.2255, +0.2309, -0.4897, +0.0304, -0.0860, -0.1170, -0.1571, +0.1275, -0.1820, -0.3654, +0.0232, -0.3386, -0.5037, +0.1978, -0.0036, +0.0813, -0.1647, -0.8769, -0.3028, -0.3804, -0.7696, +0.0939, -0.1970, -0.0756, +0.2388, +0.4887, -0.2240, +0.0294, -0.4167, -0.3421, -0.2896, +0.0338, +0.3542, +0.1363, -0.0421, -0.3361, -0.3763, +0.5503, +0.1136, +0.0669, -0.3017, -0.1507, -0.6288, -0.5275, +0.4184, -0.4006, +0.2278, +0.0248, -0.2301, -0.3362, -0.1329, -0.3787, -0.0273, +0.3377, +0.1465, -0.0040, +0.3127, -0.1651, -0.0978, +0.4950, -0.1856, -0.2066, -0.0279, -0.0435, +0.3200, +0.2473, -0.0725, -0.0819, -0.2703, -0.3825, +0.1863, -0.0269, +0.2441, -0.1633, +0.0109, -0.1532, -0.1801, +0.3215, -0.0189, +0.3776, +0.2735, +0.2794, -0.3058, +0.2496, -0.2674, +0.2918, +0.3530, -0.2802, +0.1357, +0.2323, -0.2258, +0.3445, -0.3727, -0.1343, -0.2584, +0.3894, +0.3088, +0.4367, +0.4166, -0.3000, +0.3440, +0.1129, -0.5826, -0.0498, +0.1875, -0.3181, +0.2863, +0.0757, -0.1553, +0.0070, -0.0151, +0.5215, -0.0413, +0.0430, +0.2005, -0.0768, +0.4908, -0.1021, +0.0298, -0.4536, -0.3938, -0.7115, -0.3281, +0.0436],
-[ +0.1429, -0.7486, -0.0175, -0.1436, -0.0643, -0.1031, +0.3570, +0.4050, -0.0815, +0.0001, -0.1782, +0.0159, -0.0068, -0.4581, -0.0356, +0.0264, -0.3577, -0.1983, +0.0125, -0.6086, +0.1955, -0.7601, +0.2107, +0.1950, -0.2277, -0.2083, +0.3890, +0.0133, -0.2579, -0.2204, -0.2568, +0.3742, -0.4256, +0.2367, -0.0544, -0.0623, -0.0004, -0.1718, +0.3199, +0.0778, +0.1319, +0.1961, -0.2971, -0.0769, -0.0987, -0.3242, +0.3422, +0.2269, -0.2482, -0.0209, +0.1743, -0.4017, +0.1609, +0.3292, +0.0796, -0.3552, +0.1177, -0.6123, -0.8029, -0.4316, +0.0467, -0.1625, -0.0685, -0.1786, -0.1052, +0.0359, -0.8246, -0.1224, -0.2311, -0.1663, -0.4349, +0.5463, +0.3116, +0.0843, -0.0817, +0.4950, -0.2378, -0.3152, -0.5438, -0.2174, -0.0641, +0.2376, +0.1389, +0.1698, -0.3016, -0.0105, +0.0238, -0.0417, -0.0840, -0.1700, +0.0105, +0.1367, +0.2720, +0.6785, -0.3363, +0.1792, +0.0067, -0.3054, +0.1514, -0.0196, -0.1702, -0.0847, +0.0017, -0.2192, +0.0678, +0.1268, -0.4652, -0.3753, -0.0238, -0.5654, -0.0350, +0.3150, -0.3401, -0.2279, -0.3434, +0.0283, +0.0703, -0.2647, -0.2636, -0.1750, -0.5818, -0.2056, -0.0293, +0.4088, -0.5704, -0.1289, -0.2542, -0.1802],
-[ -0.2887, +0.3308, +0.1327, -0.5094, -0.0622, -0.2413, -0.3148, +0.0616, -0.1550, +0.2265, +0.3879, -0.1951, -0.6486, +0.0115, -0.2057, +0.3291, +0.1942, -0.2094, +0.3025, -0.0428, +0.0823, +0.4690, -0.7880, +0.6142, -0.6011, -0.1640, -0.2154, +0.5126, +0.0807, +0.3205, +0.1592, -0.1571, +0.2994, -0.3585, +0.2420, -0.1281, +0.1821, -0.1843, +0.1903, -0.3561, +0.5856, +0.0123, +0.0916, +0.3216, -0.2577, -0.5488, -0.3684, +0.2314, +0.0460, -0.0247, +0.0782, +0.3424, +0.0063, +0.2094, -0.3286, +0.3532, -0.1614, +0.2834, +0.1043, -0.4423, -0.0256, +0.0870, +0.4249, -0.3413, -0.2285, +0.1121, -0.0555, +0.0010, +0.1207, +0.2360, -0.0790, +0.1614, -0.0735, +0.0818, +0.2746, +0.2402, -0.7183, +0.1044, -0.4774, +0.4292, -0.2664, -0.0594, +0.2838, -0.4776, -0.0046, -0.6516, -0.0835, +0.1015, -0.1679, -0.2869, -0.3426, +0.2073, +0.3420, -0.2174, +0.3160, -0.0505, +0.2485, +0.1510, +0.2260, -0.4438, -1.1494, +0.0271, +0.4070, -0.0237, -0.2114, +0.2593, +0.2260, -0.1828, -0.0544, +0.3111, +0.0166, +0.0297, +0.3485, -0.0505, -0.3387, -0.0293, +0.1108, +0.0087, -0.2202, -0.0637, -0.0756, -0.2728, -0.0198, -0.1262, -0.3164, +0.3487, +0.3104, +0.3920],
-[ -0.2575, +0.1666, +0.3256, -0.1886, -0.2590, -0.1386, +0.3521, -0.3582, -0.2922, +0.2653, +0.2938, +0.0030, -0.3808, +0.1105, +0.0449, -0.2666, -0.1739, -0.2229, +0.0833, +0.3438, -0.7196, +0.0778, -0.0854, +0.1274, +0.3981, -0.0870, -0.1869, -0.0256, -0.0882, -0.0591, -0.2645, +0.3365, +0.1646, +0.2441, -0.3281, -0.1445, -0.2442, +0.1015, -0.0256, +0.2571, +0.1649, -0.0259, -0.0699, +0.1460, -0.1046, +0.2116, -0.1376, +0.0917, -0.0286, -0.0055, +0.0966, -0.0678, +0.0400, +0.1181, -0.0878, -0.1292, +0.0265, +0.0441, +0.0287, -0.0853, -0.1342, -0.0030, -0.2036, -0.0305, +0.0461, -0.1499, -0.1201, -0.0007, +0.0579, -0.0417, +0.0633, -0.2599, +0.1975, +0.0240, -0.1304, -0.0229, -0.2079, +0.0305, +0.5747, +0.0475, -0.5645, -0.2887, -0.5164, +0.0432, -0.3610, -0.2888, +0.1067, -0.0617, -0.4146, +0.3116, +0.2835, -0.0129, -0.4083, -0.0518, -0.0702, -0.2992, +0.3599, -0.0642, -1.2739, -0.1203, -0.5464, +0.1658, +0.3236, +0.0734, +0.4132, -0.0319, -0.2330, -0.3762, -0.1676, +0.0437, -0.0187, +0.3352, -0.1844, -0.3109, +0.1229, +0.1187, +0.3067, -0.1564, -0.1249, +0.2623, -0.2028, -0.2382, -0.0641, +0.0678, +0.2706, +0.2068, -0.0180, -0.3670],
-[ -0.0107, -0.0179, -0.3622, +0.0487, -0.2037, -0.2486, +0.4088, -0.4331, +0.1125, +0.3157, -0.0246, -0.1149, -0.2634, +0.5252, -0.0316, -0.0396, +0.0342, -0.3630, +0.1595, +0.2105, -0.0896, +0.1590, +0.2375, +0.0225, -0.1746, +0.1284, +0.2204, +0.3032, +0.3802, -0.3472, -0.2104, +0.0068, +0.2576, -0.0977, -0.3281, -0.1515, -0.0040, +0.1479, +0.1452, +0.2931, -0.4903, -0.0811, -0.0917, +0.0062, +0.2323, -0.8050, -0.1784, +0.4353, -0.0573, +0.4593, +0.1577, -0.3910, +0.0392, +0.0360, +0.4710, +0.2190, -0.1018, -0.4349, +0.0778, +0.4254, -0.6687, +0.0132, +0.0726, -0.0929, -0.2873, -0.0379, +0.3106, +0.1391, -0.0208, -0.0201, -0.4040, -0.0819, -0.1079, -0.1654, -0.6052, +0.3173, +0.3248, -0.1358, -0.4220, +0.0344, -0.0460, -0.1394, -0.2428, -0.1595, +0.2178, -0.1904, +0.2255, +0.0940, +0.0954, -0.4658, -0.3351, +0.4072, -0.0390, -0.0776, +0.3697, -0.0263, -0.0450, -0.1758, +0.1951, +0.1053, -0.2358, +0.1302, -0.4079, +0.2972, -0.0111, -0.5701, -0.1274, -0.2291, +0.1902, -0.1665, +0.0604, -0.4641, -0.6633, +0.2213, -0.7764, +0.0351, +0.3093, +0.0849, -0.4626, +0.0663, -0.1490, +0.5589, -0.3444, -0.1921, +0.2102, +0.4465, +0.2145, -0.4431],
-[ +0.2271, +0.0093, -0.0987, -0.3881, -0.0350, +0.0747, -0.0680, +0.1378, +0.3064, -0.2883, -0.3261, -0.0059, -0.1537, -0.1148, -0.2007, +0.0185, -0.1833, -0.2434, +0.0928, +0.2168, +0.1473, -0.6421, +0.1321, -0.0033, -0.1413, +0.1213, +0.3580, +0.4134, +0.6291, -0.1581, +0.2093, -0.0749, +0.1321, +0.0703, -0.1864, +0.2468, +0.1223, -0.0090, -0.5070, +0.0125, -0.4041, -0.0245, -0.1620, -0.1767, +0.0946, -0.0966, +0.2019, +0.0895, +0.0181, +0.3667, +0.3279, -0.1238, +0.2064, +0.1062, -0.4617, -0.5064, +0.1865, +0.0008, -0.6320, -0.0860, +0.0246, -0.1346, -0.0486, -0.1026, +0.1784, +0.2213, +0.0952, -0.2822, -0.4380, -0.4222, -0.2064, -0.1091, +0.0198, -0.2463, +0.4210, -0.2130, -0.0964, +0.2051, -0.2638, -0.4065, -0.2067, -0.0830, -0.1476, +0.0103, -0.1342, -0.4563, -0.1189, +0.3326, +0.3363, -0.1587, -0.1181, +0.1159, +0.2865, -0.0199, +0.4299, +0.2091, -0.0407, -0.2726, +0.2658, -0.0264, +0.2548, +0.4658, -0.5378, +0.1585, -0.2706, -0.2006, -0.0351, -0.2616, -0.5981, +0.1679, -0.0143, -0.0829, +0.2944, -0.0259, +0.0198, -0.0762, -0.0588, -0.0206, -0.3015, -0.2721, -0.0874, +0.4428, -0.1835, -0.4881, +0.1817, +0.6561, -0.2540, +0.0049],
-[ -0.1863, -0.3087, +0.1671, +0.3022, +0.1499, -0.1739, -0.1339, -0.8251, -0.4191, +0.1242, +0.0518, +0.2402, -0.4053, +0.3328, -0.3223, -0.1882, -0.0025, -0.1106, +0.0680, +0.3380, +0.0086, -0.2912, -0.0337, -0.5541, +0.4255, -0.0656, -0.0838, +0.0699, -0.0293, +0.2684, +0.2524, -0.2258, +0.1109, -0.0906, -0.5153, -0.0830, +0.4158, +0.1373, +0.2967, +0.1961, +0.4988, +0.2814, -0.3652, +0.0527, -0.0147, +0.2100, -0.0213, -0.2260, -0.0895, -0.2451, +0.0256, +0.0032, +0.2069, -0.0900, +0.0620, -0.4997, +0.3689, +0.4957, +0.7216, +0.0192, -0.0090, -0.0156, +0.1036, -0.2198, -0.1575, +0.0765, +0.0615, -0.3929, -0.4157, +0.2005, +0.0277, +0.1536, +0.3945, +0.1446, -0.2494, +0.0705, +0.1071, -0.1884, -0.9040, +0.2916, +0.1474, -0.3503, -0.0670, +0.0115, -0.3431, -0.2466, +0.0172, -0.3685, -0.2423, -0.3563, +0.0568, -0.2901, +0.3279, -0.0507, -0.3400, +0.0597, -0.7429, +0.1562, +0.1374, +0.1472, +0.2591, -0.1652, -0.3572, -0.2839, +0.3681, -0.3434, -0.0406, +0.6815, +0.4870, +0.0323, +0.0971, -0.3273, -0.5715, -0.6297, +0.0130, -0.2182, -0.2410, +0.0553, +0.0848, -0.1464, +0.1847, -0.1045, -0.0546, +0.4837, -0.1203, +0.2788, -0.4522, -0.3611],
-[ -0.2749, +0.1106, +0.1256, +0.2567, +0.3371, +0.0996, +0.0218, +0.2143, -0.0076, -0.0124, -0.3150, -0.3540, -0.3688, -0.0342, +0.0547, +0.0646, +0.0438, -0.0632, -0.0416, +0.1328, -0.4048, +0.2881, -0.1259, +0.2477, +0.1902, +0.2809, -0.0925, +0.1505, -0.0625, -0.0313, -0.0193, +0.1215, +0.0865, -0.0537, +0.2175, -0.2814, -0.3741, -0.1073, -0.2286, -0.1381, +0.0330, -0.4756, +0.5680, +0.0102, +0.2286, +0.1292, -0.2090, -0.1476, +0.0124, -0.1540, -0.0888, +0.1818, -0.0768, +0.2275, -0.3759, +0.2016, -0.2089, -0.0438, -0.3113, +0.0180, +0.1691, -0.0824, -0.1768, +0.3830, -0.2112, +0.5549, +0.2310, -0.1869, +0.2288, -0.0184, +0.1784, +0.1876, +0.0629, +0.1112, +0.0433, -0.2884, -0.3035, +0.2641, -0.0658, -0.2794, -0.0242, -0.0812, +0.0007, +0.1537, +0.0732, -0.0304, -0.0965, +0.1865, +0.1234, -0.0193, -0.2290, -0.0515, -0.3263, -0.4178, -0.0107, -0.0935, +0.1205, +0.4655, -0.3045, -0.3361, -0.1098, -0.1217, -0.1009, -0.1051, +0.2145, -0.3336, -0.0991, +0.1733, +0.1618, +0.3899, +0.0669, +0.1899, +0.2073, +0.2872, -0.1592, +0.5334, +0.3533, +0.1068, -0.3265, +0.0487, +0.1393, -0.2843, -0.5188, -0.2346, +0.1350, -0.2899, +0.1907, -0.3176],
-[ +0.2274, -0.6246, -0.0895, +0.0151, +0.2102, +0.1204, -0.0907, -0.2346, +0.1844, +0.0237, +0.1189, -0.0365, -0.1414, -0.5732, -0.1049, +0.1028, -0.1074, +0.2010, -0.1969, -0.4422, -0.3890, +0.5785, -0.1674, +0.1003, -0.0714, -0.1012, -0.4929, +0.1018, -0.2820, -0.1159, +0.1425, +0.3787, +0.0404, -0.1041, +0.3751, -0.0828, -0.0284, -0.0910, -0.0095, +0.2729, +0.1558, +0.3046, +0.1402, -0.4915, +0.4200, -0.4424, +0.3019, +0.0146, +0.0158, -0.2747, +0.2268, -0.3321, +0.0220, -0.4112, +0.2537, +0.2902, -0.5166, -0.0034, -0.1136, +0.2072, -0.4259, +0.0879, +0.2630, +0.3531, +0.1753, -0.0971, +0.0215, -0.3038, +0.0496, -0.0076, -0.0041, +0.4259, +0.0657, -0.5145, -0.2599, -0.4776, +0.3572, -0.0882, -0.5125, +0.3645, -0.2350, +0.3037, +0.0251, +0.0069, +0.1117, -0.1438, -0.3608, -0.0945, +0.0367, +0.3858, -0.1095, +0.2089, +0.0670, +0.0303, +0.3321, -0.0496, -0.0875, -0.2644, -0.3230, +0.2989, +0.2316, -0.2202, +0.1620, +0.0545, -0.0712, -0.3471, +0.2478, +0.4852, -0.5060, -0.4551, -0.0413, -0.0806, -0.1088, +0.1450, +0.3475, -0.2555, +0.4609, -0.2173, +0.0375, -0.2081, -0.3098, +0.0208, -0.0619, -0.3731, -0.6503, +0.4515, +0.2094, -0.0824],
-[ -0.5170, +0.1003, -0.2783, -0.6186, +0.2368, -0.0190, -0.1630, -0.1213, +0.1496, +0.0248, -0.1328, +0.0539, -0.0966, -0.0531, -0.2163, -0.1158, -0.2377, +0.0500, +0.1625, +0.1170, -0.0106, -0.3097, -0.4656, -0.4708, -0.0289, +0.0066, -0.3745, -0.6951, +0.1199, -0.5173, +0.0549, +0.1097, -0.2456, +0.1115, +0.0591, +0.0470, +0.1578, -0.1879, -0.0658, +0.0909, -0.2496, -0.2248, +0.4248, -0.1354, -0.1393, -0.8688, +0.0636, -0.4394, +0.2200, +0.1561, -0.4325, +0.4339, -0.0754, -0.0817, -0.0893, -0.1214, -0.1116, +0.2879, -0.0563, -0.2715, -0.4882, +0.2859, -0.2995, -0.1398, -0.2850, -1.0355, -0.3602, -0.0328, +0.1144, +0.0813, +0.1973, -0.1108, -0.2196, +0.2758, +0.1210, +0.0388, +0.3758, -0.0191, -0.0143, -0.1181, -0.0926, -0.1991, +0.1299, +0.3758, -0.2773, -0.0428, -0.0928, +0.0626, -0.1142, -0.7525, -0.2598, +0.2538, +0.0233, +0.1504, +0.1794, -0.3095, +0.0210, -0.0850, -0.0495, -0.4411, +0.1839, +0.0477, -0.0286, +0.0936, -0.6572, +0.1839, +0.4563, -0.2091, +0.0248, +0.1385, +0.3169, +0.0519, -0.0989, -0.1175, -0.3051, +0.0354, -0.0424, +0.1304, +0.1515, -0.0171, +0.1693, -0.0891, -0.2219, -0.4009, -0.0310, +0.1282, +0.1776, -0.0047],
-[ +0.1380, +0.2142, +0.4673, +0.1246, -0.1066, +0.0043, -0.5221, +0.3742, -0.4602, -0.8135, +0.0083, -0.4086, +0.2676, +0.2790, -0.2260, -0.0560, -0.2715, +0.2882, -0.2880, +0.0254, -0.1774, -0.3830, +0.4338, -0.2213, +0.1391, -0.0732, +0.4147, -0.1880, +0.0527, -0.2910, -0.0809, -0.1841, -0.3322, -0.4953, -0.1521, +0.2495, -0.0054, -0.2932, -0.4878, -0.0038, +0.4161, -0.3234, -0.0314, +0.1115, -0.4632, -0.3006, -0.0798, +0.1703, -0.2143, -0.2859, -0.2375, +0.2771, -0.1369, -0.3072, -0.2897, -0.2418, +0.0962, -0.3550, -0.0244, +0.4272, +0.1292, -0.1235, +0.2004, +0.0508, -0.0173, -0.1179, -0.4618, +0.0211, +0.4627, +0.1255, -0.0642, -0.6615, -0.8088, +0.1172, -0.2285, +0.1128, -0.4433, +0.0289, +0.1877, +0.0257, -0.0601, +0.4759, +0.2316, +0.2525, -0.8702, -0.1753, +0.1574, +0.2693, +0.1138, +0.0027, +0.3658, -0.1321, +0.0335, -0.1231, -0.0159, +0.0725, +0.1244, -0.1485, +0.3185, +0.1363, -0.2805, +0.0108, -0.3196, +0.0761, -0.1414, -0.7086, -0.3851, +0.1082, -0.0947, -0.1132, +0.0128, +0.0426, +0.1525, -0.2935, -0.2190, -0.1058, -0.3318, +0.2028, -0.0869, -0.1759, -0.0099, -0.0156, +0.1404, +0.4959, +0.2544, -0.2563, -0.1863, -0.3104],
-[ -0.0462, -0.0661, +0.0177, +0.1117, -0.0840, -0.0354, +0.1956, -0.1682, +0.4247, -0.2188, +0.0610, -0.2316, -0.1642, +0.0931, -0.4613, +0.1745, +0.3985, +0.2796, +0.3386, -0.3525, +0.1070, -0.2179, +0.1877, +0.0971, +0.0106, -0.2052, -0.2934, +0.3679, +0.0239, +0.2812, +0.2747, +0.4661, -0.3552, +0.1835, -0.0808, -0.3574, -0.0415, -0.0578, +0.2739, -0.5322, +0.5109, +0.0240, -0.0562, -0.1229, +0.6340, +0.1371, -0.3732, +0.0357, -0.3860, -0.4552, +0.0429, -0.4369, +0.1635, +0.0917, +0.0485, +0.4785, -0.1511, +0.1110, +0.1995, +0.0097, +0.2405, -0.2414, +0.0298, -0.2812, -0.4761, +0.0651, +0.0123, +0.1065, +0.0719, -0.0054, -0.2184, +0.1448, -0.0888, -0.3939, +0.1655, -0.2067, -0.5353, +0.2353, +0.2515, +0.2236, +0.1733, -0.6740, +0.4386, -0.5420, +0.4434, +0.1039, -0.3120, +0.2169, -0.3071, -0.1024, +0.1452, -0.1416, -0.1628, +0.2083, -0.1115, -0.7625, +0.3777, +0.1805, +0.1196, -0.2727, -0.1867, +0.1559, -0.3124, +0.3247, +0.2318, -0.4715, +0.1808, +0.0566, +0.0206, -0.0373, -0.1982, -0.0788, +0.0168, +0.2310, +0.2439, +0.1661, -0.2146, +0.1834, -0.5113, -0.0335, +0.1840, +0.0022, +0.0348, +0.0051, -0.2306, +0.1406, -1.1259, +0.3664],
-[ +0.0318, -0.2679, -0.2614, -0.1973, +0.2404, +0.1434, +0.3707, +0.2090, +0.4069, -0.2247, -0.3218, -0.3096, +0.1293, -0.0884, -0.3467, -0.4976, +0.0924, +0.1781, -0.1320, +0.0549, -0.5223, -0.1325, +0.0103, -0.2401, -0.2866, +0.1653, +0.1530, +0.0176, -0.2471, -0.0895, +0.0405, -0.1687, -0.0921, -0.1267, -0.1152, -0.1043, -0.1753, +0.0893, -0.2130, -0.4188, -0.4725, -0.4629, +0.1877, -0.3559, +0.1267, -0.3203, +0.0462, -0.4118, -0.1890, +0.1122, -0.3732, -0.1022, +0.2022, -0.1366, +0.0030, -0.1273, -0.1577, +0.0149, -0.4048, -0.0553, -0.3841, -0.0635, -0.0668, -0.0240, -0.2512, -0.0342, +0.1208, +0.1698, +0.0684, +0.2576, -0.4877, +0.0467, -0.1196, +0.0137, -0.0317, -0.1261, -0.1722, +0.1796, +0.0264, -0.0866, +0.2900, -0.1445, -0.2117, -0.2555, +0.0153, -0.0128, -0.1061, +0.2955, +0.0776, -0.1622, +0.1979, -0.5717, -0.2221, -0.5955, +0.0113, -0.0887, +0.1299, +0.0254, -0.3551, +0.1862, -0.2365, -0.1536, +0.3140, -0.2480, +0.0087, -0.0997, +0.0713, -0.2663, -0.0440, +0.0937, +0.2929, +0.1531, +0.0955, -0.1225, -0.0295, -0.4336, -0.5122, +0.1122, -0.8094, -0.4266, +0.1985, +0.0234, -0.0613, +0.0515, +0.3909, -0.0183, +0.1148, -0.1523],
-[ +0.3359, -0.1869, -0.2533, -0.0985, -0.7635, +0.1533, -0.2820, -0.3471, +0.0897, +0.0203, +0.2535, -0.2971, +0.4527, +0.0458, -0.0874, +0.1152, +0.4554, +0.1142, -0.2699, +0.1179, -0.1985, -0.9075, +0.2464, -0.4019, -0.0910, -0.2593, -0.2856, -0.0436, -0.6527, +0.1452, -0.2960, +0.0344, +0.1343, -0.1048, -0.3936, -0.3032, -0.3788, +0.0353, -0.1878, +0.0576, -0.1689, -0.4045, -0.1461, +0.0830, +0.1182, -0.4652, -0.0953, -0.6720, +0.0945, -0.5396, +0.0898, +0.2677, -0.2913, -0.4229, +0.1202, -0.0904, -0.3550, -0.3097, +0.2230, +0.1057, +0.0718, -0.3367, +0.1662, +0.0343, -0.1256, +0.1963, +0.0176, -0.6387, -0.1989, +0.2022, +0.4656, +0.0942, -0.0056, -0.4187, +0.3404, +0.2211, +0.1169, +0.1007, +0.0997, -0.2284, +0.3446, -0.0014, -0.0285, -0.1841, -0.0327, +0.4128, -0.1193, -0.0727, +0.1012, +0.1710, -0.1450, -0.3435, -0.0115, -0.4703, +0.2966, +0.8223, -0.4463, +0.1917, +0.1166, +0.3306, +0.1405, +0.0708, -0.0131, -0.6147, +0.0924, +0.0075, +0.1126, +0.2569, -0.1908, +0.0480, -0.1231, +0.3264, +0.1711, -0.2605, -0.2647, +0.3721, -0.0645, +0.1503, +0.1291, +0.1172, -0.2780, -0.1826, +0.4557, -0.1936, -0.2885, +0.2577, -0.0979, +0.1202],
-[ -0.1158, -0.1203, +0.2931, -0.0169, -0.1224, -0.2196, +0.0375, +0.1217, -0.0717, +0.0309, -0.3250, -0.6930, +0.3157, +0.3399, +0.1499, -0.4654, +0.1378, +0.0857, +0.1082, -0.1218, +0.2364, -0.2335, -0.3723, +0.1551, +0.2133, -0.1149, +0.2749, +0.0897, +0.0351, +0.3511, +0.0369, +0.0891, -0.0289, +0.1253, +0.1030, -0.3115, -0.0120, +0.1679, -0.2288, -0.0316, +0.0693, -0.1857, -0.0275, +0.1549, -0.0970, +0.3139, -0.3723, -0.2072, -0.0652, -0.7408, -0.2646, -0.3538, -0.0154, -0.0892, -0.0768, -0.2742, -0.0490, -0.0602, +0.0019, +0.1352, -0.0770, -0.3543, -0.0697, -0.0010, -0.1149, +0.4413, -0.0254, -0.3315, -0.1090, -0.2054, +0.1694, +0.2616, +0.0942, +0.2497, +0.0530, +0.0563, -0.7192, +0.4092, -0.0048, +0.0902, -0.1310, -0.1415, -0.2011, -0.6722, -0.3626, -0.2573, +0.0514, +0.2064, +0.4356, -0.3869, -0.4955, +0.4278, -0.0143, +0.5334, -0.0880, +0.3717, +0.2425, +0.3499, -0.1294, -0.2654, -0.3768, -0.0888, -0.0157, -0.0979, -0.0309, +0.2135, +0.5274, +0.1955, -0.1448, +0.1123, -0.3041, +0.2034, +0.3085, -0.1826, +0.0387, -0.0188, +0.0767, +0.0393, +0.0995, -0.0815, -0.1028, +0.3061, -0.0871, +0.0163, +0.0341, -0.0941, +0.1141, -0.0859],
-[ +0.1346, -0.2172, +0.0978, -0.6672, -0.1348, -0.0431, -0.2859, +0.2175, -0.0364, -0.0001, +0.1272, -0.0153, +0.1906, +0.0659, +0.0133, -0.1530, +0.0221, +0.1844, -0.1527, +0.2800, -0.1700, +0.1811, -0.0547, -0.1051, +0.0705, +0.4800, +0.3136, +0.3016, +0.1607, -0.2637, -0.0977, +0.3550, -0.8973, -0.0959, +0.1339, -0.0700, +0.0018, +0.2663, -0.0236, +0.2359, +0.1039, +0.1942, +0.0607, -0.3812, -0.5102, +0.0543, +0.0873, +0.3242, -0.2135, -0.2219, -0.1992, +0.2718, -0.1586, +0.3889, +0.1715, -0.2721, -0.2973, -0.3207, -0.0925, +0.1679, +0.0101, +0.1243, -0.0946, +0.4589, +0.0732, +0.2290, +0.1831, -0.2087, +0.0723, -0.3444, +0.0759, +0.0474, +0.1058, +0.0749, +0.3074, +0.0300, -0.0406, -0.0367, -0.2537, -0.0259, +0.2831, +0.2101, -0.2099, +0.1691, -0.1417, +0.3665, -0.2222, +0.0689, -0.5235, -0.4461, +0.0953, +0.0713, -0.0981, +0.1386, -0.2551, -0.1353, -0.2220, +0.0984, +0.1421, -0.2133, +0.3212, +0.0994, +0.2285, -0.1218, -0.1785, -0.3109, +0.1328, -0.0235, -0.1608, +0.4227, +0.0215, +0.0019, +0.0836, +0.1117, -0.0728, -0.2913, -0.1075, +0.1626, -0.3855, +0.0457, +0.3605, +0.2480, -0.2352, -0.1792, -0.3048, +0.0033, -0.2870, -0.2734],
-[ +0.2825, +0.0253, +0.3434, -0.4158, +0.3016, +0.0192, -0.0418, -0.1255, -0.1076, +0.0548, -0.1023, -0.5851, +0.1909, +0.2882, -0.3090, -0.7278, +0.3460, +0.2750, -0.7070, -0.0496, +0.3945, -0.2519, -0.1225, -0.0607, -0.4056, -0.2111, +0.3660, -0.0585, +0.4245, +0.2649, -0.3773, +0.0827, -0.1903, -0.2281, -0.0650, -0.0638, -0.2845, -0.1337, -0.0783, +0.1342, -0.1489, -0.4966, +0.0118, +0.0197, +0.0057, +0.0949, +0.0621, -0.0338, -0.0991, +0.0066, -0.1481, +0.2726, -0.4469, -0.3302, +0.2692, +0.1707, +0.3707, +0.1253, -0.4246, -0.1088, -0.4577, +0.3361, -0.1334, -0.0922, -0.0685, -0.0547, +0.4337, +0.1579, -0.4863, +0.0767, +0.1318, +0.1400, -0.4470, +0.3186, -0.3718, -0.2955, -0.2746, -0.0406, +0.5112, -0.0238, +0.0284, -0.1063, -0.0117, -0.8589, -0.3694, +0.0320, +0.0189, +0.0331, -0.2141, -0.8608, +0.0327, -0.0556, -0.1770, +0.1723, -0.2761, -0.1774, +0.0713, -0.0250, -0.0596, -0.0625, +0.2231, +0.0175, -0.0983, +0.0422, +0.1555, -0.5649, -0.3524, -0.2454, +0.1824, -0.0103, -0.1012, -0.9742, -0.1553, +0.1821, -0.4459, -0.3179, -0.1515, +0.1620, +0.3267, +0.1404, +0.2546, -0.1374, +0.1050, +0.3883, +0.1537, +0.3372, -0.1049, +0.2927],
-[ -0.1137, -0.4166, +0.0811, -0.1074, +0.1298, +0.3253, -0.2082, -0.2213, +0.1534, -0.1803, -0.0258, +0.0401, +0.0798, -0.2134, +0.2491, +0.0716, +0.0343, -0.2944, +0.2551, +0.0941, +0.0408, -0.3241, +0.0993, +0.0733, -0.3525, -0.0441, +0.1505, +0.4496, +0.2280, -0.7034, +0.3645, +0.1627, +0.1388, +0.0158, +0.0827, +0.0373, +0.3876, +0.2836, -0.0866, -0.0687, +0.2009, +0.1649, -0.2235, +0.2029, -0.2978, -0.0627, +0.1204, +0.3592, +0.1627, -0.0046, -0.2956, -0.0393, -0.0124, -0.0285, -0.0873, +0.1263, -0.0741, -0.2644, -0.4354, +0.1968, -0.1551, +0.2574, +0.3975, -0.2532, +0.2247, +0.1793, -0.0178, +0.0389, -0.2176, -0.0078, +0.3203, -0.4747, +0.2487, -0.2343, -0.1160, +0.2001, -0.0703, -0.3625, -1.2527, -0.0600, +0.4611, -0.5930, -0.2747, -0.0267, +0.3052, +0.1597, +0.0768, +0.1167, -0.2072, +0.2038, +0.3434, -0.0937, +0.0957, +0.3292, +0.0797, -0.2865, -0.0670, -0.0445, -0.1057, -0.2379, +0.5652, +0.0320, +0.0419, +0.4116, -0.1071, +0.0689, +0.0907, +0.3484, +0.1590, +0.0351, -0.0998, +0.1812, +0.0501, -0.0919, -0.1304, -0.2934, +0.2443, +0.1057, -0.0614, +0.0500, +0.0664, -0.0375, +0.1694, -0.2717, -0.2612, -0.3212, -0.2974, +0.2638],
-[ -0.5774, +0.3181, -0.3273, -0.1211, +0.0055, -0.4124, +0.0537, -0.2612, +0.2349, -0.4658, -0.0050, -1.0234, -0.3664, -0.1299, -0.1466, -0.0418, -0.2383, -0.3654, +0.3775, +0.1982, -0.1129, -0.1871, +0.2701, +0.4368, +0.0212, +0.1457, +0.0686, -0.2753, +0.1434, -0.0047, +0.1454, +0.0819, -0.3603, +0.1466, +0.1092, -0.3422, -0.4487, -0.0906, -0.3430, -0.2524, +0.1927, +0.1330, -0.1120, +0.1445, +0.2624, +0.1544, -0.0290, -0.3791, -0.7613, +0.2273, +0.5885, +0.0024, -0.3480, +0.1977, -0.0958, -0.6726, +0.3647, +0.2863, +0.1615, -0.3028, +0.1422, +0.0351, -0.2444, +0.4095, -0.1586, -0.2540, -0.2831, +0.1385, -0.1211, +0.0820, +0.0624, -0.3549, +0.5922, +0.0954, -0.2535, -0.0218, -0.0244, +0.3862, -0.1688, -0.3774, +0.3790, +0.2072, -0.0622, -0.2919, +0.0455, +0.3040, -0.3514, -0.0860, +0.0334, -0.1671, +0.2577, -0.5322, +0.0133, +0.1657, -0.3508, -0.2676, +0.3673, -0.0115, -0.0482, -0.0297, -0.0389, +0.1215, -0.1455, +0.0523, -0.0173, -0.6891, -0.0529, +0.0384, +0.0603, -0.0842, +0.2071, -0.3928, -0.4082, -0.3285, +0.1687, -0.0882, +0.3685, +0.6179, -0.1699, +0.1308, +0.3543, -0.3176, +0.3397, +0.3826, +0.3932, -0.2160, +0.0758, -0.5191],
-[ +0.0368, -0.2841, +0.3212, -0.1046, +0.1066, -0.1692, +0.0441, -0.1738, +0.1288, +0.1462, +0.3217, +0.0865, +0.0390, -0.0192, +0.0404, -0.2603, -0.0536, -0.0572, -0.1969, +0.0769, -0.1008, -0.1035, +0.2273, +0.2291, -0.3269, +0.1858, -0.0050, +0.0674, -0.0107, -0.1338, +0.3698, -0.5048, +0.1857, +0.0551, +0.0661, -0.1068, -0.0948, +0.0117, +0.1151, +0.2025, +0.3121, -0.2408, +0.1965, +0.0487, -0.7906, -0.0334, +0.3236, +0.1644, +0.4166, -0.1055, +0.1932, -0.0195, -0.3465, +0.0443, +0.1194, +0.0125, -0.0827, -0.0962, +0.2962, -0.0488, +0.1598, +0.3571, +0.0897, +0.3379, -0.2544, +0.2126, -0.0753, +0.2236, -0.3288, -0.2804, -0.2382, -0.0673, -0.4725, -0.2956, +0.3931, -0.0577, -0.0484, -0.0825, -0.0234, -0.0012, -0.2582, +0.2310, +0.1934, -0.0328, -0.3296, -0.0377, +0.0144, -0.0493, +0.1883, +0.1098, -0.0826, -0.3920, +0.0428, +0.2089, -0.2060, -0.7064, +0.1179, -0.0451, -0.2583, +0.0018, +0.2450, +0.2332, +0.1510, +0.1215, +0.3939, -0.0024, +0.0365, -0.0031, +0.2525, +0.4259, -0.1204, +0.4661, -0.4353, -0.1290, -0.1438, +0.0636, -0.0102, -0.3655, +0.0300, +0.1916, -0.0599, -0.2007, +0.0524, -0.1662, -0.2424, -0.0274, -0.1569, +0.1000],
-[ -0.0637, -0.1863, -0.6578, -0.4075, +0.4592, +0.0931, +0.0450, -0.2538, +0.2210, -0.1249, -0.0020, +0.0283, +0.0380, +0.0780, -0.1990, -0.0818, -0.4455, -0.0233, +0.2985, -0.0360, +0.0030, +0.1289, -0.4828, -0.0266, +0.3165, +0.4611, -0.1339, +0.2269, -0.3576, +0.2379, +0.0616, +0.0536, -0.1029, -0.2106, +0.2604, +0.2081, -0.1925, -0.0754, +0.2499, +0.3368, -0.0372, +0.1727, +0.0510, +0.3065, -0.3597, +0.0893, +0.0763, +0.2531, +0.0945, -0.0978, -0.4872, +0.1585, +0.2350, +0.0042, +0.2615, +0.5016, -0.0575, +0.3570, -0.2265, +0.0205, -0.0211, +0.0035, +0.1404, -0.0716, +0.1827, -0.0442, -0.0263, +0.1428, +0.1302, +0.1828, -0.2924, -0.0227, +0.1217, -0.6324, +0.2053, +0.1390, +0.0127, +0.1238, +0.1171, -0.1365, -0.2359, -0.4082, -0.1660, +0.1427, +0.1196, -0.0325, +0.0057, +0.4846, +0.0993, -0.0405, +0.1408, -0.1807, -0.2587, +0.3101, +0.1675, +0.0447, -0.3461, -0.2691, -0.4096, -0.0942, +0.1744, -0.0936, -0.5898, -0.2103, -0.1726, -0.0253, +0.0434, -0.1817, -0.0017, -0.0732, +0.0117, -0.0722, +0.0378, -0.0350, +0.1071, +0.1702, +0.0475, -0.2638, -0.1625, -0.1349, -0.0802, +0.2415, -0.5080, -0.1928, -0.1470, -0.4723, +0.0916, -0.3390],
-[ -0.0319, -0.2568, -0.3452, -0.8975, +0.0234, +0.0465, -0.2783, -0.0049, +0.2664, +0.1066, +0.1903, -0.1544, +0.1015, +0.0390, +0.2634, +0.1084, +0.4512, -0.0436, -0.1367, +0.0045, -0.1837, +0.1029, -0.1632, -0.1837, +0.6919, -0.0553, +0.0326, -0.1813, -0.0900, +0.1512, -0.4626, -0.1875, -0.4928, -0.0598, +0.1387, -0.2047, +0.2451, +0.0565, -0.1416, -0.3491, -0.3006, -0.1248, +0.0152, -0.2328, +0.2402, -0.0661, +0.0658, +0.1040, +0.3802, -0.0112, +0.0407, -0.1680, +0.0345, +0.1971, +0.3401, +0.2459, -0.0255, +0.1214, +0.2680, -0.3016, -0.2448, -0.1874, -0.2089, -0.1908, -0.1026, -0.0855, -0.4025, -0.3408, -0.2456, +0.5108, +0.3292, +0.3236, +0.0067, -0.2123, -0.3467, -0.4285, +0.3948, -0.1683, +0.1793, +0.0202, +0.1046, -0.1635, +0.0089, +0.1688, -0.2510, -0.3722, -0.2089, -0.1783, -0.0669, +0.0678, -0.5277, -0.0529, +0.1733, +0.0191, -0.0705, +0.0364, +0.1663, -0.1209, +0.1131, +0.1186, +0.2512, -0.0488, +0.0809, -0.1145, -0.1271, -0.0396, -0.1508, +0.1063, +0.0833, -0.0061, +0.0375, +0.0654, -0.3352, -0.2458, -0.2320, -0.3859, -0.0070, +0.1126, -0.1032, -0.2134, -0.0926, +0.0302, +0.1784, -0.0682, -0.0282, -0.7006, +0.1910, -0.3904],
-[ +0.3192, +0.1111, -0.6012, +0.3225, -0.4535, -0.0085, -0.3111, +0.1855, -0.1676, -0.0738, +0.0822, +0.1434, +0.4061, -0.0507, +0.4361, -0.3297, +0.3959, -0.0188, +0.4148, -0.5738, +0.1457, -0.0489, +0.2778, -0.3531, -0.1397, -0.1520, -0.0287, -0.6212, -0.3127, +0.2671, +0.2058, -0.4405, -0.2342, -0.5902, +0.3898, +0.3465, +0.1755, -0.0220, +0.1983, -0.0664, +0.2772, +0.1739, +0.1469, +0.1508, +0.0469, -0.0437, +0.2568, +0.2491, -0.0083, +0.1356, +0.0938, +0.0837, +0.0836, +0.0214, +0.4250, -0.1934, -0.4020, -0.1029, -0.5578, +0.2044, -0.2170, -0.0228, +0.1993, +0.2275, +0.1241, +0.1742, +0.0646, -0.2667, -0.2929, -0.1490, -0.1064, -0.1058, -0.0915, +0.4289, +0.0903, -0.0145, +0.0636, -0.1609, +0.1068, +0.0953, -0.1067, +0.6037, +0.0392, -0.3197, +0.5477, -0.2598, -0.1731, +0.2520, -0.1743, +0.3163, +0.1029, +0.0826, +0.0984, -0.1887, +0.1584, +0.0799, -0.0282, -0.3150, +0.2303, -0.1113, +0.0595, +0.3788, -0.0392, +0.3025, -0.3878, -0.5151, +0.2330, +0.0285, +0.3161, -0.0239, -0.4795, +0.0254, -0.2269, +0.2386, +0.1402, +0.1470, -0.6547, -0.0564, +0.1567, +0.2744, -0.2991, -0.1626, -0.0430, +0.3150, -0.3246, -0.5712, -0.0055, -0.3797],
-[ -0.3311, +0.5520, +0.0202, +0.0347, -0.0955, +0.1769, -0.1216, -0.5414, -0.0140, -0.4940, +0.0579, +0.1224, -0.3528, -0.0838, +0.0529, +0.3608, -0.0284, +0.3117, -0.2008, -0.1805, -0.0194, -0.0832, -0.4345, -0.0929, +0.2921, -0.1498, -0.1107, -0.1055, +0.1120, +0.0489, -0.0705, +0.3460, -0.5063, -0.1734, -0.1611, -0.1879, +0.0308, -0.1548, +0.2727, -0.3340, -0.0900, +0.0219, -0.2370, +0.1133, -0.4604, +0.0397, +0.0569, -0.0033, +0.1989, +0.0316, -0.0793, +0.3309, -0.2333, -0.0901, -0.0592, +0.6892, -0.2496, -0.3073, -0.2298, +0.0616, -0.3792, +0.1182, +0.1591, -0.3000, +0.0748, +0.0657, +0.1301, -0.4092, -0.0038, +0.2277, +0.1257, -0.2273, +0.1688, -0.2584, -0.4970, -0.4494, +0.1215, -0.4090, -0.2102, -0.0350, -0.5087, -0.4668, -0.1650, -0.0987, +0.1236, +0.2362, +0.2316, -0.0291, -0.0943, -0.5639, +0.1708, +0.2437, -0.1004, -0.1398, +0.1035, +0.1159, -0.1351, +0.1072, -0.1315, -0.3223, -0.4333, +0.4723, -0.1710, -0.2299, +0.2976, -0.0060, +0.1195, -0.0104, +0.1074, -0.2846, -0.4527, -0.2632, +0.1364, +0.0941, +0.1204, +0.0046, +0.0114, +0.0163, -0.1973, +0.3729, +0.0846, -0.4045, +0.2118, +0.0164, -0.2190, -0.2371, -0.2993, +0.2432],
-[ -0.1999, +0.2731, -0.5014, +0.0910, -0.0931, +0.1036, -0.1270, -0.0817, -0.0154, -0.0206, -0.0408, +0.4497, +0.2223, +0.2196, -0.7578, +0.2677, +0.0995, -0.2112, -0.0028, +0.2438, +0.1108, +0.2180, -0.1645, +0.1080, -0.0588, -0.3713, +0.2330, +0.0622, +0.0356, -0.1107, +0.2171, +0.3460, +0.1169, -0.0950, +0.0433, +0.2683, +0.3525, +0.0266, -0.0754, -0.5264, +0.2388, -0.6409, -0.0726, +0.0384, -0.1989, -0.0009, -0.4445, -0.1684, +0.1225, -0.1660, +0.4413, -0.1799, +0.2400, -0.3099, +0.0016, -0.0833, -0.7784, +0.4708, -0.6577, +0.3799, +0.6264, -0.1871, -0.3739, -0.4713, -0.1501, -0.4015, -0.1328, +0.0957, +0.1912, +0.0638, -0.0467, -0.4078, +0.1610, -0.0365, -0.3455, -0.2260, -0.3127, -0.1146, +0.0137, +0.5440, -0.0219, +0.2123, -0.0637, -0.2723, -0.2934, +0.1655, -0.2298, -0.2410, -0.5185, -0.2223, -0.0961, +0.0352, +0.2925, +0.3485, -0.1372, -0.4120, +0.1116, -0.1099, +0.0138, +0.0291, -0.0382, -0.7153, -0.2397, +0.2314, +0.1870, -0.0262, -0.3472, -0.1412, +0.1835, +0.1803, -0.3371, +0.1257, -0.0936, -0.0660, -0.0033, -0.1456, +0.1906, -0.0405, -0.0503, +0.0937, -0.2006, -0.3532, +0.0603, +0.2505, +0.3601, -0.0452, -0.0635, -0.6510],
-[ +0.0801, -0.1152, -0.1023, -0.2728, +0.2922, -0.1832, +0.0599, -0.1848, +0.4450, +0.1490, -0.1221, +0.1036, +0.0132, +0.0810, +0.1268, -0.1337, -0.3961, +0.1085, -0.0716, -0.1921, -0.3443, +0.1464, +0.0135, +0.2471, +0.1164, -0.1025, -0.0783, -0.2663, -0.1993, +0.0015, +0.0044, -0.4095, -0.0273, -0.1155, -0.4331, +0.1066, +0.0919, -0.2454, -0.2628, +0.2389, -0.1057, +0.2725, -0.1989, -0.1479, +0.0510, +0.0092, -0.1120, +0.1414, +0.0799, -0.0754, -0.2215, -0.1256, -0.0623, +0.2077, +0.3035, -0.2214, -0.6918, +0.1394, +0.2235, +0.1078, +0.0306, -0.1905, +0.1945, +0.1752, +0.3299, +0.1567, -0.4560, -0.0486, +0.2782, +0.0370, -0.0034, -0.1706, +0.2711, +0.0758, +0.3491, -0.4888, -0.1950, +0.1386, +0.1543, +0.0083, +0.1213, -0.3797, -0.0387, -0.3016, +0.0131, -0.2130, -0.3180, +0.1819, -0.1755, +0.0802, -0.2931, +0.1786, -0.0149, -0.1051, -0.0315, +0.1551, -0.1358, +0.0589, +0.5969, +0.2370, +0.3050, +0.2023, +0.2449, +0.3847, -0.1073, +0.0952, -0.1834, -0.0657, -0.0297, -0.1044, -0.1129, -0.2891, +0.1358, +0.0482, +0.1766, +0.1571, +0.2808, +0.4726, +0.1341, -0.2285, -0.3607, -0.0398, +0.6096, +0.1937, +0.2873, -0.1861, -0.1185, +0.3545],
-[ -0.3278, -0.1930, -0.1599, -0.5355, -0.1366, +0.1130, +0.0473, -0.2217, -0.0350, +0.0798, +0.0793, -0.5043, +0.1174, +0.3034, +0.0124, +0.2226, +0.3267, +0.1707, +0.2169, -0.5309, +0.1600, +0.0517, -0.4852, +0.0062, +0.0718, +0.1663, -0.0552, +0.0169, +0.0383, -0.0693, +0.1500, +0.0157, -0.0304, +0.1954, -0.0287, -0.3461, +0.1973, +0.0111, +0.1130, -0.1460, +0.0315, -0.5328, +0.2015, +0.3556, -0.0869, +0.0870, -0.5072, +0.1132, -0.2748, -0.4480, -0.2697, -0.0652, -0.5685, -0.4562, +0.1975, +0.2419, -0.4626, +0.0024, -0.1507, -0.1471, +0.2193, -0.1275, +0.4040, +0.3209, +0.1640, -0.1510, -0.4820, +0.1794, -0.4405, -0.1735, +0.1729, -0.3057, -0.4526, -0.0080, -0.4693, -0.2131, -0.2706, +0.0447, +0.1040, -0.3679, -0.4076, -0.1979, -0.2949, +0.1116, +0.2748, -0.3093, -0.0293, -0.0922, +0.1830, +0.1941, +0.3643, -0.1352, +0.3278, +0.0598, +0.1934, +0.1198, +0.0962, -0.4302, +0.1065, +0.0470, -0.2098, +0.3883, +0.0830, +0.1810, +0.0977, +0.1435, -0.0660, +0.0221, +0.2323, +0.0524, +0.2645, +0.1619, -0.1579, +0.1316, -0.2469, +0.2635, -0.1006, -0.2155, +0.0331, -0.2031, -0.0216, -0.1451, +0.2895, -0.0214, +0.3568, -0.3865, -0.1667, -0.1800],
-[ -0.3304, -0.2134, +0.3510, -0.5108, -0.2111, -0.1792, -0.0421, +0.4758, +0.2467, -0.5291, -0.0360, +0.3120, -0.0341, -0.3329, +0.0485, +0.0262, -0.0625, +0.2772, +0.0243, +0.0503, -0.3026, +0.1754, +0.1102, -0.1137, +0.2720, -0.2735, +0.2843, +0.0928, +0.3817, -0.1360, +0.3084, +0.2154, +0.0551, +0.0254, -0.2090, -0.2294, +0.3103, +0.2654, +0.1559, -0.5294, +0.0432, +0.3977, -0.4601, +0.1524, -0.1085, -0.4227, -0.4719, +0.2092, +0.1943, +0.1581, +0.0410, +0.4207, +0.0977, -0.3378, +0.1116, -0.0014, -0.4745, +0.6479, +0.0745, +0.5830, +0.1199, -0.1011, -0.1293, -0.0804, +0.0018, +0.2811, -0.2055, +0.3042, +0.0299, -0.1093, -0.1341, -0.5747, -0.1965, -0.0029, -0.4240, -0.0170, -0.0404, +0.2126, -0.4633, +0.2287, +0.2028, -0.3558, -0.1158, +0.4914, +0.3413, +0.1495, -0.0327, -0.4714, -0.7613, +0.1391, +0.0399, +0.2837, -0.2018, -0.3605, -0.2774, -0.1837, -0.0889, +0.1551, +0.0221, +0.4301, +0.3622, +0.1331, +0.6120, +0.4287, -0.0283, -0.6826, -0.0267, -0.0294, +0.0663, -0.0459, -0.2412, -0.5911, -0.1372, +0.2309, +0.1248, +0.1185, +0.2075, +0.2477, -0.1539, +0.1403, +0.3769, -0.2115, +0.1617, -0.0457, +0.0571, -0.2857, +0.6603, +0.4566],
-[ -0.1823, +0.0784, +0.2491, -0.0658, -0.1253, -0.3280, -0.0786, -0.0834, +0.1769, -0.1943, +0.0284, +0.2453, -0.1602, +0.2141, +0.2370, +0.2935, -0.0225, -0.1074, -0.0917, +0.0168, +0.0555, +0.0727, +0.1091, -0.4227, -0.0792, -0.2282, +0.1589, -0.0921, +0.0707, -0.2317, -0.1100, -0.4094, -0.4553, -0.2184, -0.0116, +0.1466, +0.1430, +0.1080, -0.4107, -0.1796, +0.2525, +0.3216, -0.9063, -0.0929, +0.3810, -0.7382, +0.5492, -0.0668, +0.3180, +0.4302, -0.0739, -0.0155, -0.1496, -0.0550, +0.2669, -0.3280, +0.1120, +0.1728, -0.1383, +0.2225, +0.2539, +0.2513, +0.0321, +0.5312, +0.2007, -0.4269, +0.1030, -0.0593, +0.2921, -0.1206, -0.1005, +0.3027, -0.3273, -0.3401, +0.4240, -0.1429, -0.3607, -0.2518, -0.3908, -0.1625, +0.0287, -0.0235, -0.4878, +0.4316, -0.2891, +0.0565, +0.2353, -0.0641, +0.3064, +0.2112, -0.1420, -0.2177, -0.3821, +0.7271, +0.3713, -0.3661, +0.5337, +0.1600, +0.2798, +0.0060, -0.5892, -0.0844, -0.0186, +0.1678, -0.4085, -0.6148, -0.3494, -0.2869, -0.1150, -0.2749, -0.0230, -0.1066, +0.0143, +0.0127, +0.0161, -0.2056, -0.2318, -0.5619, +0.1652, +0.1019, -0.1633, -0.1833, -0.2370, +0.2717, +0.2952, +0.0667, +0.0990, -0.4266],
-[ -0.1404, +0.2058, +0.1602, +0.0134, -0.0048, -0.0035, -0.0355, -0.2216, +0.2586, +0.3609, -0.2009, -0.1837, -0.0456, -0.0235, -0.2660, -0.0855, +0.2575, -0.1742, +0.0712, -0.3809, +0.0540, -0.3518, +0.0654, -0.0985, -0.0174, -0.2376, -0.0256, -0.4111, -0.2828, +0.0993, +0.2304, +0.5239, -0.3554, +0.0383, +0.2434, -0.5734, -0.1051, -0.3595, +0.2396, -0.8436, -0.1097, +0.3730, -0.0296, -0.7251, -0.5459, +0.0122, -0.2128, -0.0621, -0.0256, -0.1174, +0.0882, -0.4369, -0.0668, +0.1133, -0.1152, +0.2048, -0.1807, -0.1928, +0.1486, +0.0628, +0.0596, +0.2119, -0.6358, -0.2254, -0.7158, -0.1149, -0.2410, -0.5986, +0.5575, +0.0465, +0.1609, +0.1187, +0.0130, +0.1342, +0.0813, -0.0330, -0.3847, +0.1347, -0.4587, -0.1143, +0.2428, -0.5963, -0.1608, -0.1482, +0.0627, +0.3220, +0.1516, +0.4999, -0.0128, -0.0200, -0.1320, -0.0554, +0.2049, -0.1251, -0.5828, -0.8083, +0.1950, -0.1099, -0.0353, +0.1212, +0.1774, -0.2833, +0.3942, +0.0153, -0.0157, +0.3691, -0.2966, -0.0717, -0.6072, +0.1585, +0.3019, +0.3623, -0.1689, -0.1160, +0.0535, -0.2640, -0.1563, -0.3521, +0.2048, +0.4548, +0.0275, +0.1527, +0.0274, -0.2322, +0.1108, -0.2821, +0.1913, +0.3169],
-[ +0.1590, -0.1035, -0.2605, +0.0136, -0.3923, +0.0692, -0.7490, -0.2982, -0.0454, +0.0929, -0.2295, -0.3157, -0.0764, -0.5633, +0.0159, -0.3085, +0.1804, -0.0719, -0.3588, -0.7964, -0.6185, -0.3666, -0.0235, -0.0345, -0.3317, +0.1480, -0.4855, +0.1127, -0.5958, +0.1819, -0.0419, -0.1468, +0.1142, +0.1051, -0.2639, +0.0997, +0.3395, -0.3084, -0.3258, -0.1066, -0.2893, -0.0037, +0.0564, -0.1242, +0.0657, -0.0035, +0.0636, +0.4068, -0.1448, -0.3482, -0.2538, +0.3569, +0.2159, -0.0154, -0.6304, -0.4189, -0.0635, -0.3691, -0.2921, +0.0409, +0.1899, -0.3812, +0.2210, -0.6655, +0.3989, -0.1049, +0.1303, -0.0892, -0.5919, -0.3518, -0.1278, -0.1322, +0.4399, +0.1367, -0.7090, -0.6477, +0.6335, -0.0354, +0.0506, -0.9850, -0.2243, -0.0365, -0.2207, -0.0357, +0.0192, -0.3252, +0.4193, -0.4387, -0.0567, -0.1070, +0.0985, +0.0036, +0.3469, -0.3330, +0.1098, +0.2214, +0.2048, -0.0146, -0.0623, -0.5665, +0.2825, -0.0504, -0.5541, -0.1815, +0.0756, -0.0723, -0.2771, +0.2300, +0.0135, -0.1535, +0.3194, +0.0648, -0.4801, -0.3012, -0.0178, -0.4948, +0.0913, -0.0701, -0.0560, +0.1917, +0.0169, +0.2973, -0.2595, -0.4123, -0.2222, +0.2014, -0.0542, -0.3881],
-[ +0.0190, -0.2289, +0.2122, +0.3353, -0.1944, -0.1196, +0.3250, -0.4051, -0.4948, +0.0590, -0.4226, -0.5429, -0.0153, +0.1209, +0.1909, +0.0308, -0.0752, -0.5306, -0.0138, -0.2742, -0.2818, +0.3312, -0.3404, -0.3811, +0.1262, -0.2478, +0.3360, -0.0831, -0.2199, +0.3797, -0.0050, -0.3790, +0.3728, -0.4673, -0.1201, -0.6100, +0.2481, +0.0763, +0.0353, +0.2943, +0.2041, +0.2258, +0.0065, -0.3684, +0.1407, +0.0883, -0.2261, -0.3986, +0.1192, +0.0393, -0.1829, +0.0456, -0.1700, -0.1890, -0.0255, +0.5810, +0.2534, -0.6135, -0.2221, +0.3232, +0.1238, +0.2076, -0.0528, -0.2240, -0.1124, +0.1144, +0.0085, +0.0646, +0.2492, +0.3381, +0.0875, +0.2317, +0.2245, +0.2454, -0.0249, -0.6176, -0.2258, +0.0930, -0.1846, +0.2402, -0.1385, +0.2153, -0.2008, -0.5581, +0.1088, -0.5005, +0.3305, -0.3271, +0.2312, -0.1030, -0.2210, -0.1379, +0.0190, +0.0899, +0.1926, -0.0067, +0.2582, +0.1681, -0.4289, +0.1044, +0.2660, -0.7339, +0.0163, -0.1567, -0.0121, +0.2644, -0.2077, +0.2582, -0.4713, +0.2558, +0.4078, +0.1073, -0.2123, +0.0709, +0.1464, +0.3106, +0.1395, +0.3353, +0.0492, -0.5039, -0.0581, -0.1024, -0.2474, +0.3306, -0.0213, -0.3695, -0.3309, -0.2358],
-[ -0.2505, +0.2642, -0.4537, -0.0715, +0.3695, -0.0352, +0.1565, -0.1376, +0.0881, -0.2340, +0.2502, -0.0066, +0.2090, +0.3373, +0.1071, -0.3952, -0.0842, -0.0159, -0.0483, +0.0554, -0.3171, -0.1729, -0.0182, -0.0288, +0.1663, +0.1096, +0.1333, -0.1396, +0.1167, -0.5935, -0.4258, -0.2818, -0.0363, +0.1614, +0.0594, -0.0180, -0.0911, -0.3805, -0.3195, +0.2354, -0.7418, -0.3067, +0.2896, +0.1554, +0.2314, -0.3847, -0.2630, -0.1717, -0.4242, -0.1676, -0.2017, +0.0866, +0.1201, -0.4409, +0.5562, -0.2542, +0.5081, +0.1408, +0.0570, +0.0872, -0.1119, +0.0402, +0.6168, -0.0142, +0.2616, -0.4573, -0.0325, -0.2873, +0.1618, +0.2425, +0.0082, -0.0065, +0.0754, -0.1841, -0.0383, +0.1628, +0.0744, -0.2854, -0.4410, -0.0051, -0.1549, -0.1816, +0.0458, -0.1471, +0.1906, -0.1438, -0.0535, +0.1475, -0.1722, -0.0339, -0.1129, -0.1283, -0.1106, +0.1569, -0.4002, +0.2532, +0.2737, -0.3029, -0.0787, -0.0859, +0.0837, +0.0402, -0.2344, +0.0842, +0.0386, -0.0083, +0.3807, +0.0054, -0.5496, -0.1724, -0.2242, -0.0842, -0.4564, +0.0385, -0.2174, +0.3352, -0.3090, -0.1349, -0.0586, -0.1559, +0.1631, +0.2784, +0.0279, +0.4398, +0.4739, -0.0570, +0.0061, -0.2062],
-[ +0.1434, -0.0120, +0.3951, -0.0323, -0.2571, +0.0301, +0.0365, -0.0118, -0.0874, +0.1590, -0.2019, -0.0344, +0.0095, -0.1811, +0.2940, +0.3832, -0.0999, -0.3384, +0.0198, -0.0699, +0.3587, -0.0567, -0.0724, -0.3066, +0.2375, -0.2321, -0.3101, +0.0757, +0.3101, +0.1344, +0.3533, -0.5987, +0.3279, -0.1368, +0.1387, +0.4028, -0.0494, +0.2006, +0.0743, -0.8107, -0.2589, +0.2490, +0.1449, +0.0505, -0.5133, +0.1138, +0.0307, -0.3560, +0.3254, +0.1286, -0.2014, +0.3468, +0.3491, -0.0319, -0.0878, +0.1543, +0.2314, -0.2761, -0.1381, -0.0057, -0.5610, -0.1594, -0.0920, +0.4453, -0.1576, -0.2773, +0.1801, -0.1316, +0.0393, -0.1425, +0.4727, -0.1651, +0.1977, +0.0339, -0.6448, -0.3207, -0.4467, +0.1506, +0.0784, +0.0261, -0.1625, +0.1947, +0.1033, -0.0283, -0.3328, +0.2162, +0.7168, +0.0928, +0.2083, +0.2409, +0.0455, -0.1177, +0.4082, +0.0083, +0.0361, +0.4231, +0.5370, -0.0506, -0.1792, -0.3001, -0.0351, +0.1178, +0.0498, +0.4208, -0.4401, +0.1326, -0.0392, +0.1412, +0.0806, +0.3868, +0.8497, +0.1497, +0.0860, +0.0240, -0.0507, +0.3800, -0.0406, +0.0583, -0.6224, -0.1246, -0.0229, -0.1372, -0.3068, +0.0459, -0.0281, +0.2181, +0.1075, -0.4332],
-[ -0.4636, -0.1112, +0.0763, +0.4141, +0.0402, -0.5420, +0.2227, -0.6480, -0.3164, -0.4396, -0.4744, +0.0671, -0.2261, -0.0518, +0.0014, +0.3857, +0.1624, +0.0687, +0.2872, -0.2497, -0.0027, -0.3947, -0.1018, +0.2272, -0.2266, -0.0169, -0.1020, +0.3085, -0.1820, +0.0355, +0.0255, -0.3090, +0.2653, -0.1058, -0.3634, -0.0307, +0.0202, -0.2707, -0.0831, -0.0681, -0.0213, -0.1671, +0.2558, +0.1859, -0.2014, -0.1705, +0.0005, -0.0036, +0.1420, -0.2307, +0.1531, -0.0214, -0.3054, -0.1012, +0.2385, +0.1473, +0.2885, -0.2721, -0.3078, -0.4205, -0.2689, +0.2199, -0.2707, +0.1737, +0.1931, +0.1001, -0.1801, -0.2993, -0.2526, +0.3641, +0.2463, -0.4613, -0.0852, -0.0683, -0.4316, +0.4021, +0.2350, -0.2239, -0.4374, +0.3698, +0.1811, -0.0643, -0.1829, -0.0204, +0.0173, +0.2112, +0.1542, -0.0099, +0.3586, -0.9393, +0.0668, -0.0593, -0.0195, -0.2426, +0.1660, +0.0517, -0.0871, -0.0915, -0.1157, +0.2283, -0.0123, -0.5005, -0.2247, -0.2321, +0.2065, -0.2147, +0.0276, +0.4313, +0.3968, -0.0005, +0.3617, +0.4281, -0.3239, -0.0066, +0.2102, -0.1717, +0.0734, +0.0493, -0.0372, -0.0340, +0.4729, +0.0822, +0.0106, -0.1141, +0.0119, +0.1059, +0.5751, +0.0668],
-[ -0.1552, +0.1920, +0.1906, -0.4119, +0.1690, -0.0936, -0.0005, -0.3644, +0.7333, +0.1379, +0.2201, -0.2639, +0.4613, -0.2908, +0.2669, -1.1749, -0.3588, +0.2477, -0.5366, -0.0223, -0.1503, +0.3160, +0.0281, +0.3906, -0.5610, +0.1908, -0.1706, -0.2998, +0.0783, +0.1982, +0.0441, -0.2543, +0.2529, +0.1253, +0.0761, +0.1273, -0.1639, +0.3318, +0.1196, -0.6859, -0.0741, -0.1769, -0.0100, +0.4201, -0.3729, -0.0130, +0.2054, +0.1697, -0.1171, -0.1656, -0.2938, -0.3180, +0.2930, +0.0248, -0.0721, +0.1678, +0.4060, +0.0378, +0.1610, +0.3815, -0.0424, +0.0788, +0.0789, -0.3713, -0.0217, +0.0841, -0.3375, +0.3190, +0.0918, +0.4838, +0.2233, +0.3977, +0.2742, -0.4574, -0.0468, -0.1012, +0.1981, -0.0430, +0.1140, +0.0615, +0.0295, -0.0799, -0.0695, -0.2327, -0.6654, +0.2112, -0.1571, -0.4852, -0.3658, -0.3385, -0.0080, +0.2630, -0.1378, -0.2598, -0.1100, +0.3519, +0.4706, -0.0383, -0.0452, +0.1254, -0.3156, -0.2174, +0.0628, -0.3415, +0.3510, -0.2029, -0.0020, +0.0680, -0.2272, -0.8619, -0.2280, +0.1946, +0.3584, -0.1512, -0.3592, +0.2931, +0.0253, -0.3035, +0.1828, -0.2700, -0.3571, -0.4811, -0.6953, -0.0204, -0.3862, -0.6288, -0.0145, -0.0406],
-[ +0.1678, -0.1390, +0.2876, -0.0368, -0.2344, -0.1094, +0.0984, -0.1800, -0.2036, +0.0680, +0.1698, -0.1941, -0.5914, +0.4885, +0.1021, -0.3722, +0.3561, -0.1853, +0.1896, -0.2605, -0.1587, -0.0873, +0.0486, -0.3496, +0.2293, -0.1008, +0.1305, +0.3650, -0.1152, -0.2546, -0.0588, -0.4204, -0.0234, +0.0420, -0.1034, +0.1464, -0.2898, +0.0839, -0.3266, -0.1044, -0.5746, -0.0885, +0.1007, +0.2220, -1.0912, -0.0480, +0.1591, -0.0165, +0.1192, +0.1978, +0.0232, -0.1556, -0.5672, -0.1858, +0.1479, -0.2103, -0.2111, -0.0703, -0.2522, +0.2085, -0.2553, +0.0499, -0.2740, -0.1353, -0.2710, -0.0528, +0.4056, -0.2755, +0.1720, -0.0192, +0.0148, -0.1274, -0.1029, -0.2500, +0.1273, +0.2180, +0.3116, -0.0436, -0.0094, -0.2959, +0.0379, -0.0557, +0.0774, +0.0563, +0.1035, -0.3976, -0.1366, +0.0774, -0.0490, -0.5567, -0.1338, -0.3588, -0.2579, -0.5681, +0.2617, -0.0666, +0.0752, +0.1150, -0.1603, +0.1110, +0.0370, -0.1144, -0.3738, -0.1971, -0.1416, +0.0396, +0.4996, +0.1288, +0.0554, +0.0123, +0.0905, -0.4663, +0.0454, -0.0723, +0.0772, -0.6927, +0.4248, -0.3354, +0.2230, -0.1773, +0.1688, +0.3252, -0.1065, -0.1715, -0.3558, -0.0626, +0.1096, +0.1991],
-[ +0.5921, -0.0539, -0.2375, -0.1628, -0.1813, -0.2862, +0.0293, -0.2155, -0.2371, +0.3062, -0.0559, -0.3696, -0.4438, +0.0744, -0.0515, -0.1233, +0.3211, +0.0144, +0.0047, +0.1096, -0.1194, +0.6654, +0.0189, -0.0285, +0.5427, +0.2019, -0.2679, -0.0657, -0.2132, -0.3312, +0.3644, -0.1502, -0.3224, +0.4975, +0.1831, -0.1414, +0.0861, +0.1378, -0.2480, -0.3489, +0.1228, -0.0426, -0.1649, -0.1352, +0.5559, -0.2245, -0.1738, +0.2697, -0.0013, +0.0406, +0.1814, +0.3375, -0.3825, -0.0905, -0.3900, +0.0475, -0.0292, +0.1905, -0.6014, +0.2037, -0.2561, -0.0093, -0.1547, -0.1622, -0.1100, -0.1235, -0.1932, -0.4019, -0.4531, +0.2393, +0.2683, -0.0960, -0.1682, +0.2321, +0.2489, -0.2497, +0.3791, -0.0741, +0.3354, -0.0953, +0.1158, -0.0730, +0.3047, +0.3713, -0.2526, -0.5759, -0.0975, +0.1361, -0.3150, +0.0852, +0.0006, -0.1836, +0.2002, +0.3521, +0.1334, -0.0675, +0.3020, +0.0340, +0.2560, +0.2306, -0.2568, +0.1243, +0.3763, -0.2964, +0.1928, +0.1165, -0.3346, -0.0858, -0.0298, -0.1786, -0.2049, -0.3626, +0.2401, -0.1222, +0.3287, -0.5254, +0.0560, -0.3043, +0.2072, -0.0904, -0.2016, -0.0695, +0.4787, -0.3004, +0.0996, +0.1439, -0.3243, -0.1055],
-[ +0.1111, -0.1740, +0.1508, -0.1986, +0.2262, -0.3348, -0.0585, +0.0075, +0.0359, +0.0449, -0.4827, -0.0655, +0.1545, -0.0082, -0.2903, -0.2934, +0.1367, -0.2222, -0.4653, -0.0171, +0.1057, -0.1496, -0.0883, -0.3486, +0.1808, +0.2586, +0.0096, -0.0701, +0.2976, +0.3417, -0.0200, +0.0370, -0.1724, -0.1279, +0.1512, +0.0398, -0.0496, +0.3608, -0.0239, +0.2864, +0.1176, +0.1120, +0.2264, -0.3415, +0.0121, -0.3474, -0.3206, +0.0721, -0.0702, -0.3024, +0.0170, -0.0474, +0.2562, +0.4340, +0.0519, +0.1430, +0.1811, -0.0179, -0.1797, +0.6682, -0.4247, +0.0873, -0.1702, +0.0747, +0.0966, +0.1486, -0.0962, -0.6584, +0.2975, -0.0368, +0.2390, +0.1650, -0.1969, +0.0966, -0.3846, -0.0257, -0.0487, -0.0734, -0.0613, -0.0289, +0.1590, -0.0105, -0.1821, +0.0777, -0.1220, -0.6621, +0.1552, -0.2265, +0.2804, +0.5431, +0.0168, +0.3805, +0.2050, -0.1815, -0.2352, +0.0362, -0.1197, -0.1010, +0.2668, -0.4902, +0.0595, +0.0568, +0.1720, +0.1513, -0.5935, -0.2029, -0.6192, +0.0444, +0.2029, +0.3536, -0.5571, -0.3656, -0.2919, -0.1727, -0.4999, -0.1579, +0.2853, +0.5241, -0.2430, +0.3972, -0.4621, +0.2171, -0.0693, +0.2835, +0.1048, +0.3082, +0.0935, +0.0725],
-[ -0.1637, -0.0871, +0.1658, -0.2654, -0.0754, -0.1575, +0.2605, -0.3529, +0.0581, -0.2371, +0.0493, +0.0024, +0.0636, +0.1201, -0.0833, +0.1548, -0.0617, +0.1090, +0.1521, -0.1700, +0.1232, +0.0961, -0.3606, -0.7468, -0.3476, -0.2093, -0.1083, +0.1433, +0.2611, -0.3620, +0.1350, -0.1761, -0.0702, -0.2724, +0.1582, -0.3202, -0.0834, -0.0354, -0.4836, -0.1879, -0.2959, -0.2197, +0.1708, +0.3084, -0.4935, +0.0483, -0.0412, -0.3479, -0.1102, -0.0092, -0.0574, +0.0554, -0.2258, +0.2767, +0.2602, -0.4930, -0.2602, -0.4295, -0.0097, -0.1366, +0.0042, -0.1456, -0.2534, -0.0490, -0.2300, -0.1938, +0.0845, -0.2032, +0.0032, -0.2577, -0.1209, +0.0597, -0.0013, -0.2991, +0.3123, -0.2665, -0.3323, +0.1128, -0.6301, +0.1209, +0.0201, -0.0950, -0.1123, +0.0299, -0.4154, -0.0366, +0.0223, -0.0708, -0.7754, +0.1047, -0.4431, +0.2150, -0.0731, +0.1860, -0.2326, +0.0030, -0.2935, -0.3126, +0.2240, +0.4270, +0.2995, -0.0847, -0.1550, +0.0892, +0.1713, -0.0596, -0.0584, +0.1644, +0.0519, -0.5139, -0.2303, -0.6931, -0.2711, -0.0971, -0.3829, -0.3374, +0.0538, +0.2356, -0.3548, +0.3561, +0.0897, -0.0909, -0.1119, -0.2261, -0.0979, -0.0202, -0.8850, +0.2295],
-[ -0.1634, -0.2828, -0.1941, -0.2810, +0.0986, +0.0981, -0.2612, -0.2277, +0.0979, -0.0239, +0.2944, -0.1705, +0.2270, -0.0299, +0.0262, +0.1895, -0.0745, -0.1899, +0.0421, -0.7681, +0.0562, -0.4968, -0.3613, +0.0405, -0.1105, -0.3492, -0.1548, -0.2436, +0.0937, +0.4257, -0.3796, +0.1241, -0.3825, +0.5613, +0.1613, -0.4511, -0.2494, +0.3871, +0.3589, -0.0450, +0.2856, +0.1787, -0.0970, -0.2310, -0.1176, -0.1352, -0.6234, -0.0065, +0.1151, -0.0174, +0.0149, -0.0273, +0.1629, +0.1581, +0.3120, +0.5614, +0.0688, +0.2278, +0.1334, +0.2673, -0.1221, -0.3665, +0.0668, -0.4807, -0.0818, -0.1851, +0.3883, +0.1152, +0.4085, -0.1056, +0.0702, -0.1919, -0.1840, -0.3105, +0.1887, +0.1173, -0.1200, +0.3380, -0.0967, +0.3400, -0.0601, +0.1227, +0.0433, +0.3186, +0.2203, +0.1091, -0.4412, -0.2574, +0.3692, +0.1454, -0.2175, -0.0362, +0.2412, -0.0417, +0.4794, -0.2736, +0.2893, -0.2836, -0.1868, -0.0621, +0.0612, +0.4949, +0.0728, -0.3448, +0.0081, +0.1892, -0.4146, -0.2561, -0.0357, +0.1077, -0.0580, +0.1262, -0.1692, -0.0372, -0.1210, -0.4731, +0.4645, -0.2352, -0.3995, +0.2874, +0.0848, +0.2734, -0.1254, +0.4217, -0.2578, +0.2693, -0.2673, +0.0498],
-[ -0.0628, +0.0296, -0.2983, -0.3481, -0.1473, +0.1786, -0.5650, +0.0384, +0.0395, -0.1228, -0.0090, +0.6397, +0.0374, -0.6429, -0.3989, -0.1724, +0.4038, +0.1364, +0.2632, +0.0267, -0.1227, +0.3067, +0.3173, +0.2586, +0.0388, +0.1178, -0.1741, -0.1198, -0.3351, -0.2439, -0.5281, -0.3739, +0.0095, -0.1192, +0.1664, -0.3714, -0.0687, -0.3244, -0.2592, -0.1771, +0.0574, -0.0862, -0.1435, +0.1585, -0.2317, -0.4128, -0.5971, -0.2712, +0.1453, -0.0166, -0.2195, +0.0543, +0.1135, +0.0443, -0.0980, -0.0873, +0.1613, +0.3857, -0.2544, -0.5476, -0.1106, -0.4170, +0.1687, -0.1565, +0.2169, -0.2409, +0.0623, +0.1636, -0.2886, +0.0399, +0.2059, +0.2386, -0.3149, -0.1199, +0.0318, +0.3464, +0.1410, -0.0834, -0.8710, +0.1241, +0.2162, -0.1006, -0.7545, -0.0171, -0.3134, -0.2252, -0.2220, -0.0807, -0.0750, +0.1127, +0.3198, -0.3802, -0.3772, -0.0536, +0.0959, -0.0257, -0.1361, -0.5826, +0.2504, -0.1742, -0.2791, -0.4393, -0.4317, +0.0342, -0.1934, -0.3139, -0.2882, +0.0038, -0.0628, -0.3115, +0.2009, +0.5177, +0.2402, -0.1266, +0.2183, -0.1377, -0.1591, -0.0679, +0.3299, -0.1463, -0.3163, +0.0590, +0.0126, +0.3101, +0.0180, +0.0617, -0.0267, -0.0517],
-[ -0.1878, +0.4202, -0.2018, -0.2199, -0.1093, +0.0883, +0.3946, -0.1421, +0.0568, +0.1144, +0.1511, -0.2157, +0.1200, -0.1398, +0.5402, -0.1717, +0.2102, -0.7088, +0.0888, -0.2136, +0.0865, +0.0689, -0.3463, +0.1241, +0.0271, -0.1606, +0.1215, +0.2254, +0.0182, -0.2754, -0.1091, +0.3262, +0.0484, +0.0632, +0.1665, +0.0405, +0.2157, -0.6539, +0.0117, -0.0504, -0.0204, -0.2643, +0.3264, +0.2175, +0.3935, -0.1287, -0.3278, -0.1537, +0.0975, -0.0697, +0.4259, +0.1344, +0.3404, -0.3377, -0.1828, +0.1118, -0.5460, +0.1486, -0.1924, -0.2064, -0.1048, +0.2057, -0.0103, +0.1334, -0.0832, -0.2903, -0.1947, -0.1323, -0.3305, -0.1156, +0.1135, +0.1272, +0.3634, -0.0064, -0.8530, -0.3437, -0.2028, -0.1464, +0.0134, +0.1799, -0.1531, -0.0605, +0.1737, -0.3357, -0.0260, +0.0243, +0.0821, -0.4290, -0.2971, +0.0604, -0.3610, -0.9631, +0.0909, -0.1828, -0.0168, -0.2583, -0.0384, +0.0965, -0.1840, -0.0546, -0.6720, -0.5470, +0.0744, -0.2020, -0.2608, -0.0065, +0.1288, -0.1573, +0.1691, -0.2865, -0.2280, +0.1725, +0.5208, -0.2204, -0.2221, -0.1635, -0.2530, -0.1879, -0.1018, -0.3523, +0.5690, +0.0229, +0.5258, +0.0883, +0.1659, +0.1884, +0.1938, -0.3107],
-[ -0.1181, +0.0420, +0.1144, +0.1611, -0.1838, +0.2476, -0.0909, -0.1870, +0.1146, +0.1150, +0.0946, -0.0853, +0.2211, +0.0397, -0.2939, -0.2748, -0.0733, -0.4318, +0.0864, +0.2981, -0.2610, +0.0152, +0.4888, +0.0618, -0.1510, -0.1448, -0.4673, +0.2183, -0.1130, -0.0786, -0.3847, +0.1379, +0.1242, +0.0200, -0.0700, +0.1541, -0.2642, +0.1701, +0.0021, +0.3278, -0.1615, +0.2148, -0.0260, -0.0893, -0.4782, +0.0654, +0.6166, +0.0800, +0.1462, -0.2415, +0.0865, -0.7428, -0.6088, +0.5626, -0.0687, -0.4575, +0.3253, -0.0043, +0.2689, -0.3320, -0.0873, +0.2519, -0.2260, -0.0534, -0.4402, -0.0939, -0.5351, -0.0932, +0.1957, +0.0074, -0.1433, +0.0204, -0.4745, +0.0286, -0.0910, +0.4747, -0.6399, -0.0882, +0.0181, +0.2373, -0.0368, -0.0419, +0.4141, +0.0785, -0.2220, +0.3220, +0.0220, +0.1948, +0.0091, +0.3534, +0.4111, +0.2544, +0.2341, -0.1570, -0.1050, +0.0645, -0.2550, -0.0280, -0.1230, +0.3032, +0.1779, +0.1246, -0.1200, -0.1179, -0.2386, -0.7218, +0.1017, +0.0982, -0.1698, +0.2219, -0.1897, -0.3570, +0.0490, -0.0444, +0.0950, -0.2295, +0.0222, +0.1401, +0.0871, -0.3157, +0.0077, -0.2118, +0.1846, +0.2797, -0.2519, +0.5200, -0.1003, -0.3801],
-[ -0.0374, +0.0125, -0.1276, -0.0663, -0.0598, +0.0254, -0.1572, +0.0380, +0.1068, -0.6109, +0.3036, -0.1031, +0.2926, +0.7185, +0.1928, +0.1294, -0.1074, +0.0822, -0.2497, -0.0638, -0.2045, -0.0279, -0.4689, +0.1881, -0.2892, -0.1539, -0.1233, +0.4763, -0.0517, -0.4180, -0.2516, -0.1770, -0.0086, -0.2397, +0.1959, -0.3844, -0.0017, -0.0121, -0.0297, +0.1524, +0.0519, -0.1683, -0.0179, -0.1571, -0.2795, -0.1275, -0.0718, -0.3185, +0.1964, +0.4256, +0.2213, -0.0376, -0.0930, -0.2075, -0.1796, +0.2767, +0.1493, +0.1180, -0.0987, -0.0247, +0.2443, -0.5713, +0.1010, -0.3878, +0.2381, -0.5685, -0.0383, -0.5102, -0.2925, -0.5523, -0.0822, +0.1612, +0.3682, +0.3328, -0.4877, +0.0733, -0.1662, +0.5293, -0.0499, -0.1371, +0.0455, +0.2431, -0.0888, +0.3100, +0.1143, -0.5558, -0.1580, -0.0643, +0.4244, +0.4820, +0.1560, -0.4581, +0.0270, +0.0924, +0.3386, +0.0239, -0.0115, -0.5032, -0.0458, +0.4652, +0.1183, +0.1134, -0.0802, -0.2699, -0.5722, +0.2359, +0.2058, -0.0863, -0.3910, -0.0556, +0.1493, -0.0604, +0.1420, -0.2824, +0.2240, +0.0645, -0.0183, -0.0387, +0.5395, -0.0833, +0.1167, -0.0518, -0.0461, +0.0443, +0.0494, +0.1201, +0.0229, -0.1096],
-[ +0.4898, +0.4718, -0.0682, -0.0311, +0.1615, -0.1496, -0.1432, +0.1643, -0.2215, +0.1757, +0.4375, +0.4404, -0.0622, -0.5233, -0.1271, +0.2250, -0.2745, +0.2733, +0.1107, -0.3827, +0.1241, +0.3758, +0.2248, -0.2225, +0.1124, -0.1181, -0.0423, -0.5795, -0.4674, +0.3522, +0.0859, -0.0276, -0.2329, +0.3446, -0.1834, -0.0068, -0.1553, -0.1485, +0.0824, -0.2299, +0.2591, -0.3897, +0.0787, +0.3867, -0.2286, +0.1480, -0.2998, -0.3949, -0.2774, +0.1865, -0.4783, +0.6124, -0.3644, -0.3829, -0.0067, -0.0521, -0.2011, +0.0770, +0.0012, +0.0381, +0.0878, -0.0414, -0.2545, -0.5219, -0.0408, +0.3443, +0.0090, -0.0228, +0.0870, +0.3942, -0.0491, +0.1444, +0.0063, -0.0771, -0.0745, -0.2912, +0.0112, +0.2357, +0.3547, +0.0734, -0.0780, -0.0617, +0.3603, -0.6174, -0.2102, -0.0907, -0.1515, -0.1293, -0.4516, +0.2042, +0.1366, +0.4122, -0.0986, +0.3063, -0.8169, -0.4886, -0.0303, +0.2678, -0.2087, +0.1952, -0.1536, +0.0337, +0.5130, -0.3060, +0.0524, +0.0624, -0.0559, +0.0889, +0.2813, +0.1058, +0.1298, -0.3953, -0.0201, -0.1515, +0.3005, +0.5508, +0.0059, +0.0024, -0.0398, -0.0980, -0.0488, -0.4250, +0.3168, -0.1026, -0.1809, -0.3030, -0.1698, -0.0848],
-[ +0.3695, +0.3071, +0.2333, +0.0139, -0.3983, -0.0711, -0.2194, -0.6272, -0.2138, +0.0617, -0.0111, -0.6236, +0.2183, +0.0222, +0.0592, +0.4917, -0.2183, +0.0121, -0.1354, -0.0017, +0.2402, +0.1886, -0.2910, -0.7567, -0.1246, -0.2037, -0.5099, -0.1605, -0.2461, +0.0206, +0.4707, -0.5077, +0.1170, +0.2024, -0.2554, +0.0730, +0.0879, +0.0928, -0.4353, -0.0598, +0.2081, +0.0372, -0.1332, -0.3373, +0.2284, -0.0599, +0.4024, +0.0604, +0.1383, -0.0774, -0.1523, +0.6480, +0.0155, +0.1066, -0.1377, -0.3421, +0.1621, -0.2353, -0.1816, -0.4314, +0.0973, +0.4458, +0.1650, -0.0560, +0.0744, +0.2842, +0.0021, +0.0804, -0.0905, -0.0140, -0.2298, -0.1811, -0.2960, -0.1459, +0.0368, +0.1198, +0.2527, +0.0157, +0.1724, -0.0734, -0.0688, +0.0016, +0.0925, -0.4295, -0.1006, -0.0191, +0.0594, +0.0157, -0.3886, -0.2070, -0.1863, +0.4119, +0.2145, +0.1962, +0.3108, -0.0909, -0.0882, -0.1576, +0.0135, -0.1729, +0.0140, +0.0432, +0.1751, -0.1687, -0.1999, -0.1014, -0.5196, -0.2550, -0.0893, -0.1267, +0.0980, +0.5148, +0.0603, -0.1135, +0.1299, +0.1265, +0.2391, -0.0833, -0.3704, +0.3892, +0.0321, +0.1687, -0.1774, +0.1666, +0.0407, -0.0665, +0.4508, -0.0340],
-[ +0.1389, -0.2080, +0.3438, +0.4899, -0.2797, -0.1417, +0.2512, +0.1198, -0.2197, +0.2436, +0.4070, +0.3478, -0.1127, +0.3079, -0.0048, -0.1004, -0.1047, +0.3478, +0.1476, +0.1566, -0.0925, +0.3851, -0.1324, -0.2224, -0.1426, -0.2631, -0.1746, -0.3112, +0.2770, +0.0137, -0.4146, -0.1265, +0.1451, -0.1700, -0.0411, +0.2917, -0.1317, -0.4289, -0.0707, +0.0520, -0.2571, +0.0517, -0.2700, -0.2443, -0.2731, -0.1958, +0.1699, +0.0438, -0.2558, -0.1989, +0.1992, +0.2155, -0.3511, -0.0328, +0.1605, -0.3222, -0.1463, -0.3556, +0.0530, +0.3442, -0.1352, +0.1355, +0.2699, +0.3785, +0.0217, -0.3072, +0.1845, -0.3802, +0.3923, +0.2325, -0.1082, -0.3326, -0.1154, -0.1105, +0.0031, -0.1160, +0.1205, +0.2553, -0.1605, -0.4819, -0.2491, -0.0375, +0.0202, +0.1819, -0.2861, -0.0136, -0.2221, -0.2957, -0.1213, +0.1185, +0.1611, -0.2615, -0.3213, +0.5138, +0.2730, +0.2119, +0.1809, -0.0294, -0.1709, +0.0105, -0.1378, -0.1316, +0.0682, +0.2159, +0.4921, -0.0666, +0.0769, +0.1773, -0.2154, -0.2371, -0.0556, -0.3074, +0.1083, -0.3648, +0.1665, -0.4355, -0.3632, -0.2370, -0.2437, -0.0211, +0.2440, -0.1843, -0.1545, -0.2505, +0.1790, -0.1286, -0.1876, +0.0066],
-[ +0.1689, +0.2206, -0.0781, -0.1455, +0.0397, +0.0219, -0.2993, +0.0903, -0.2283, +0.1591, +0.2444, -0.2100, -0.1380, -0.1889, +0.2269, -0.4279, -0.0857, +0.2944, +0.2988, +0.3288, +0.3567, -0.0988, -0.1966, -0.1906, +0.0061, -0.1165, +0.1244, +0.0469, +0.1843, -0.5449, +0.3939, -0.5508, -0.0447, -0.3135, -0.0453, -0.0627, +0.1362, -0.1780, +0.1294, -0.3741, -0.2563, +0.0990, -0.0449, +0.3342, +0.2931, +0.1074, -0.1005, -0.1918, -0.2936, +0.1220, +0.0024, +0.0063, +0.1774, +0.2586, -0.0011, +0.0033, -0.4226, -0.3821, +0.1809, -0.0285, +0.0375, -0.1220, +0.0390, +0.0580, +0.0155, +0.0621, -0.2021, +0.1297, -0.2579, -0.1164, +0.3854, +0.3059, -0.6227, +0.4577, -0.2496, +0.2659, +0.1491, -0.0004, +0.3749, -0.2097, -0.0885, +0.3152, -0.1971, -0.0840, -0.1774, -0.5290, -0.1122, +0.0411, -0.1771, -0.2706, +0.2021, +0.2337, -0.2176, +0.0079, -0.0904, +0.1092, +0.1135, +0.1338, -0.1462, +0.0274, +0.3584, -0.1800, +0.4639, -0.1490, -0.3155, -0.0412, +0.1629, -0.4656, -0.0496, +0.0748, -0.0045, +0.1361, +0.1575, +0.1444, +0.0315, +0.1265, +0.0749, +0.0722, +0.2141, -0.3132, -0.2626, +0.1807, +0.3173, -0.0458, -0.0529, -0.4732, -0.0423, +0.2795],
-[ +0.1614, -0.3846, +0.3338, -0.0183, +0.0286, +0.0085, -0.0646, -0.0875, +0.0821, +0.1362, -0.4212, -0.1688, +0.1994, -0.0489, -0.1341, -0.0673, -0.0943, +0.3059, -0.1284, -0.2643, +0.1213, +0.0141, -0.3665, +0.1340, -0.0951, -0.1020, +0.1972, -0.2862, +0.4121, -0.3036, +0.2082, +0.2528, -0.1514, +0.4938, -0.2471, -0.4203, -0.0928, +0.3780, +0.0119, -0.0783, -0.1615, +0.1439, +0.3527, -0.1908, +0.2838, +0.0668, -0.0234, -0.3280, -0.1800, -0.0103, -0.6500, -0.2414, +0.1170, -0.0475, -0.4425, +0.3974, -0.1808, -0.2993, -0.0731, +0.2598, -0.0778, +0.0570, +0.4062, +0.3539, +0.0569, +0.0185, +0.0098, +0.0246, +0.2126, -0.1912, +0.0584, -0.1487, +0.2746, +0.0755, +0.2073, +0.2170, -0.2629, +0.0391, +0.1679, +0.0640, -0.5268, +0.1509, -0.1113, -0.0692, -0.5873, +0.0353, +0.0339, +0.1475, +0.1000, -0.0805, -0.5734, -0.1932, -0.0914, +0.1323, -0.2580, +0.3211, -0.0493, -0.7405, -0.1821, -0.0603, -0.3156, +0.4612, -0.2098, +0.2076, -0.0475, -0.0307, +0.4645, +0.0965, -0.2655, +0.0462, -0.1490, +0.4663, +0.1683, -0.1155, -0.1533, +0.3838, +0.0265, -0.0092, -0.2440, +0.1372, -0.1355, -0.1840, -0.8211, +0.0373, -0.3227, -0.2345, +0.3017, -0.5007],
-[ -0.7194, +0.1233, -0.0451, +0.4639, +0.2358, -0.1510, +0.1254, +0.2313, -0.1787, +0.1401, +0.2545, -0.3689, -0.2419, -0.0821, -0.0639, +0.2946, -0.5942, +0.2970, +0.5321, +0.4658, -0.0104, -0.1767, -0.3440, +0.0767, +0.1729, -0.5545, +0.5259, +0.2951, -1.0173, +0.1334, +0.1770, -0.3246, +0.0155, -0.1276, +0.0960, -0.0504, +0.0450, +0.1771, -0.1464, -0.0822, +0.2322, +0.1848, -0.1134, -0.2567, -0.4594, -0.0382, -0.6554, -0.1064, -0.2206, -0.0739, +0.3366, +0.1127, -0.0090, +0.3358, -0.0705, -0.0750, -0.6799, +0.2498, +0.1230, +0.1456, +0.1680, +0.1652, +0.1617, -0.0904, +0.5898, -0.0638, +0.1600, +0.0301, +0.4253, +0.2886, +0.0156, +0.2199, -0.2753, -0.1821, -0.2855, +0.0326, -0.0055, +0.0443, +0.5850, +0.3302, -0.1953, -0.2251, -0.4092, +0.1372, -0.3366, +0.0798, +0.0072, +0.3039, +0.1618, -0.4104, -0.3004, -0.1219, -0.3149, -0.0726, -0.2950, -0.0165, -0.9270, -0.2799, -0.1752, -0.0162, -0.0462, +0.0538, -0.1469, +0.1161, +0.0670, -0.0248, +0.0987, -0.1501, -0.2436, +0.0872, +0.4334, -0.5042, +0.0042, -0.2367, +0.6838, +0.3448, +0.0355, +0.0805, +0.1266, +0.0622, +0.3305, -0.0711, -0.0195, -0.0055, -0.0946, -0.0947, -0.0616, +0.3404],
-[ +0.3272, -0.2307, -0.4980, -0.3687, +0.2682, -0.0280, -0.1263, +0.2620, -0.1047, -0.2322, -0.4030, +0.0904, +0.2516, -0.6150, -0.0529, +0.0397, +0.1731, +0.1377, +0.1052, +0.2936, -0.2730, +0.0615, -0.1997, +0.1070, +0.2508, +0.1554, +0.2048, +0.5632, +0.0154, +0.2170, -0.3470, -0.5387, -0.1137, +0.0830, +0.0412, -0.3426, +0.1562, -0.1541, -0.3798, +0.2924, -0.4815, +0.0288, +0.0003, +0.0698, -0.1956, -0.6329, +0.0033, -0.1108, +0.1074, -0.1663, +0.0352, -0.2713, +0.0867, -0.3850, +0.2340, -0.1578, +0.1721, -0.7906, -0.3210, +0.0378, -0.2736, -0.2421, -0.2189, -0.2970, -0.0288, -0.2068, +0.2631, -0.1496, +0.3061, +0.1604, +0.4461, +0.1724, -0.2270, -0.2402, -0.1807, -0.0693, +0.1151, -0.0305, -0.0112, +0.0159, -0.0346, +0.0245, +0.1452, +0.1488, -0.0366, -0.0898, -0.0973, -0.4954, +0.3385, -0.1914, -0.2531, -0.0537, +0.0391, -0.3276, -0.0391, -0.4617, +0.1141, +0.1026, -0.0772, -0.4487, -0.2116, -0.1719, -0.6509, -0.3549, -0.0131, -0.3162, -0.1257, +0.1993, +0.3512, +0.1550, -0.0918, +0.0812, +0.0252, -0.0723, -0.2245, -0.0305, +0.0530, -0.0849, +0.1550, -0.3906, -0.0536, +0.0028, -0.0251, +0.0676, +0.3088, -0.2304, -0.3914, -0.1776],
-[ +0.0754, -0.0331, -0.1040, +0.0217, +0.0386, +0.0777, +0.0818, -0.2514, -0.4614, +0.2256, -0.0788, -0.1833, +0.3704, +0.2216, -0.3747, -0.1590, -0.6929, +0.0802, -0.1232, +0.4860, +0.2148, -0.0651, +0.3254, -0.2056, +0.1625, +0.2458, -0.4113, -0.4391, -0.3837, +0.2540, +0.0527, -0.2951, +0.1566, +0.0967, +0.1662, +0.6384, +0.0095, -0.3455, +0.1615, -0.2592, -0.0434, -0.0727, -0.0382, -0.4776, -0.4566, -0.3037, -0.1459, -0.4048, +0.2599, -0.0861, -0.0116, -0.1129, -0.0676, -0.0800, -0.1187, -0.3390, +0.1063, +0.2348, -0.1164, +0.1153, -0.1498, +0.0402, -0.4802, -0.1661, -0.1160, +0.1173, -0.0176, +0.2695, +0.0772, +0.0372, +0.0242, +0.0225, +0.1049, -0.7242, +0.0126, -0.0755, +0.1022, -0.2108, -0.1998, +0.2239, +0.0868, +0.1431, -0.0998, -0.0364, -0.0655, -0.3919, -0.1501, +0.0311, -0.2907, -0.4067, +0.0829, +0.0872, +0.0864, -0.1518, -0.3844, -0.3313, -0.0999, +0.1984, +0.0486, +0.0816, -0.4610, -0.3460, -0.1629, +0.0140, -0.0830, -0.2701, +0.4440, -0.3354, +0.0757, -0.1434, +0.0249, -0.3367, -0.0574, +0.2688, -0.2757, -0.0715, -0.4653, -0.0473, -0.1148, +0.1354, -0.0367, -0.4103, +0.2259, -0.6937, -0.2013, -0.0564, +0.2864, -0.2999],
-[ -0.1390, +0.3005, -0.0987, -0.4789, +0.0332, +0.1438, +0.1070, +0.1519, -0.6019, +0.4098, +0.4004, -0.1516, -0.1093, -0.2201, +0.2699, +0.1977, +0.4157, -0.1772, -0.0797, +0.0854, -0.7648, -0.4394, -0.0438, -0.4718, +0.3928, -0.5257, -0.0439, +0.1315, -0.1150, -0.1163, +0.1980, +0.3534, +0.1772, -0.7586, +0.1434, +0.2689, -0.2058, +0.0350, -0.1247, -0.3290, +0.3909, +0.0623, -0.0877, -0.2343, -0.2182, +0.6083, -0.9525, +0.1864, -0.3507, +0.1482, -0.0038, -0.7236, -0.0294, -0.1077, +0.0192, +0.0980, -0.2851, -0.0462, +0.0435, +0.1113, -0.1022, +0.3637, +0.2610, +0.1618, +0.0215, -0.0779, -0.0163, +0.0879, -0.4159, -0.4511, -0.1508, +0.2072, -0.0557, -0.2555, -0.4352, -0.0096, +0.1234, -0.3254, -0.2381, +0.3456, -0.2058, +0.3037, -0.0526, -0.0977, -0.2569, +0.5950, +0.4026, +0.3997, -0.0944, -0.3276, -0.1265, +0.1403, -0.0443, +0.2053, +0.0302, +0.0350, +0.3422, -0.0679, -0.2907, +0.0528, -0.1514, +0.2496, +0.1636, +0.1756, -0.1530, +0.1945, +0.3399, -0.3761, -0.5962, -0.1480, +0.0239, -0.3460, +0.3300, -0.3923, +0.0366, +0.2525, +0.3290, -0.0804, -0.0721, -0.0075, +0.1203, -0.1507, -0.0603, -0.0650, +0.2470, +0.0277, +0.1761, +0.1118],
-[ -0.1023, +0.1811, +0.1096, +0.0398, -0.0287, -0.0113, +0.1133, -0.1833, +0.1573, -0.2773, +0.2050, -0.1728, -0.2022, -0.1899, -0.2964, -0.0777, -0.4232, -0.2348, +0.0104, -0.3079, +0.0108, -0.0532, -0.6523, -0.1098, +0.1428, +0.0241, -0.1377, -0.1040, -0.0198, -0.1276, -0.1225, +0.1877, +0.1434, -0.1603, +0.0083, +0.3261, -0.0649, +0.2380, +0.1431, +0.1992, +0.2852, +0.0863, +0.1383, +0.0683, -0.0237, -0.1648, -0.3055, +0.0780, -0.2690, -0.1308, +0.0550, -0.2885, -0.0357, +0.3337, +0.3640, +0.2330, -0.4088, -0.0555, +0.2426, -0.0360, -0.0471, +0.0268, +0.0698, -0.3097, +0.4724, +0.0377, +0.1186, -0.3599, -0.1465, -0.0735, +0.1470, +0.1003, +0.0560, +0.2386, -0.7249, +0.3320, -0.1094, -0.1790, -0.3375, -0.1804, +0.3751, +0.1747, -0.1219, -0.4064, +0.2044, -0.1771, -0.2139, +0.2752, -0.2412, +0.3879, -0.0443, -0.4725, +0.0672, +0.1978, +0.0040, +0.0679, -0.1308, -0.1091, -0.3235, -0.0660, -1.2227, -0.2144, +0.0729, +0.2776, +0.0983, +0.3612, +0.1038, -0.1449, -0.2453, -0.0479, +0.2660, +0.0042, +0.0880, +0.1908, -0.1619, +0.2752, -0.0579, +0.0556, -0.1338, +0.1464, -0.0785, +0.2846, +0.4422, +0.2484, -0.6025, -0.2763, +0.1162, -0.3478],
-[ -0.5782, +0.1906, +0.1734, +0.1883, -0.0293, -0.0389, +0.0819, +0.0158, +0.1459, -0.0329, +0.1881, +0.3707, +0.0956, -0.2496, -0.1015, +0.3248, +0.1064, -0.2893, +0.3955, +0.1916, +0.2692, +0.0676, +0.0055, -0.6039, -0.1335, -0.2131, +0.1014, -0.0254, -0.0912, -0.2667, +0.0564, -0.2423, +0.0568, +0.2143, -0.1274, +0.0890, -0.1465, +0.3149, -0.1007, +0.5162, +0.3685, +0.0812, -0.1759, -0.2218, +0.4711, -0.1292, -0.0327, -0.0697, +0.0674, -0.0355, -1.6970, -0.5040, +0.3186, +0.0522, +0.2239, +0.0747, +0.4768, -0.4289, -0.1898, +0.0650, +0.3639, +0.1651, +0.2521, -0.1041, -0.1097, -0.1902, -0.3308, -0.0783, +0.0330, +0.0435, -0.2222, -0.3439, +0.1648, +0.3389, -0.1015, +0.0497, -0.0452, +0.0318, +0.0559, -0.3934, +0.1315, +0.2891, -0.0126, -0.0007, +0.0235, -0.0232, -0.0145, -0.1985, -0.2792, -0.1734, -0.3868, +0.4253, -0.1242, -0.1719, -0.1692, -0.5732, +0.1520, +0.7987, +0.1763, -0.3345, -0.2268, -0.0233, -0.2024, -0.0249, +0.1214, -0.0592, -0.2435, +0.2254, -0.3216, +0.2705, -0.0196, +0.0999, +0.3110, -0.1762, -0.2190, -0.4913, -0.0483, +0.4600, -0.5647, +0.0644, -0.0517, -0.6167, -0.1300, -0.1070, -0.1628, -0.0141, -0.1285, +0.3464],
-[ +0.2531, -0.4246, -0.1124, -0.1414, +0.3469, +0.0590, +0.0769, +0.1326, -0.0672, -0.5040, +0.4048, -0.1567, +0.0505, -0.3964, +0.1137, +0.0952, +0.3906, +0.1974, -0.5820, -0.4967, +0.0089, -0.9033, +0.2035, +0.3123, -0.0154, -0.0289, -0.2539, -0.3530, +0.0047, +0.1289, -0.0604, +0.1756, -0.1851, -0.3747, -0.2330, +0.0155, -0.2719, +0.3565, -0.8995, -0.3202, -0.0988, -0.4006, -0.0811, -0.0058, +0.3941, -0.2473, -0.0218, -0.0270, -0.3174, -0.3637, -0.5382, +0.0212, -0.3645, -0.0166, +0.3558, -0.3776, -0.2406, -0.1041, -0.2648, +0.0408, +0.0477, -0.3856, +0.3001, -0.2375, +0.0915, -0.0683, +0.0510, +0.1140, +0.3605, +0.0479, -0.0216, +0.0533, +0.1311, +0.0990, -0.2098, +0.4808, -0.0483, -0.6076, -0.0011, -0.3198, -0.3740, +0.3489, -0.1652, -0.1550, -0.0346, -0.1286, -0.0016, -0.0003, -0.4651, -0.1696, -0.5290, +0.1247, -0.0264, -0.4317, -0.2631, -0.3566, -0.0829, +0.4125, +0.3511, +0.3472, +0.3246, -0.2954, +0.0431, +0.0219, +0.1410, +0.1440, +0.2573, -0.1697, -0.0990, -0.1925, -0.3016, -0.5556, -0.0015, -0.1362, +0.0310, -0.6040, -0.1562, -0.2446, -0.2332, +0.1920, +0.1550, +0.1036, -0.4364, -0.1748, -0.1564, -0.2098, -0.4382, +0.3966],
-[ +0.1260, +0.0490, +0.3787, -0.0375, -0.2074, +0.1874, +0.0317, -0.0706, -0.0983, +0.3232, -0.1024, +0.0829, +0.2997, -0.6455, +0.1067, -0.0603, -0.5746, -0.0119, +0.1894, +0.1563, -0.1189, -0.0454, +0.5147, +0.0360, -0.1992, -0.0254, +0.3549, +0.1757, -0.4647, -0.0077, -0.2720, -0.1760, -0.2262, -0.4833, -0.2636, +0.3875, +0.0347, +0.0979, +0.0910, -0.1617, +0.2177, -0.2526, -0.2857, +0.2492, -0.4129, +0.5601, -0.5158, +0.6762, -0.0035, -0.2667, -0.1909, -0.4599, +0.4615, -0.4111, +0.1033, +0.0490, -0.1589, +0.0755, -0.1904, +0.1806, +0.0493, -0.1964, -0.1795, +0.1061, +0.1791, +0.4933, -0.1962, -0.1606, -0.5060, +0.0979, +0.1747, +0.2053, +0.0114, -0.1039, +0.2534, -0.0638, -0.3248, +0.2861, -0.2703, +0.0699, -0.6233, -0.2882, +0.4067, -0.3037, -0.4889, -0.2084, +0.0349, -0.0843, +0.0359, -0.1602, -0.2522, -0.0374, +0.2539, -0.0456, +0.0193, -0.1338, +0.0877, +0.0100, -0.2885, -0.5033, -0.1374, +0.2941, -0.1094, -0.3068, +0.3346, -0.1147, -0.2984, +0.2426, -0.0239, -0.0587, -0.3346, -0.1018, +0.1709, -0.2609, +0.0585, -0.3472, -0.1020, -0.2216, +0.2505, +0.0018, -0.2663, +0.3529, +0.2675, +0.1840, -0.7017, -0.0175, +0.2269, -0.2479],
-[ +0.3040, +0.2737, -0.5742, -0.0408, +0.0635, -0.0384, -0.3790, -0.2584, -0.4556, +0.0124, -0.1558, -0.2336, -0.1191, -0.2965, -0.0478, -0.2460, -0.1696, -0.2144, -0.1847, -0.0240, -0.2321, +0.1156, +0.0593, -0.5346, -0.2271, +0.1473, +0.1119, -0.2017, +0.0852, -0.6201, +0.2337, +0.1348, +0.2248, -0.4217, +0.1638, -0.1542, +0.2474, +0.1655, -0.2747, -0.3630, -0.1479, +0.1020, +0.0481, +0.0818, -0.0606, -0.5730, -0.0580, +0.2307, +0.0102, +0.3657, -0.0025, +0.1403, +0.5203, -0.3502, -0.0716, -0.0956, +0.2056, +0.3511, -0.0761, -0.3415, -0.4086, -0.1799, +0.1528, -0.2285, +0.4164, -0.4004, +0.4581, +0.0228, +0.3447, -0.0499, +0.1209, +0.3148, +0.1120, +0.0279, -0.0009, -0.0518, -0.2637, +0.0562, -0.0797, -0.3466, -0.1235, +0.2356, -0.4437, -0.2633, -0.5231, +0.3174, +0.5079, -0.0572, -0.2430, +0.2296, +0.0292, +0.0220, +0.1550, -0.0500, -0.1876, -0.0993, -0.4246, +0.0450, -0.2272, +0.0427, -0.3256, +0.4864, +0.3597, +0.4831, +0.0694, +0.0089, +0.2025, -0.3835, +0.3883, +0.1819, -0.5876, +0.2974, -0.3375, -0.3222, +0.0057, -0.2190, -0.0620, +0.0231, -0.1838, -0.0152, +0.2449, -0.1569, -0.1453, -0.2986, -0.1157, -0.0309, +0.1738, -0.1929],
-[ +0.1540, +0.0907, +0.0518, -0.3168, +0.2437, -0.1048, +0.1006, -0.0696, -0.2625, -0.2643, -0.2835, -0.3560, +0.3865, +0.1339, -0.0532, -0.4447, -0.0998, -0.1350, -0.0618, -0.0229, +0.1311, -0.4932, +0.0372, -0.4844, -0.4117, +0.3505, +0.1197, +0.0140, +0.2804, -0.2457, +0.3772, -0.3713, +0.0690, -0.3633, +0.2494, +0.2031, +0.1649, -0.4295, +0.4660, -0.2606, -0.5435, -0.2758, -0.1259, -0.2487, +0.0974, +0.0217, -0.0250, +0.2417, +0.0858, +0.1764, +0.0492, +0.0453, +0.1658, -0.2055, +0.3024, +0.3197, -0.6662, +0.0136, -0.1004, -0.0527, -0.0925, +0.0632, -0.4504, -0.8565, +0.0316, -0.3916, +0.1335, -0.0838, -0.0710, -0.0795, -0.5285, +0.4056, +0.2705, +0.2677, +0.1918, -0.1448, -0.4974, -0.4795, -0.5206, -0.2320, +0.0128, +0.4737, +0.0136, +0.0774, +0.3074, +0.0766, -0.2378, +0.0485, +0.3838, -0.2468, -0.1098, -0.2152, +0.0587, -0.2543, +0.3835, -0.1868, +0.4615, -0.4107, +0.2520, +0.0725, +0.3860, +0.1150, -0.3168, +0.0991, +0.1227, +0.0676, -0.0073, +0.0185, +0.0667, -0.4643, +0.2600, -0.0383, -0.2920, +0.0836, -0.3683, +0.2688, +0.2978, -0.1071, -0.2877, -0.0936, -0.0374, +0.0552, -0.2354, -0.0068, -0.5642, -0.0270, +0.3623, -0.6247],
-[ -0.1794, -0.6469, -0.2005, -0.0931, +0.1129, +0.0514, -0.0467, +0.3075, -0.0633, -0.1825, +0.2719, -0.3011, +0.2022, +0.4541, +0.1091, +0.1069, -0.2843, -0.0083, -0.1186, +0.1789, +0.1923, +0.2096, +0.2436, +0.2531, -0.2846, +0.1484, +0.5951, -0.2624, +0.2010, +0.0453, -0.1421, +0.1439, +0.0311, +0.1574, -0.1362, +0.2092, -0.1079, +0.0097, +0.0032, -0.2158, -0.2078, -0.2905, +0.1767, -0.5548, +0.0682, +0.0185, -0.1438, -0.3615, +0.0546, +0.0569, -0.0391, -0.7231, -0.1122, -0.0317, +0.2239, +0.1588, +0.1139, +0.0698, -0.1196, -0.5234, -0.4367, -0.1172, +0.1110, -0.0475, -0.1380, +0.1305, -0.2057, -0.7198, +0.0661, -0.1014, +0.0224, +0.0770, -0.5482, +0.2791, +0.2226, -0.2000, -0.0676, -0.4551, +0.0832, -0.0944, +0.0012, -0.0266, +0.3025, +0.0629, -0.0212, +0.3119, -0.3967, -0.0072, +0.0522, -0.1675, +0.2270, -0.5319, +0.1066, -0.4644, +0.2507, -0.7823, +0.3102, +0.0146, +0.1905, -0.2320, +0.0155, -0.3714, -0.3955, +0.1832, -0.0578, -0.4893, +0.0741, -0.1344, -0.2543, +0.0362, -0.5893, -0.5407, -0.0138, -0.3061, -0.1880, -0.7254, +0.1985, +0.1975, +0.3145, +0.0314, -0.2741, +0.4982, -0.0651, +0.3584, +0.0948, +0.0382, -0.1478, -0.6292],
-[ +0.0108, +0.1363, -0.4603, -0.6946, +0.1555, -0.4470, -0.0054, -0.0728, +0.2475, -0.2475, +0.2982, -0.1344, +0.2278, +0.2052, -0.6269, -0.3164, -0.3965, -0.0100, +0.5359, -0.4468, +0.1302, -0.4960, -0.4109, +0.2271, -0.4049, +0.2888, +0.0563, +0.2683, -0.1955, +0.3281, -0.3322, -0.0276, +0.1287, +0.5680, +0.0449, +0.0856, +0.1424, +0.1702, -0.1806, +0.5474, +0.1719, -0.1926, -0.0079, -0.1671, +0.0840, -0.0674, -0.2571, -0.0109, -0.2267, +0.2417, +0.3584, +0.3720, -0.0394, -0.0459, -0.0924, -0.3447, +0.0089, -0.9740, +0.0036, -0.3574, -0.1076, -0.4138, +0.1189, -0.1872, +0.1986, +0.1237, +0.1391, +0.4177, -0.0582, -0.2411, -0.1025, -0.3558, +0.4156, -0.1450, +0.0069, -0.2615, +0.3515, -0.2806, +0.0704, -0.3630, +0.2234, -0.1900, -0.3181, -0.1556, +0.2019, -0.0437, -0.2472, -0.4759, -0.2476, -0.4334, +0.3947, +0.2041, +0.0127, +0.2119, -0.3167, +0.2268, -0.1841, +0.3159, -0.4010, -0.2133, -0.0276, -0.4166, -0.0255, -0.0258, -0.2008, -0.5324, -0.3827, -0.8062, +0.5195, -0.2211, +0.2540, +0.0670, +0.1731, +0.1564, +0.2965, -0.2518, +0.1688, +0.4063, +0.1802, +0.2394, -0.2798, -0.2258, +0.0013, +0.0755, +0.0758, +0.0380, -0.0515, +0.0203],
-[ +0.0682, +0.0607, -0.4312, -0.0837, -0.0390, -0.0473, +0.2011, +0.2264, +0.0435, +0.1802, +0.2948, +0.4862, -0.2232, +0.2120, +0.2287, +0.3143, +0.0856, -0.1173, +0.3023, -0.5732, -0.2188, -0.1307, -0.1044, +0.0311, +0.1745, -0.0431, -0.1285, +0.0134, -0.6088, -0.3926, +0.0858, -0.2324, +0.0178, -0.2543, +0.1034, -0.2823, +0.0999, -0.1172, +0.2767, +0.4904, -0.3913, +0.2075, +0.1072, +0.0606, -0.0847, +0.4113, +0.1683, +0.1330, +0.0234, -0.2255, -0.0991, +0.2487, -0.0258, +0.0851, -0.4635, -0.1941, +0.0976, +0.0097, +0.3667, -0.5655, +0.3308, +0.0844, -0.2296, +0.5016, +0.0795, +0.0289, -0.4559, +0.4661, -0.1285, +0.1738, -0.3641, +0.2920, +0.1332, +0.1255, +0.1899, +0.0596, +0.0581, +0.3625, +0.2658, +0.1000, -0.0309, +0.4054, -0.1588, -0.0548, -0.0737, -0.2622, +0.1349, +0.0257, -0.1382, -0.2838, +0.3152, +0.0558, +0.3262, -0.1312, -0.2371, -0.1248, +0.4027, +0.0974, -0.3818, -0.4092, -0.0118, -0.2306, +0.0839, -0.0772, +0.1386, +0.0937, -0.2221, +0.0781, +0.3098, +0.0550, +0.1964, -0.6213, +0.1870, +0.0641, +0.1922, +0.0954, -0.0066, +0.0672, +0.0384, -0.1116, -0.0447, -0.0057, +0.0436, -0.2353, +0.1362, +0.0894, -0.0830, +0.0130],
-[ +0.2553, +0.2339, +0.0967, +0.7129, -0.2857, -0.1087, +0.2100, -0.2756, -0.2708, -0.1745, +0.2868, -0.3398, -0.0809, -0.0359, +0.1840, -0.6609, +0.0503, -0.0303, -0.5335, +0.4147, +0.3857, +0.2817, -0.2322, +0.2738, -0.1197, -0.0957, +0.0977, +0.2833, -0.1044, +0.1534, +0.3056, -0.0947, -0.0552, -0.0028, -0.2728, -0.1350, +0.4430, +0.1648, -0.4715, +0.1161, -0.1061, +0.0075, -0.3901, -0.1448, -0.0034, +0.0361, +0.3333, +0.2831, +0.0583, -0.0816, -0.2184, +0.2277, +0.2847, -0.0651, -0.0631, -0.1300, -0.7026, +0.0612, +0.3413, +0.0853, -0.0591, -0.2359, -0.0052, +0.0620, +0.0290, +0.0936, -0.3844, -0.2343, -0.0891, +0.1331, +0.0239, +0.3608, -0.0228, +0.5134, +0.5165, -0.3740, -0.0318, +0.2402, -0.0454, +0.1330, -0.2295, -0.2050, +0.1477, -0.4862, -0.3914, +0.0083, -0.0326, -0.1580, +0.5535, +0.2553, -0.3117, -0.3831, -0.0202, +0.1943, -0.4166, +0.0539, -0.3034, -0.4123, +0.2323, +0.5206, -0.1463, +0.2259, -0.4273, +0.0657, -0.0571, +0.0722, -0.1226, -0.0538, -0.0069, -0.2261, -0.1497, -0.2016, +0.3124, -0.7570, +0.0104, +0.2903, +0.0640, +0.0830, -0.2558, -0.2965, +0.1475, +0.2381, -0.0430, +0.7055, +0.0051, -0.2930, +0.0725, +0.1653],
-[ +0.1017, -0.0169, +0.3433, -0.0247, +0.3333, +0.4303, -0.0808, +0.0873, -0.1596, +0.3726, -0.1868, +0.0866, -0.1615, +0.0522, +0.1393, -0.5026, +0.2647, -0.2591, -0.3463, +0.0496, +0.3718, -0.3523, -0.0447, +0.4346, -0.1340, +0.0819, -0.6307, -0.3348, -0.4477, +0.1867, -0.0589, +0.1986, +0.1826, +0.0722, +0.1900, -0.0628, -0.1909, -0.1866, +0.0619, +0.1771, -0.5174, +0.2349, +0.0508, -0.0999, +0.0179, -0.0232, +0.3815, -0.0653, +0.0794, +0.4170, -0.6661, +0.2416, -0.3119, +0.0735, -0.1154, -0.5300, -0.4085, -0.0628, -0.2777, +0.3121, +0.3427, +0.2223, -0.2194, +0.0163, +0.1581, -0.2255, +0.1695, +0.0007, -0.5535, -0.4634, -0.0713, +0.2734, +0.0629, +0.0570, +0.1100, -0.1807, -0.4638, +0.0892, -0.2699, -0.2704, +0.3017, +0.0141, -0.6492, +0.0556, +0.2206, -0.2548, +0.5063, +0.3248, +0.5339, +0.1342, -0.3769, -0.2276, +0.1179, -0.0696, -0.4020, +0.1742, -0.7131, -0.1189, +0.1510, +0.0971, +0.0307, -0.1883, +0.1087, +0.0189, +0.2568, -0.0677, +0.0837, +0.3688, -0.1358, -0.0299, +0.0662, -0.1572, -0.4141, -0.4710, +0.1579, +0.1420, +0.3501, -0.3492, -0.2122, +0.0453, -0.1907, +0.1908, +0.1346, -0.1349, -0.2534, +0.1119, +0.2728, -0.2293],
-[ +0.2693, -0.1020, -0.3455, +0.0030, -0.3548, +0.1798, +0.4188, +0.0925, -0.0413, +0.4003, +0.1355, +0.1477, +0.2107, +0.1396, +0.0675, -0.1143, +0.2218, +0.1212, +0.1667, +0.5631, -0.1789, +0.2033, -0.0790, -0.1211, +0.2683, +0.1936, +0.0309, +0.0716, -0.0439, +0.1382, +0.2220, -0.3047, -0.0533, +0.0854, +0.0078, +0.2174, +0.6549, +0.2140, -0.0696, +0.1489, +0.1232, +0.0858, -0.6816, -0.1291, -0.5285, +0.3526, +0.0384, +0.2509, +0.2088, -0.2426, +0.1777, +0.1761, +0.1864, -0.0985, +0.2616, -0.1704, -0.0899, +0.0956, +0.3256, -0.1290, +0.0407, +0.1948, -0.2022, +0.2970, +0.1606, +0.3364, +0.2783, +0.5472, -0.2109, +0.1295, -0.0814, -0.1079, +0.1947, -0.2231, -0.1824, +0.2293, -0.1339, -0.3247, +0.1065, +0.1698, -0.3407, +0.3650, +0.1766, -0.2943, -0.4004, +0.0150, +0.1015, -0.0351, -0.0017, +0.0853, -0.0862, +0.2807, +0.1220, +0.4419, -0.0513, +0.1721, +0.1401, +0.4210, -0.1857, -0.0636, +0.0270, -0.2352, +0.0363, -0.0249, -0.0597, +0.2238, -0.3294, +0.0218, -0.0032, -0.0701, -0.1210, +0.1158, -0.0764, +0.0413, +0.0088, +0.1163, -0.0208, -0.0476, -0.0188, +0.1646, -0.2721, -0.3308, -0.1978, +0.0704, -0.0254, -0.5013, -0.2004, +0.1996],
-[ +0.2633, -0.1499, +0.0166, -0.5333, +0.1778, +0.4300, +0.1187, +0.0878, +0.4357, -0.1351, -0.2278, +0.2826, +0.4363, +0.1333, -0.0353, -0.3369, -0.1327, +0.3520, -0.2643, -0.1522, -0.2161, +0.1890, -0.2408, +0.2558, -0.1769, +0.1612, +0.2292, +0.1531, -0.2258, +0.2110, -0.4630, -0.0362, -0.1990, -0.1168, +0.0159, -0.4588, -0.0290, +0.1523, -0.1201, -0.0006, +0.1122, +0.0192, +0.4572, +0.0165, -0.4139, +0.2357, +0.2230, +0.0980, -0.0781, +0.1679, -0.2461, +0.2794, +0.2259, -0.2183, +0.0412, -0.1722, -0.2792, +0.2898, +0.2379, -0.0363, -0.2130, -0.1842, +0.1052, -0.0095, -0.2856, +0.0777, +0.0496, +0.0280, -0.2245, -0.0076, -0.0632, -0.0875, -0.0481, -0.5607, +0.0340, -0.1438, -0.0158, -0.1934, +0.2243, -0.2398, -0.0403, -0.6139, -0.4362, -0.0030, -0.2919, -0.0780, -0.3351, -0.0650, -0.0780, -0.2431, -0.3703, -0.4119, +0.1445, +0.0133, +0.0393, -0.3822, +0.1098, +0.1970, +0.0569, -0.5413, -0.1958, +0.1032, +0.0823, +0.1366, -0.0495, -0.1210, -0.1508, -0.2696, -0.0934, +0.0480, +0.2404, -0.1181, +0.0223, -0.4104, -0.4513, +0.0789, +0.1213, -0.0352, -0.1675, -0.2540, -0.0869, +0.0362, -0.2360, -0.0736, +0.3257, +0.0739, -0.0038, +0.0745],
-[ -0.1152, +0.2965, -0.3136, -0.1767, +0.0926, -0.5773, +0.0044, +0.1510, -0.1418, -0.2058, +0.0223, -0.3192, -0.2464, -0.3721, +0.0900, +0.0702, -0.0699, +0.0563, -0.5249, -0.1389, -0.0329, -0.1351, +0.0523, +0.3451, -0.0718, -0.3792, +0.0844, +0.0541, -0.4429, -0.2259, -0.2771, +0.0803, +0.1938, -0.0576, +0.2719, -0.3080, +0.1831, -0.1929, +0.0382, -0.0297, +0.0554, -0.0088, +0.0183, -0.0070, -0.0396, -0.5188, +0.0332, +0.0408, -0.2020, -0.0902, -0.1569, +0.3531, +0.1486, +0.1994, -0.2587, +0.3177, +0.2230, +0.3852, +0.0526, +0.0521, +0.2908, -0.4346, +0.1264, -0.3982, +0.0842, -0.6006, +0.6465, -0.3693, -0.1780, -0.1894, +0.3467, -0.0559, +0.0476, -0.0536, +0.5247, -0.0387, -0.4233, +0.4379, -0.5253, -0.1410, -0.1401, -0.2706, -0.0231, -0.0002, +0.3057, -0.1973, +0.2027, +0.1584, +0.1657, +0.2245, +0.1908, -0.2495, -0.0467, +0.3324, -0.0309, +0.2062, +0.1451, +0.1661, -0.7140, +0.5208, -0.1006, +0.1176, -0.0063, +0.0877, -0.1852, +0.2412, +0.2701, +0.2423, -0.0322, +0.0373, +0.2032, -0.0462, +0.1739, -0.2051, +0.4769, +0.2840, +0.0295, -0.1836, +0.1977, +0.1941, +0.0022, -0.1481, -0.0497, -0.0241, +0.4881, +0.1507, +0.0563, +0.5255],
-[ +0.1783, -0.1203, -0.2837, -0.0693, -0.0784, -0.5550, -0.2614, +0.0294, -0.2250, -0.6219, +0.0918, -0.1786, +0.0339, +0.1697, +0.4793, -0.1741, +0.2219, -0.1546, -0.1324, -0.1727, -0.4113, -0.1253, -0.1133, +0.2454, -0.1448, +0.1979, -0.3952, +0.1347, -0.1608, -0.2029, -0.2363, +0.0604, -0.1048, +0.1909, +0.4279, -0.5313, -0.5097, +0.1291, -0.1537, +0.2515, +0.0301, -0.1484, +0.2159, +0.0742, -0.0764, +0.3921, -0.5697, -0.0334, +0.0640, +0.1345, -0.0446, -0.2890, -0.3501, +0.3603, -0.4679, +0.1560, -0.4771, -0.1902, -0.2499, -0.7031, +0.2479, +0.2047, +0.1851, -0.2436, -0.1453, -0.0497, +0.0418, -0.4254, +0.4114, +0.2546, +0.5168, +0.6939, -0.2599, -0.3046, -0.4814, +0.1555, -0.1132, -0.0019, -0.1333, +0.3497, -0.4754, +0.0764, -0.0157, +0.2168, -0.1795, -0.5074, +0.3335, +0.1166, +0.4986, +0.3988, +0.1274, -0.5790, -0.2656, -0.5017, +0.2233, +0.0550, +0.0143, -0.2615, -0.4955, +0.1764, -0.2795, -0.4044, +0.2753, +0.2312, +0.1464, -0.0805, +0.5014, -0.1711, -0.6885, -0.5679, +0.3286, -0.2191, -0.0982, +0.3592, +0.2221, +0.0310, -0.0824, -0.3813, -0.0662, -0.7379, -0.2829, -0.0762, -0.2882, -0.4549, -0.1073, -0.1336, -0.1835, -0.1327],
-[ +0.4517, +0.0658, -0.3340, +0.2966, -0.1853, -0.0043, -0.3360, +0.0280, -0.2086, -0.0996, +0.0273, -0.2293, -0.0638, -0.2680, -0.1610, +0.3207, +0.0587, +0.1650, -0.1426, -0.2957, +0.3290, -0.1567, -0.5362, +0.1573, -0.0615, -0.4283, -0.2864, -0.0530, +0.0971, -0.0878, -0.0782, -0.0000, +0.1582, +0.6758, +0.3259, +0.1928, -0.0288, -0.1770, +0.0926, -0.0870, +0.0457, -0.3155, -0.1675, -0.4340, +0.1712, +0.0053, +0.0989, +0.1947, -0.0384, -0.0906, -0.2912, +0.1230, -0.3258, -0.2202, -0.4676, +0.1021, +0.0618, -0.0397, +0.0854, -0.1780, +0.1357, +0.0466, +0.0795, -0.2550, -0.2503, +0.1017, -0.1647, -0.2143, -0.1276, +0.0739, +0.1593, -0.1818, +0.1127, -0.0927, -0.8645, +0.0464, +0.2128, -0.1659, +0.0030, -0.0731, +0.0294, +0.0992, -0.0481, +0.0158, -0.3424, -0.2776, +0.2169, -0.1007, +0.0535, +0.0958, +0.1272, -0.3455, +0.0960, +0.2129, +0.1420, +0.1840, +0.3833, -0.4782, -0.0468, +0.1290, -0.1255, -0.2247, -0.0768, -0.0179, +0.0375, -0.0087, -0.0451, +0.1420, -0.0974, -0.0792, +0.0055, +0.3840, -0.2168, +0.0080, +0.4134, +0.2009, -0.3005, +0.3029, -0.1305, -0.2074, -0.1235, +0.1048, +0.3730, +0.0040, -0.1392, -0.2744, +0.0893, +0.0640],
-[ -0.2067, +0.2301, -0.1646, -0.2645, +0.2361, +0.1113, +0.0502, -0.0047, +0.0101, -0.3107, -0.2395, -0.4054, -0.3047, -0.1105, +0.0458, -0.6247, +0.2991, +0.1149, +0.2152, +0.0058, -0.1267, -0.1580, +0.2562, -0.1681, -0.4301, -0.5288, +0.1117, +0.1572, -0.0636, -0.0258, +0.0505, -0.6769, -0.4278, -0.1437, -0.1065, -0.0424, +0.2820, -0.1881, +0.0922, +0.2906, +0.1197, +0.1735, +0.2757, -0.0850, -0.5826, +0.0295, -0.2369, -0.0866, -0.0146, -0.1379, -0.1154, +0.2802, +0.1067, -0.2483, +0.0971, +0.0321, +0.0438, -0.0545, +0.1608, -0.6518, +0.0127, -0.0457, -0.2670, +0.2368, +0.0150, +0.2014, -0.3092, +0.0049, -0.0913, -0.0520, +0.0037, -0.0204, -0.2846, -0.0804, +0.3840, +0.3022, +0.3030, -0.0264, +0.3104, -0.2525, -0.4555, +0.0665, -0.5402, +0.1549, -0.2790, -0.3014, +0.1059, -0.0015, +0.0155, -0.6908, +0.3992, +0.1417, -0.2429, +0.0394, +0.1702, -0.0042, -0.3149, +0.3281, +0.0022, +0.2559, -0.0678, +0.7093, -0.5322, -0.0675, -0.3888, -0.3135, -0.0432, +0.5027, +0.0406, -0.0088, +0.3937, +0.3382, -0.1515, +0.1129, -0.2990, +0.0603, +0.0857, +0.0208, -0.5491, +0.0658, -0.3145, +0.1052, +0.2350, -0.1393, -0.0873, +0.1726, -0.0157, -0.0962],
-[ -0.3887, -0.3419, -0.2082, -0.3848, -0.1498, +0.2693, -0.1537, +0.2435, +0.0828, +0.3029, -0.3123, +0.1239, +0.2061, -0.2443, -0.0488, -0.0663, -0.2655, -0.0834, -0.2414, -0.0122, +0.0514, -0.7199, -0.4183, +0.2118, +0.3534, -0.2131, -0.3576, -0.1144, -0.0576, +0.0392, -0.1840, +0.2215, -0.5385, -0.2425, -0.0777, +0.0208, -0.1796, +0.1108, +0.1878, +0.1009, +0.1568, -0.1247, -0.1476, +0.1501, -0.2837, -0.0996, +0.2396, -0.0442, +0.1063, +0.2721, -0.1514, +0.2922, -0.1659, -0.3875, +0.0173, +0.3768, -0.0494, -0.3885, +0.1457, -0.2002, +0.3482, -0.5610, +0.1872, +0.0486, +0.3783, -0.1147, -0.0878, -0.0411, -0.0771, -0.0347, +0.0312, +0.0703, -0.3597, -0.2080, +0.1644, -0.0097, +0.4533, -0.0798, +0.1823, +0.0052, -0.0697, -0.3489, +0.1621, -0.0199, -0.2716, -0.1253, +0.0369, +0.0719, -0.0387, -0.1067, +0.0970, +0.0786, -0.5694, +0.2189, +0.0160, +0.1855, -0.0319, -0.1075, -0.0951, +0.1119, -0.2590, +0.3577, -0.1265, -0.2266, +0.1194, +0.2802, +0.2770, +0.0235, +0.2434, +0.3130, +0.1270, -0.4183, +0.1559, +0.2719, -0.3041, -0.2625, +0.0789, +0.0228, -0.3127, +0.2764, -0.0512, +0.1628, -0.0959, +0.1506, -0.1898, +0.1287, +0.1856, -0.0313],
-[ +0.2018, +0.2554, -0.0049, -0.3112, -0.2239, -0.3388, +0.3906, +0.1859, -0.1265, +0.3720, -0.1896, +0.0098, +0.0376, +0.2438, +0.1950, +0.0796, -0.0422, -0.0262, -0.2366, +0.1564, +0.2580, +0.1235, -0.3529, -0.5791, -0.0359, -0.3110, -0.2399, +0.4439, +0.0040, +0.1688, +0.1939, -0.2981, +0.0870, +0.4176, -0.3759, -0.2486, +0.1234, +0.1051, +0.0157, -0.4434, -0.0287, +0.4169, +0.0161, -0.2643, +0.4733, -0.1172, +0.0843, -0.2524, -0.0453, -0.0913, -0.1426, -0.3986, -0.0733, +0.0797, +0.1183, -0.1853, -0.2104, +0.0994, -0.3430, +0.2793, -0.6255, +0.3737, +0.2317, -0.1720, +0.1032, +0.1511, -0.2115, +0.5591, -0.0244, -0.0046, -0.1598, -0.1281, -0.0300, +0.2074, -0.0218, +0.1136, +0.0940, +0.0987, -0.5553, -0.0394, -0.0461, -0.1228, +0.1672, +0.0195, +0.3806, +0.2578, -0.4602, +0.0679, +0.0663, +0.0252, -0.0842, -0.0321, -0.2086, +0.0606, -0.2867, -0.1604, -0.2171, +0.4462, -0.3729, -0.7239, +0.1828, -0.0708, +0.0649, -0.3095, +0.4024, +0.0170, -0.0434, -0.1998, +0.2228, +0.5068, -0.0601, -0.3232, -0.1708, -0.3354, -0.1161, -0.4872, +0.0997, +0.3460, -0.0601, -0.3048, +0.1425, -0.3348, -0.4696, +0.0979, +0.0794, +0.1274, +0.2205, +0.1029],
-[ +0.2202, -0.0473, -0.0483, +0.0908, +0.2507, +0.1783, -0.0428, -0.0113, -0.0889, -0.2476, +0.1438, -0.2904, +0.1929, -0.5124, -0.1411, +0.0491, +0.2510, +0.5334, -0.0648, +0.3099, +0.0367, +0.2053, -0.0321, +0.0069, +0.3099, -0.0422, -0.7279, +0.3423, -0.1532, +0.0617, -0.1533, -0.0856, +0.0292, +0.0060, -0.1155, -0.3122, -0.3182, +0.0682, +0.1417, +0.3202, +0.2111, +0.4028, +0.0776, -0.1851, +0.0884, +0.1650, +0.0792, -0.5007, +0.4097, -0.0505, -0.5315, -0.8284, +0.2097, +0.3150, -0.0899, +0.5223, +0.3590, +0.1334, -0.2466, -0.4766, +0.1727, -0.0124, -0.1536, -0.3359, -0.2406, -0.2959, +0.3427, -0.2860, +0.0579, -0.1943, +0.1129, -0.2535, -0.1982, -0.0823, -0.3116, +0.0267, -0.0368, -0.8230, -0.0157, -0.0027, -0.2506, +0.0386, -0.1757, +0.1732, +0.1558, -0.4040, +0.2373, -0.0159, -0.0559, -0.4249, +0.1963, +0.0035, +0.2762, +0.1329, -0.0338, -0.3528, +0.4236, +0.3524, +0.3066, -0.1558, +0.4670, +0.0273, +0.0020, -0.1610, +0.0273, +0.2771, -0.1472, -0.1650, +0.1146, -0.0556, +0.4777, +0.2354, -0.0608, -0.0926, -0.3920, +0.1041, +0.2493, -0.4355, -0.0731, +0.2479, -0.7999, -0.1610, +0.2666, +0.2134, +0.1338, +0.0135, -0.6830, -0.1893],
-[ -0.1152, +0.1442, -0.0220, -0.7058, -0.3012, -0.0015, -0.2417, -0.3607, -0.1625, +0.0061, -0.0695, -0.2861, -0.0088, +0.0729, +0.3041, +0.3543, +0.2796, +0.0359, +0.0541, -0.5513, +0.0041, -0.0687, -0.2319, +0.4381, -0.2315, -0.4676, -0.3778, +0.2826, -0.2813, -0.5964, +0.5921, -0.0691, -0.0296, +0.4393, +0.1530, +0.2270, -0.0868, -0.5361, -0.0368, +0.3822, +0.1015, +0.3149, -0.2556, +0.0701, +0.1325, +0.1867, -0.1930, +0.2955, +0.1443, +0.0907, -0.7181, -0.1485, -0.9969, +0.2466, -0.0384, +0.1874, +0.1444, -0.3377, +0.0616, +0.2895, -0.1200, +0.0314, +0.4350, +0.0230, +0.1443, -0.3053, -0.0222, -0.0372, +0.2736, +0.1352, -0.0322, +0.2443, +0.2799, -0.1980, +0.1430, -0.4997, +0.5547, +0.0101, -0.4364, +0.1719, +0.2264, +0.2338, -0.1936, -0.3765, -0.4489, -0.4625, -0.3184, -0.0327, -0.1858, -0.1664, -0.0074, +0.2940, +0.0657, +0.0209, -0.3291, -0.0707, -0.1251, -0.0179, -1.4153, +0.2057, -0.1318, -0.0649, -0.0746, +0.1426, -0.0178, -0.3179, +0.0938, -0.1089, -0.1703, -0.0076, +0.1258, -0.3994, -0.3611, +0.1069, +0.4496, +0.2736, -0.0324, +0.0022, -0.5305, +0.0004, -0.3541, -0.2936, -0.4940, +0.3456, +0.2212, -0.0787, -0.4951, +0.1607],
-[ +0.1808, +0.1338, +0.2585, -0.4397, +0.0622, -0.1769, -0.0225, -0.0177, +0.0734, +0.0638, -0.1966, -0.5875, -0.3866, +0.3552, +0.0917, -0.2711, +0.0791, -0.0989, -0.0565, -0.1037, +0.4928, -0.3035, -0.0973, +0.0508, +0.3004, -0.1029, -0.4030, +0.0268, +0.0685, +0.1040, -0.4739, -0.0076, -0.5081, +0.1892, -0.2594, +0.6059, -0.2552, -0.1620, -0.0864, +0.1521, +0.1867, +0.3853, +0.3173, +0.0243, -0.2726, -0.3549, -0.1538, +0.1737, +0.1056, +0.3319, -0.1266, +0.1966, -0.3478, +0.1736, -0.6014, -0.2518, +0.4000, +0.3501, +0.4711, +0.3372, +0.1510, +0.4035, +0.1676, -0.3453, -0.0087, -0.2413, +0.5548, -0.6989, -0.3707, +0.0316, +0.1842, -0.0989, -0.3163, -0.1315, +0.4837, -0.2424, +0.2195, -0.0846, +0.0250, -0.3628, -0.0584, -0.5256, -0.0596, +0.3859, +0.1934, -0.0144, +0.1942, -0.1791, +0.3130, +0.7044, +0.1126, -0.3029, +0.2233, -0.0153, -0.0767, -0.2393, +0.0245, +0.1158, +0.0386, +0.5383, -0.0311, +0.0613, +0.2475, +0.1752, +0.0003, -0.1864, +0.1285, +0.2277, -0.2469, -0.1582, -0.2115, +0.2388, +0.0677, -0.0029, -0.0497, +0.3063, -0.1699, +0.3031, -0.3998, -0.0385, -0.0300, -0.0523, +0.4780, +0.2601, +0.5331, -0.0449, +0.1596, -0.1041],
-[ +0.2238, +0.1284, -0.1701, +0.1403, -0.0135, +0.2474, +0.0308, +0.2728, -0.1048, +0.1523, -0.0382, +0.4176, -0.3344, +0.2705, +0.3271, +0.7143, -0.4450, +0.4092, +0.1036, -0.4947, +0.2866, -0.5911, -0.1048, +0.0398, +0.2436, +0.1804, -0.2068, +0.1557, -0.4103, -0.0793, +0.2855, -0.0640, -0.1582, -0.1056, -0.2873, +0.7593, -0.4392, -0.2479, +0.1564, -0.2532, -0.6649, -0.2479, -0.7535, -0.0447, -0.2502, -0.2208, -0.0584, -0.5366, -0.2103, +0.0147, +0.0866, +0.6192, -0.1458, +0.0391, -0.0438, -0.2746, +0.2588, -0.1434, +0.3173, -0.0749, -0.5273, +0.1983, -0.1958, -0.2106, +0.0725, +0.1267, -0.4564, +0.0371, +0.2196, -0.0905, +0.0582, -0.0972, -0.1200, +0.0785, +0.0373, +0.1558, -0.1794, -0.0782, +0.0833, -0.2928, +0.2547, -0.3066, +0.3207, -0.0713, +0.1041, +0.0323, -0.3902, +0.1083, -0.1922, +0.0627, +0.2882, +0.1281, -0.6859, +0.3662, -0.3920, -0.0183, -0.5185, -0.3081, -0.3686, +0.0500, +0.0318, -0.1623, -0.2901, +0.1586, +0.0187, -0.4677, -0.2002, -0.3237, -0.0840, +0.1040, +0.0714, +0.2835, -0.1764, -0.1995, +0.2796, -0.0560, +0.0650, -0.3539, +0.1896, +0.3324, -0.3503, -0.2889, -0.0343, +0.3707, -0.0376, +0.2383, -0.3181, +0.3099],
-[ -0.1127, -0.3128, +0.0028, +0.1006, -0.1284, -0.0052, +0.3716, +0.0876, +0.3156, -0.0414, -0.0690, -0.0513, +0.1852, +0.0597, -0.0213, +0.0427, -0.5044, +0.2126, -0.2119, -0.1303, -0.4426, +0.3006, +0.3830, +0.1086, -0.1569, -0.1747, -0.3161, -0.2888, +0.2725, +0.2182, -0.4447, -0.6314, +0.0895, -0.0459, -0.4898, -0.0969, -0.0063, +0.5000, +0.0557, -0.0516, -0.1925, -0.0804, +0.2792, -0.0105, -0.1772, +0.2723, -0.2916, -0.1807, -0.0976, +0.3596, -0.5005, +0.0279, +0.2975, -0.3719, +0.1297, -0.3601, +0.0749, -0.0975, +0.4026, -0.2229, -0.0846, +0.2353, -0.1063, +0.0776, -0.1897, -0.0136, -0.1587, -0.3237, -0.2042, +0.2351, +0.0336, -0.1441, -0.0715, +0.1958, -0.0658, +0.1386, +0.1308, +0.1369, +0.0607, -0.1522, +0.0956, -0.0699, +0.3380, -0.4043, -0.0375, +0.1118, -0.6505, -0.1881, -0.3635, +0.3707, +0.2681, -0.0927, -0.2507, +0.0609, +0.0271, +0.1656, +0.0221, -0.5332, +0.0420, +0.0947, +0.0090, -0.1108, +0.1345, +0.2935, -0.2839, +0.2581, +0.2247, -0.1338, -0.0634, +0.1884, -0.1076, -0.0599, -0.0024, -0.1269, +0.1119, -0.3119, -0.1935, -0.2787, -0.0870, -0.5573, -0.1073, -0.0517, -0.1105, -0.3601, +0.4294, +0.1922, -0.5099, +0.1859],
-[ +0.4151, +0.0486, -0.2621, -0.1066, -0.4595, +0.2190, +0.0539, +0.2084, +0.0236, -0.0017, -0.0462, -0.1106, -0.6621, -0.4632, -0.1909, -0.1931, -0.2267, -0.1587, -0.2585, +0.1337, +0.2305, +0.5494, +0.3112, -0.2645, -0.0419, -0.5014, +0.0660, -0.4007, -0.0919, +0.1091, +0.0193, +0.4635, -0.2758, +0.1595, -0.1809, -0.2396, +0.2757, -0.0915, -0.3786, -0.2914, -0.0223, -0.1506, +0.3220, -0.4689, +0.0942, +0.1772, +0.2289, +0.0095, -0.1261, +0.0043, +0.2686, +0.3630, -0.5158, +0.2660, +0.2270, -0.1899, -0.3355, +0.1850, -0.0454, -0.1173, -0.4624, +0.2398, -0.0933, +0.2974, +0.3400, +0.0097, +0.0780, -0.0762, -0.0705, -0.3773, -0.3827, -0.1402, +0.2830, +0.0033, +0.0435, -0.1584, -0.0909, -0.2032, -0.5186, +0.3478, +0.1443, +0.1681, -0.1531, +0.5813, -0.1559, -0.3443, -0.1627, -0.0723, -0.0982, +0.0982, +0.1497, -0.1783, +0.1030, -0.1996, -0.0243, -0.0758, -0.6743, +0.3288, -0.1346, +0.0569, +0.0086, -0.5111, -0.0393, +0.1989, +0.1777, -0.0203, +0.0408, +0.1340, -0.2372, -0.1229, +0.3350, +0.1631, +0.2887, +0.1170, -0.2061, -0.4772, +0.1707, -0.1617, +0.1395, -0.2869, -0.0917, +0.0842, +0.2473, -0.0274, +0.1507, -0.1940, +0.0308, +0.2831],
-[ +0.0270, +0.2691, -0.3350, -0.1182, +0.0450, +0.3980, -0.1312, +0.1354, -0.1923, +0.2128, +0.5420, -0.2478, +0.0921, +0.1335, +0.4008, -0.0317, -0.4794, +0.0225, -0.2191, -0.0190, +0.0188, -0.5584, +0.3829, +0.2571, +0.0469, +0.2138, -0.2720, +0.4466, -0.0466, -0.1490, +0.2479, -0.3620, -0.5180, -0.1234, -0.1863, -0.1151, -0.1035, +0.2302, -0.0834, +0.1094, -0.3245, +0.3910, -0.0073, +0.2668, -0.3793, -0.2312, +0.3521, -0.1891, -0.0857, +0.2789, -0.3569, +0.0599, +0.0285, +0.4213, +0.1397, +0.1513, -0.2065, -0.0173, -0.0085, +0.1375, +0.0513, -0.1107, -0.3131, +0.0857, -0.5247, -0.1168, -0.1839, +0.4625, -0.1646, -0.4847, +0.0265, +0.0781, -0.1780, +0.8386, -0.0829, +0.0929, -0.2670, -0.0063, -0.0791, -0.6327, -0.7086, -0.1977, -0.1171, -0.0106, +0.6187, -0.2497, +0.0773, +0.2595, +0.1312, +0.1604, +0.0626, -0.2817, +0.3393, -0.1228, -0.1665, -0.0861, +0.1366, -0.1221, -0.1432, -0.5733, +0.2195, -0.0654, -0.0690, -0.0420, -0.2693, +0.1086, +0.1585, -0.5603, +0.1529, -0.2381, +0.1962, -0.1147, +0.0971, +0.1910, +0.1819, +0.2031, +0.0518, -0.0561, +0.6765, -0.2260, +0.1227, +0.2146, +0.2084, -0.0776, +0.0527, +0.0995, -0.2007, -0.1233],
-[ -0.2873, -0.1797, +0.0470, +0.1901, +0.1030, +0.0715, -0.0712, -0.0926, +0.0925, -0.3459, -0.3944, -0.2083, -0.0272, -0.2135, +0.0001, -0.4917, -0.1781, +0.1894, -0.2399, -0.0392, +0.5503, +0.0293, +0.1843, +0.0312, -0.2312, -0.3056, +0.1651, +0.2846, +0.1764, -0.0142, -0.3850, -0.5774, -0.0760, -0.0523, -0.6263, +0.3228, +0.4584, +0.1473, +0.5229, -0.3264, -0.0887, +0.3426, -0.1249, +0.1273, +0.0110, +0.0840, +0.0106, -0.1928, -0.0661, -0.0125, -0.1421, -0.2616, -0.2185, +0.0325, -0.2325, +0.1996, +0.1432, -0.6655, -0.3260, -0.8642, -0.1621, -0.5049, +0.5077, -0.8273, +0.4845, -0.1448, +0.0955, -0.3162, +0.1370, +0.2197, +0.0644, +0.1087, -0.4276, -0.3397, -0.0150, -0.1073, -0.9972, +0.3535, -0.6538, -0.1315, +0.1838, -0.2415, -0.3531, -0.3833, +0.2568, -0.3342, +0.0648, +0.0233, -0.3272, +0.2680, +0.3175, +0.1118, +0.3420, +0.1392, +0.4184, +0.0296, -0.4763, -0.0176, -0.0144, -0.5814, -0.3503, +0.3994, +0.2795, +0.3018, +0.0602, -0.0197, -0.2284, +0.0503, -0.5084, +0.3896, -0.0316, -0.2142, -0.1859, +0.5103, -0.0580, -0.4366, -0.3467, +0.2605, -0.1273, -0.2157, -0.1276, +0.0491, -0.0039, -0.0419, -0.3699, +0.4374, +0.1162, -0.6341],
-[ +0.0881, -0.0428, -0.3523, +0.2652, -0.5092, -0.1459, +0.0844, -0.0671, -0.2616, +0.1079, +0.0182, -0.0213, -0.1061, +0.2430, +0.1738, +0.1872, -0.1859, +0.0672, -0.3635, -0.3092, +0.0467, -0.1636, +0.0847, -0.4381, -0.1506, -0.1320, -0.0478, -0.1204, +0.0794, -0.0013, +0.0643, +0.4463, -0.5180, +0.2987, +0.2615, +0.2146, -0.1057, +0.0422, +0.2968, +0.1310, -0.2525, -0.1665, +0.2121, -0.4593, +0.4054, +0.1538, -0.0042, +0.0514, -0.2158, +0.0907, +0.1021, -0.4739, +0.0356, +0.0105, -0.0032, -0.6401, +0.1607, -0.5373, -0.5146, +0.1560, -0.1215, +0.0354, +0.4660, -0.3790, +0.2760, +0.0380, -0.2825, +0.3231, -0.1135, -0.2536, +0.0494, +0.1541, -0.0165, +0.1671, -0.0775, +0.5874, -0.1627, -0.1555, +0.4098, -0.1272, -0.1850, +0.1632, +0.0497, -0.0743, -0.0829, -0.1529, -0.1856, -0.4889, -0.0907, -0.0640, +0.2289, +0.5469, +0.0572, -0.0645, +0.1524, +0.3242, -0.2129, -0.1097, +0.1131, -0.1921, -0.2634, -0.2343, -0.0592, +0.1269, -0.1817, +0.3688, +0.0245, -0.3743, +0.1940, +0.1823, -0.2238, -0.0054, +0.0251, +0.0565, +0.3600, -0.1530, +0.2105, +0.3182, -0.2694, -0.1781, -0.1540, +0.0377, -0.2013, +0.1521, -0.3718, +0.2454, -0.0135, -0.0690],
-[ -0.0353, +0.1273, +0.1086, +0.3101, -0.5079, -0.4920, +0.3528, -1.0276, -0.1074, -0.0415, -0.0216, +0.2085, +0.3988, -0.1835, -0.5477, -0.1663, -0.2457, +0.1004, +0.0504, +0.3388, -0.1777, +0.1018, +0.0198, -0.0650, +0.0922, -0.0420, -0.1174, -0.2334, +0.2075, -0.0436, -0.0588, +0.2837, +0.2075, -0.0769, -0.0617, -0.0373, -0.1305, -0.2308, -0.0265, +0.4699, +0.5611, -0.2701, +0.2300, +0.1910, +0.2018, +0.1750, -0.4274, +0.3083, +0.2516, -0.3755, +0.6978, +0.4048, -0.0261, +0.2413, +0.2155, +0.2323, +0.1521, -0.0571, +0.2908, +0.3256, +0.1790, +0.3086, -0.2499, -0.1769, +0.2698, +0.1223, +0.0859, +0.2772, +0.0137, -0.3890, +0.0773, -0.2195, +0.0124, +0.0221, -0.6253, +0.2795, +0.1522, +0.1918, -0.4858, +0.6520, -0.0586, -0.3499, +0.0054, -0.2153, +0.2401, +0.2565, -0.0043, -0.0296, -0.2459, +0.3949, +0.2121, +0.1500, -0.2814, -0.2656, +0.1898, +0.3232, -0.1631, -0.0039, -0.3462, +0.0166, +0.1790, -0.0065, -0.0522, -0.1100, +0.1022, -0.1440, +0.2267, +0.0971, +0.3084, -0.4332, +0.2683, +0.0773, +0.0125, -0.1468, -0.1822, -0.4774, -0.2671, -0.1772, +0.0039, +0.0833, -0.1179, +0.0099, +0.0683, +0.0194, -0.5451, +0.0219, -0.0482, +0.0236],
-[ -0.0090, +0.0548, +0.0090, +0.3092, +0.0976, -0.0626, +0.0472, +0.1432, -0.0912, +0.1453, +0.0198, -0.0755, -0.0584, +0.2909, -0.1208, -0.3472, +0.1000, -0.1955, -0.4332, +0.1317, -0.2439, -0.1974, +0.0393, -0.1747, -0.0932, -0.2908, -0.4298, -0.6810, +0.1605, -0.0770, -0.0548, -0.1976, +0.3308, -0.1112, +0.2167, -0.8931, +0.2516, -0.0820, +0.2553, +0.1484, -0.4512, -0.3038, -0.1564, -0.1418, -0.2413, -0.2708, +0.1223, +0.4261, +0.1597, +0.2612, +0.0826, -0.1703, -0.1501, +0.1301, +0.1994, +0.0556, +0.3606, -0.4255, -0.2676, +0.4226, +0.0928, -0.0036, -0.3854, +0.0639, +0.3991, -0.0069, -0.1642, +0.1054, +0.3349, +0.0114, +0.2166, +0.1949, -0.2591, +0.1421, -0.0570, -0.1126, +0.4689, -0.0098, +0.0989, -0.2056, +0.0760, +0.1136, -0.1069, +0.0169, +0.2328, -0.1154, -0.3517, -0.2529, -0.0477, -0.1290, +0.0745, +0.2672, +0.0654, +0.0687, +0.0551, +0.1848, +0.0550, -0.4109, +0.2507, -0.1512, +0.1814, -0.0178, +0.0753, -0.0270, +0.4997, -0.2452, +0.3953, +0.1132, -0.0255, -0.0010, +0.0948, -0.1982, -0.1473, -0.4566, -0.1062, +0.2412, +0.0324, +0.0770, +0.2883, -0.1728, +0.1389, -0.4306, -0.4021, +0.2307, -0.3570, -0.4037, +0.1354, -0.0002],
-[ +0.1589, -0.1895, -0.3689, -0.5727, -0.2003, +0.1168, +0.1060, -0.2306, -0.4607, -0.0903, -0.0011, +0.3110, -0.0802, +0.1225, -0.4624, -0.3856, -0.3799, +0.6809, -0.4660, +0.1443, +0.0860, +0.2358, +0.3056, -0.0617, -0.0484, -0.0795, -0.3600, +0.4075, +0.0335, +0.1461, -0.7056, -0.1246, -0.1867, -0.2580, +0.0790, -0.2452, +0.1160, +0.2423, -0.2178, +0.4376, -0.3230, -0.0658, +0.1403, -0.1059, -0.0664, -0.0812, -0.3583, -0.0568, -0.0803, +0.1634, -0.5470, +0.1477, +0.1001, +0.3944, -0.0091, +0.1279, +0.1031, -0.0828, +0.0511, +0.2370, -0.1112, +0.1076, -0.2241, -0.1850, -0.1509, +0.1283, -0.0812, -0.2306, -0.1560, -0.0871, +0.0507, +0.2300, -0.1790, -0.0950, -0.4634, -0.0224, -0.2822, -0.0187, +0.3859, +0.3795, -0.1656, +0.5539, -0.3940, +0.2439, -0.3326, +0.0786, +0.2440, -0.2166, -0.2951, -0.0167, -0.1098, -0.2217, +0.3969, -0.3522, +0.4583, +0.1530, +0.0412, +0.1156, +0.0537, -0.1116, +0.2062, -0.9592, -0.2470, +0.1359, +0.0993, +0.1294, +0.2242, -0.9313, +0.0561, -0.1260, -0.0798, +0.0884, -0.2110, -0.7277, -0.3866, -0.1434, +0.0363, -0.2238, -0.0164, -0.0179, +0.1237, -0.0881, -0.4443, +0.1300, -0.0737, -0.2013, +0.4890, -0.2268],
-[ -0.1106, +0.2496, +0.1603, -0.4358, -0.0318, +0.4562, +0.0668, +0.0913, +0.0326, -0.3287, -0.0950, -0.0000, -0.1749, +0.0147, +0.1572, +0.1337, +0.3227, +0.0310, -0.1516, +0.0094, +0.0951, -0.3136, -0.0813, -0.2938, -0.1727, -0.0615, +0.4927, +0.0826, +0.2202, +0.0253, -0.6977, +0.1356, +0.3201, -0.3092, -0.2199, +0.1048, -0.0584, -0.5777, -0.0738, -0.1789, -0.2877, +0.3229, +0.0150, +0.0197, -0.2914, -0.2028, -0.1299, +0.0008, +0.2346, -0.1959, +0.1455, -0.2369, -0.3370, -0.0204, -0.0299, -0.0892, -0.3299, -0.1583, +0.0046, -0.1719, -0.2365, +0.2064, -0.2505, -0.1913, -0.0303, -0.2115, -0.2317, +0.0057, +0.1364, +0.2279, +0.1970, -0.1972, +0.3322, +0.3355, +0.0605, +0.0261, +0.0419, -0.2607, -0.2405, +0.1252, -0.0398, +0.2787, -0.1420, -0.1658, +0.1677, -0.2601, -0.0801, -0.1050, +0.1703, +0.3236, +0.0146, -0.2126, +0.2793, -0.3282, +0.3748, -0.2006, -0.1309, +0.4723, +0.2652, -0.4449, +0.0144, -0.3682, -0.0513, -0.1969, +0.2342, -0.2195, +0.0066, +0.0730, -0.1386, +0.2343, -0.1026, -0.0102, +0.1281, -0.2790, +0.0387, +0.1683, +0.2041, +0.1323, +0.0995, -0.0678, -0.2548, +0.3116, +0.0275, -0.4052, +0.1195, -0.0628, -0.1240, +0.5709],
-[ +0.1611, +0.1684, +0.1180, -0.0337, -0.0164, +0.2005, -0.4611, -0.1769, +0.2780, -0.1636, -0.3267, -0.7983, +0.0632, -0.2480, +0.1168, -0.0431, -0.2038, -0.0721, +0.1671, -0.1710, +0.0372, +0.1101, -0.3353, +0.1319, -0.0475, -0.0662, +0.0418, -0.9465, +0.3207, +0.1905, -0.1956, +0.2353, -0.1500, -0.1944, -0.1521, -0.1222, +0.2512, +0.3976, +0.0530, -0.2475, -0.4579, -0.2476, -0.1615, -0.1236, -0.5453, +0.2712, -0.1133, +0.0285, -0.0988, -0.0021, -0.2373, +0.0719, +0.0631, +0.1569, +0.0420, +0.2127, -0.2636, -0.1228, +0.1000, -0.3128, -0.2440, +0.1935, +0.2123, +0.2302, -0.3028, +0.1696, -0.1394, +0.3321, -0.0264, -0.0710, +0.2143, -0.1402, +0.1902, -0.0156, +0.2402, +0.1609, -0.2699, +0.2212, -0.2134, -0.0889, +0.0275, -0.1004, -0.0181, +0.2129, -0.1209, +0.0828, -0.3149, +0.1096, +0.1476, -0.0693, +0.1365, -0.1460, -0.0319, -0.1213, +0.1037, -0.0795, -0.1108, +0.4878, +0.1358, -0.0006, +0.0897, -0.0319, -0.0744, +0.2202, +0.0410, +0.1397, +0.0272, -0.1102, +0.0604, -0.0668, -0.6511, +0.1980, -0.1455, +0.4493, -0.1050, +0.0986, -0.2703, -0.1455, +0.0464, +0.1289, +0.1522, +0.1892, -0.0211, +0.1349, +0.0311, +0.2558, -0.0779, +0.3977],
-[ +0.1549, -0.3957, -0.0942, -0.6545, -0.1147, +0.0885, +0.0263, +0.3899, -0.0039, +0.1578, +0.1178, +0.0588, -0.3606, +0.3915, -0.0311, -0.0269, +0.1901, +0.2721, +0.0042, +0.0927, +0.1884, -0.1861, +0.0426, -0.4855, -0.1304, +0.2175, -0.2916, +0.1244, +0.4870, -0.2349, -0.2040, -0.0040, -0.2405, -0.2903, +0.0529, +0.3191, +0.4127, +0.1782, -0.1870, -0.4273, -0.0206, -0.2915, -0.1524, -0.4046, -0.0423, -0.1181, -0.1054, -0.5696, -0.1597, -0.2354, -0.0163, -0.9035, +0.3200, +0.1112, -0.2512, +0.2378, +0.2037, +0.5013, -0.3021, +0.2650, +0.1290, -0.1847, +0.4552, -0.9110, +0.2156, -0.1397, +0.0881, +0.1174, -0.0092, -0.3658, -0.5517, +0.1533, +0.4847, -0.0725, +0.3432, -0.4701, -0.6041, +0.3269, +0.2537, +0.4220, +0.2289, +0.0101, -0.2262, -0.1981, -0.0431, -0.2085, +0.5592, -0.7000, -0.0529, +0.1269, -0.4089, +0.1060, -0.3534, +0.1786, -0.0607, -0.2296, -0.4937, -0.0940, +0.4213, +0.1533, -0.3961, +0.1725, -0.8912, +0.0248, +0.0092, -0.4522, -0.0179, -0.2877, +0.1628, -0.1096, -0.2574, -0.0872, -0.2096, -0.0405, +0.1788, -0.2012, -0.0524, +0.0632, -0.5398, +0.1414, -0.5686, +0.1372, -0.3937, -0.4191, -0.0216, -0.0568, +0.0698, +0.2414],
-[ +0.1718, -0.0079, -0.1722, +0.3320, +0.0736, +0.2562, +0.0251, -0.2438, +0.2509, -0.3281, +0.3477, -0.0962, -0.1747, +0.6608, -0.1284, -0.0620, +0.2505, +0.0576, +0.1825, +0.0376, +0.2137, +0.1334, -0.0137, -0.1572, +0.2251, +0.1485, -0.0870, -0.4884, +0.1099, -0.4984, +0.0576, -0.3160, -0.0971, +0.0686, -0.2857, -0.1786, -0.0665, -0.0147, +0.2700, -0.0514, +0.1172, +0.0407, -0.0610, -0.0642, +0.0641, -0.0284, -0.1473, -0.1814, +0.2611, -0.0045, +0.1158, +0.1137, +0.2471, +0.1978, -0.1271, +0.2265, -0.6208, -0.5634, +0.3271, +0.2243, -0.2667, +0.1716, -0.3122, +0.1045, +0.3088, -0.0122, -0.1800, -0.0375, -0.2735, -0.2114, +0.2025, -0.0350, -0.2953, -0.5958, -0.4832, -0.6282, -0.0991, +0.2455, -0.1095, +0.1874, -0.0986, +0.3314, +0.0481, -0.0645, +0.4166, -0.1145, -0.2953, +0.1156, +0.1745, +0.2837, +0.4273, -0.0217, +0.0088, +0.1717, +0.3309, +0.1483, -0.1668, -0.1604, -0.4858, -0.3747, +0.1971, -0.5613, +0.1759, -0.1036, +0.3260, -0.3445, +0.2426, -0.2171, +0.1091, -0.2270, +0.1575, -0.0349, -0.0231, -0.3729, -0.4534, -0.5497, +0.2144, -0.1105, +0.0400, +0.1656, -0.3746, +0.3577, +0.3003, +0.2348, -0.0513, +0.2820, +0.0473, +0.2366],
-[ -0.1913, +0.1249, -0.1732, -0.2680, +0.0227, -0.2906, -0.0469, +0.2907, -0.2876, -0.0223, +0.2126, +0.0124, -0.1818, -0.0529, +0.2163, +0.5855, -0.4238, +0.1553, -0.3659, +0.1536, +0.2847, -0.1533, +0.0937, -0.0114, -0.3242, -0.3720, -0.0967, +0.0381, +0.1980, -0.2949, +0.5866, -0.7887, +0.4248, -0.8988, -0.2377, +0.0433, +0.0411, +0.3731, -0.0635, -0.2109, -0.2147, -0.6306, -0.3525, -0.4667, -0.0714, -0.0446, +0.1229, +0.1204, -0.0778, +0.3604, +0.3999, -0.2006, +0.1629, +0.2834, +0.1890, +0.0876, -0.2733, +0.4668, +0.1295, +0.6109, +0.6013, +0.1212, +0.1495, -0.1013, -0.0258, +0.0329, +0.0146, -0.2249, -0.1254, +0.0451, -0.1161, +0.0509, +0.0342, +0.4697, -0.2697, -0.8005, -0.0243, +0.0727, -0.5215, +0.0011, +0.1684, -0.2429, +0.0306, +0.2113, +0.3269, +0.2809, -0.3176, -0.1760, +0.0876, +0.0676, -0.3935, -0.0752, -0.0276, +0.2095, -0.0323, -0.2302, +0.4134, +0.2879, -0.2407, +0.3646, +0.2311, +0.2115, +0.0899, -0.2074, +0.0238, -0.3053, +0.0006, -0.2911, +0.0807, +0.0398, -0.0187, +0.2942, +0.0755, -0.4258, -0.0959, -0.3400, +0.0590, -0.0067, -0.2461, -0.5850, -0.6598, +0.4854, -0.1813, -0.1474, +0.7169, +0.1375, +0.1376, +0.0359],
-[ +0.4524, +0.0223, +0.0119, +0.4184, +0.3407, -0.4284, -0.0053, -0.0177, +0.0914, -0.1727, +0.3593, -0.1639, -0.0031, +0.0938, +0.3939, -0.5016, +0.3695, +0.0559, -0.0370, +0.0097, -0.3375, +0.2016, +0.3032, -0.2097, -0.2397, -0.6238, +0.2770, +0.3377, +0.2961, -0.2426, -0.3826, -0.2628, -0.3084, -0.0764, -0.2180, +0.2903, -0.3832, -0.2275, +0.3650, +0.0053, +0.2570, -0.0952, -0.0308, -0.0060, +0.1119, -0.0977, +0.0164, +0.1121, -0.2184, -0.1349, -0.2883, -0.0804, +0.2702, -0.2342, +0.2967, +0.3763, -0.0868, +0.2934, -0.2347, +0.3500, +0.1751, -0.4036, -0.1235, +0.3100, +0.0484, -0.4195, -0.2837, -0.3306, -0.3631, +0.0059, +0.2298, +0.0809, +0.3639, -0.0795, -0.3863, +0.1088, +0.1869, -0.1940, +0.4728, -0.0070, +0.1099, -0.1665, +0.2909, +0.3550, -0.2971, +0.2387, -0.4757, +0.0819, +0.1032, -0.3366, +0.1963, -0.1535, -0.2657, -0.0605, +0.1982, +0.2318, -0.1578, -0.1356, -0.3610, -0.2701, -0.7643, +0.0454, -0.5442, -0.0430, -0.0145, -0.3589, +0.4091, -0.2258, +0.0022, +0.1099, -0.5204, +0.0504, -0.0081, -0.3179, -0.1154, +0.0752, -0.3016, +0.2487, -0.5536, -0.0588, -0.0644, +0.3218, +0.0549, +0.0735, -0.2451, -0.8390, -0.3746, -0.2682],
-[ -0.0016, -0.0452, +0.1532, -0.7650, +0.0169, +0.1665, -0.1787, +0.1150, -0.0360, +0.0130, -0.1275, -0.2408, +0.3302, -0.4338, +0.0053, +0.4180, +0.1073, +0.1265, -0.1695, -0.0095, +0.3174, -0.1767, -0.1039, +0.1327, +0.2633, -0.2024, -0.1561, +0.0774, -0.0627, +0.1923, +0.1428, -0.1714, +0.1412, -0.7353, -0.2745, +0.5773, -0.1019, -0.1372, -0.2105, -0.2976, +0.2121, -0.2573, +0.2477, +0.0023, +0.1221, -0.1968, +0.5837, +0.1092, +0.1521, +0.0283, -0.1028, -0.4350, +0.6186, +0.2715, -0.2510, +0.2805, -0.3659, +0.1554, -0.5880, -0.1447, -0.3310, -0.1246, +0.0657, +0.0716, -0.3006, -0.1052, +0.3839, +0.1904, +0.4279, -0.0166, -0.0742, +0.1262, -0.4340, +0.4478, +0.0889, +0.5178, -0.1752, -0.2383, +0.0182, -0.4434, +0.2788, -0.4208, +0.0039, +0.5008, +0.1493, +0.0291, +0.0577, -0.2342, +0.1468, -0.4043, +0.0001, +0.2849, +0.3798, -0.1892, +0.0185, -0.4745, +0.3082, +0.0759, +0.0991, +0.2442, +0.2099, -0.1283, -0.2924, -0.2373, -0.6365, +0.5487, +0.1724, -0.1166, -0.0525, -0.2684, -0.1275, -0.1771, -0.1892, +0.3937, -0.0792, -0.6260, +0.0029, +0.1770, +0.2306, +0.2485, +0.0466, -0.0944, +0.0566, +0.1276, +0.1477, +0.0082, +0.2286, -0.1510],
-[ -0.1199, +0.3643, +0.2857, -0.2871, +0.2386, +0.0583, -0.1731, +0.0074, -0.0773, -0.1434, +0.3898, -0.5540, +0.0593, -0.3754, -0.2622, +0.3060, -0.1933, -0.0526, -0.1061, -0.0014, -0.6364, -0.2215, -0.3393, +0.2105, +0.1445, -0.2767, +0.0421, -0.2355, -0.1554, +0.3102, -0.1943, +0.0001, -0.3861, +0.0041, -0.0981, +0.4100, +0.0132, +0.1019, -0.0265, +0.2601, -0.5624, -0.2934, +0.3179, +0.5419, -0.0551, +0.0878, -0.7451, +0.3718, +0.0703, -0.0895, +0.0483, -0.0379, -0.0465, +0.0353, -0.1371, -0.3223, +0.2306, -0.2298, +0.0244, +0.2445, -0.3638, +0.0880, +0.1780, +0.0115, +0.2871, +0.0781, -0.2232, -0.0586, +0.0061, +0.5511, -0.0018, +0.0148, -0.0773, -0.0519, +0.0476, +0.2574, -0.5450, -0.1663, +0.2035, -0.0355, +0.2185, +0.0480, +0.1931, +0.0432, +0.2283, -0.2709, +0.2036, +0.1182, -0.0344, +0.2057, +0.3461, +0.0326, +0.2119, +0.1630, +0.1640, -0.3767, +0.0827, +0.3805, -0.1525, +0.1811, +0.0695, -0.2068, +0.2242, -0.0237, +0.2619, +0.0086, +0.3502, +0.1682, +0.1652, +0.1989, -0.4398, -0.2614, +0.0829, -0.0355, +0.1752, -0.1772, -0.0422, -0.4577, -0.1499, -0.3355, +0.0394, +0.2369, +0.1219, +0.2975, -0.4451, -0.3666, -0.0082, +0.1522],
-[ +0.1437, +0.1224, -0.3918, -0.0514, +0.0086, -0.7202, -0.1270, +0.1309, +0.1368, -0.9251, -0.1310, -0.1672, -0.0649, +0.2541, +0.3051, +0.2231, +0.0904, -0.4305, -0.2895, +0.2720, -0.0440, -0.0308, +0.1066, +0.0813, -0.1520, +0.0280, -0.1259, -0.0510, -0.6828, +0.0160, +0.1415, +0.1845, +0.3022, -0.4259, +0.0890, -0.3119, -0.4578, -0.1781, -0.0130, -0.0715, -0.1318, -0.1111, +0.2490, +0.0330, +0.0753, -0.2763, -0.0104, -0.2097, -0.0717, +0.0752, +0.0167, +0.1028, +0.0059, -0.1039, -0.3831, +0.2080, -0.1394, -0.1861, -0.5240, -0.1540, -0.0547, +0.1486, +0.0644, -0.7054, +0.0501, -0.1106, +0.2911, -0.4076, +0.0784, +0.2586, -0.5799, -0.0241, +0.1035, +0.4729, -0.2316, +0.0955, +0.1980, +0.2074, +0.1257, +0.1966, -0.0541, -0.5537, +0.1174, +0.0074, +0.4825, +0.2543, -0.2226, +0.3017, -0.6206, +0.1855, -0.1653, +0.1181, -0.2842, -0.1470, -0.1760, -0.0710, +0.1804, -0.0457, -0.8516, +0.2589, +0.2182, +0.4728, -0.1165, -0.4510, +0.2497, -0.2057, +0.2234, -0.0425, +0.4023, +0.0146, +0.1678, -0.0695, +0.2158, -0.0381, -0.1743, +0.1496, -0.1089, -0.0381, -0.1673, +0.4718, -0.2082, -0.6251, -0.2411, +0.3403, -0.2797, -0.0130, -0.3459, -0.1456],
-[ +0.0733, -0.0360, +0.1024, +0.0427, -0.3455, -0.0165, +0.2678, -0.3823, -0.0074, -0.2066, -0.0813, +0.1675, +0.0614, -0.0818, -0.0098, -0.3373, -0.0009, -0.1579, +0.2214, +0.3661, -0.3002, -0.1751, +0.0850, +0.0664, -0.7089, -0.0570, -0.6223, -0.0760, -0.2579, +0.1160, -0.4883, -0.3417, +0.1093, -0.3465, -0.1029, +0.0323, -0.0124, +0.1743, +0.2238, +0.2200, +0.2838, +0.0199, +0.1371, +0.2527, -0.1738, -0.0343, -0.0504, +0.1290, -0.2154, +0.3672, -0.0281, +0.4991, +0.5160, -0.0292, +0.2712, -0.0429, +0.0020, +0.3000, +0.1499, +0.3555, -0.3632, +0.5845, +0.1193, +0.0651, -0.3064, -0.2260, +0.0438, -0.3252, -0.2209, +0.0876, -0.2948, -0.3681, -0.0442, +0.1585, +0.4002, -0.1729, -0.0857, +0.0738, +0.1218, -0.2164, +0.1597, +0.0583, -0.3370, +0.4479, -0.0440, +0.2751, -0.1229, -0.5297, +0.0170, +0.1326, -0.1707, -0.1165, +0.0453, +0.0743, -0.1221, -0.0458, +0.0028, +0.0599, -0.5900, +0.0896, -0.4746, -0.2719, +0.0281, +0.0356, +0.2661, -0.0380, +0.1702, -0.0690, -0.1933, +0.0336, +0.0947, +0.0578, -0.6923, -0.1154, -0.4010, +0.0136, +0.1166, +0.0909, -0.2182, -0.1437, +0.2823, +0.0751, -0.4068, +0.0748, -0.0749, +0.2066, -0.0593, +0.0359],
-[ +0.1265, -0.0627, +0.2708, -0.2773, +0.1730, +0.0656, -0.4082, -0.1399, -0.0302, -0.0061, -0.2213, -0.7247, -0.3789, +0.1175, +0.1405, +0.0403, +0.0540, -0.4520, -0.1542, +0.1201, +0.3539, -0.3941, -0.3645, +0.3899, -0.1617, +0.3308, -0.0598, +0.0362, +0.2295, +0.0053, +0.3446, -0.4717, -0.2345, -0.4764, +0.1418, -0.2275, -0.3499, -0.0334, -0.0724, +0.0027, -0.2637, +0.2906, +0.2269, +0.2278, +0.0008, -0.3168, -0.2358, +0.1961, -0.1241, -0.0219, -0.2630, -0.5756, -0.1580, -0.0458, -0.0436, -0.0687, +0.1328, +0.0779, -0.2274, -0.2464, -0.4239, +0.2344, -0.2781, -0.0248, -0.1314, -0.0011, +0.1282, -0.2285, -0.0377, +0.4072, -0.0057, +0.1904, +0.2026, -0.0776, -0.2365, +0.0172, +0.3016, -0.2762, +0.1806, -0.3418, -0.4736, -0.1129, -0.0965, +0.0512, -0.1640, -0.5656, +0.3251, -0.0625, +0.2431, -0.7916, +0.4731, +0.1314, +0.3754, +0.2090, -0.0308, -0.6271, +0.1037, -0.0316, +0.5101, +0.2145, -0.0424, -0.0907, -0.2650, +0.0871, -0.5630, +0.3257, -0.2033, +0.0002, +0.0630, -0.1801, +0.1567, +0.0362, -0.2026, -0.1676, +0.2884, +0.0877, +0.3338, +0.1547, +0.1157, -0.1227, +0.0091, -0.2324, -0.2646, +0.1589, +0.1033, +0.2009, +0.1363, +0.2472],
-[ +0.3672, -0.0901, +0.1674, +0.1741, -0.2490, +0.0575, +0.3177, -0.5621, +0.0752, -0.4964, +0.0001, -0.1637, -0.2243, -0.4065, +0.0050, -0.7852, -0.0936, -0.2096, +0.0598, +0.2685, +0.4182, -0.3412, +0.3916, +0.0203, +0.1744, +0.0933, +0.3562, -0.3311, +0.0469, -0.2780, -0.3809, -0.5812, -0.4755, +0.3753, -0.0527, -0.5474, -0.3383, +0.2383, -0.1474, -0.2493, +0.2020, +0.1638, +0.0508, +0.2289, +0.0218, -0.2402, -0.0091, -0.1547, +0.3674, +0.4758, +0.2179, -0.1136, -0.2481, -0.3880, -0.1108, -0.0173, -0.0563, +0.0266, -0.3333, +0.0366, +0.1629, +0.0646, +0.1936, +0.1930, +0.1110, +0.2076, -0.1780, -0.1180, +0.1521, -0.0950, -0.0727, -0.0017, +0.3475, -0.0342, -0.0499, -0.5500, -0.0339, +0.1342, +0.3349, -0.1089, +0.5189, +0.0124, +0.0046, -0.4442, -0.1642, +0.2013, -0.0279, +0.0108, +0.1346, +0.4585, +0.1802, +0.3017, -0.2408, -0.0645, +0.4384, +0.0099, +0.4344, +0.4860, +0.1790, -0.2444, -0.3877, -0.0284, -0.0566, +0.1372, -0.3824, -0.6377, -0.0628, -0.0398, +0.1073, +0.3323, -0.0827, +0.0376, -0.0416, +0.1855, -0.2737, -0.2940, -0.4861, +0.1553, +0.2175, -0.1099, -0.2827, +0.0182, +0.0924, -0.0093, -0.6144, +0.1743, +0.0977, +0.1084],
-[ -0.3080, +0.0907, -0.1649, +0.3318, +0.2758, +0.0320, -0.2480, +0.0117, -0.3531, -0.0572, -0.2509, +0.0474, +0.3281, -0.1668, +0.0472, +0.2543, -0.0862, +0.0207, +0.1018, +0.2401, +0.2810, +0.4449, -0.2407, -0.4852, -0.1038, -0.0502, +0.4901, +0.1284, -0.3240, -0.6291, +0.3866, +0.0484, +0.3418, -0.0835, +0.3512, +0.2007, +0.3187, +0.2226, -0.2257, +0.3427, -0.2731, -0.4103, -0.2178, -0.4763, +0.0986, +0.2132, -0.2027, -0.0528, +0.1876, +0.1881, -0.0998, -0.0737, +0.1540, +0.0492, -0.0989, +0.1285, +0.0750, -0.4498, +0.0803, -0.3685, -0.0318, -0.0641, -0.2312, -0.0639, +0.0131, -0.2716, -0.0166, +0.0095, -0.0550, +0.2155, -0.1151, +0.0280, -0.5577, +0.2472, -0.1704, -0.4050, -0.5706, +0.1635, -0.3534, +0.2263, +0.1519, -0.2761, -0.2593, +0.3671, -0.3879, +0.1204, +0.2487, +0.4244, +0.1836, -0.2578, -0.0479, -0.1153, +0.1945, -0.0349, -0.2565, -0.3167, -0.2075, -0.3321, -0.0222, +0.2474, -0.4006, -0.0428, +0.0766, -0.0910, +0.1290, -0.1410, -0.2871, +0.1620, -0.2337, -0.0841, -0.4411, -0.0992, -0.0288, +0.1999, +0.0152, +0.1243, +0.0414, +0.3242, -0.4499, -0.0982, -0.1245, -0.5705, -0.1811, -0.2595, +0.1088, -0.1888, -0.2619, +0.2435],
-[ +0.2564, -0.5431, -0.5082, +0.3797, -0.1371, -0.1407, +0.2606, -0.3532, +0.1148, +0.0348, -0.6669, +0.5390, -0.0679, -0.6189, -0.1997, +0.1223, -0.3101, +0.0410, -0.0733, -0.1994, -0.2091, +0.3170, -0.8236, -0.2025, -0.3470, -0.0958, +0.1701, +0.0633, +0.4095, -0.2781, +0.0751, -0.1107, +0.0279, -0.3456, -0.3023, -0.1047, +0.4750, +0.1992, +0.0064, -0.3119, -0.0697, +0.0908, -0.0153, +0.3006, +0.1023, +0.0865, -0.3193, -0.2363, -0.0379, -0.0737, -0.1497, -0.1821, -0.4256, +0.1869, -0.0092, -0.5244, +0.2473, -0.0994, -0.4700, +0.0160, +0.0074, +0.1139, +0.2407, +0.0043, -0.2212, +0.1343, -0.0217, +0.2449, +0.0947, +0.3478, -0.0248, -0.0637, +0.1599, +0.1110, +0.3378, +0.1366, -0.0477, -0.1392, -0.0558, -0.0633, +0.1529, -0.0403, +0.1934, -0.3078, +0.0564, +0.0266, +0.2551, -0.4909, -0.1975, -0.0311, -0.1966, +0.0851, -0.0700, +0.3483, -0.3742, -0.0266, -0.0608, +0.3700, -0.0319, -0.3136, -0.0212, +0.4177, -0.1627, -0.1911, -0.0261, +0.0379, -0.7147, -0.1136, +0.0332, +0.2362, +0.2517, +0.0570, +0.1935, -0.0097, +0.3102, +0.3422, -0.1285, +0.2687, +0.1173, -0.1157, +0.2377, -0.2715, -0.1053, +0.1276, +0.5240, -0.3129, +0.0906, +0.2394],
-[ +0.0182, -0.1299, -0.0132, -0.0445, +0.0434, -0.1050, +0.2383, -0.0531, -0.0667, +0.0269, -0.1853, +0.1164, +0.0166, -0.0413, -0.0896, -0.0977, +0.1889, +0.3095, +0.0361, -0.2056, +0.3806, -0.0326, -0.5333, +0.1189, +0.1859, -0.1565, +0.0555, -0.3661, -0.8639, -0.2448, -0.0557, -0.0534, +0.0042, -0.5713, +0.5114, +0.4660, +0.0137, -0.1421, +0.0979, -0.2005, +0.2329, +0.2130, +0.1805, -0.1600, +0.2769, +0.2827, -0.1460, +0.1061, +0.0854, -0.0310, +0.1183, +0.2273, +0.0824, +0.2282, +0.0108, -0.2525, +0.0771, -0.1526, -0.0139, +0.0269, -0.5221, -0.3769, -0.2342, -0.0453, +0.2171, +0.2046, +0.4883, +0.0497, +0.2218, +0.2181, +0.1806, +0.0522, +0.1161, -0.1453, +0.3688, -0.2118, -0.4573, +0.1621, +0.0019, +0.0855, +0.0834, -0.1672, -0.3092, +0.0172, +0.0616, -0.3783, +0.1639, -0.1543, -0.1446, -0.5286, +0.1300, -0.0023, +0.3224, +0.4647, +0.0172, +0.2039, -0.2361, +0.1141, -0.1565, +0.2557, +0.2248, +0.2834, +0.1647, +0.1474, +0.0831, -0.1383, +0.3499, +0.0644, -0.0408, +0.0691, -0.1987, -0.1009, +0.1492, -0.7122, +0.2109, -0.2153, -0.1362, +0.3380, +0.3956, -0.3061, -0.0537, -0.1554, +0.0221, -0.0772, +0.2158, -0.1286, -0.0206, -0.7828],
-[ -0.4612, -0.7768, -0.1705, -0.1334, +0.1252, +0.2581, -0.0253, +0.3918, -0.0171, -0.2106, -0.0601, +0.0502, +0.2695, -0.4787, +0.1919, +0.1659, -0.5232, -0.4664, +0.5166, -0.0030, +0.2659, +0.0514, +0.2924, +0.1007, +0.2972, +0.1873, +0.2086, -0.1280, +0.3712, +0.3357, +0.0716, +0.2718, -0.4366, +0.0580, +0.0064, -0.0801, +0.1128, +0.3085, +0.6918, +0.0245, -0.2338, +0.0123, -0.4176, -0.2340, +0.0233, -0.2649, -0.0671, +0.0879, +0.1039, -0.0559, +0.0625, -0.0018, +0.1866, -0.1498, -0.1005, +0.3043, -0.4272, -0.2103, -0.2707, +0.3701, +0.0207, -0.1693, +0.1511, +0.0725, -0.1867, -0.6037, +0.0822, +0.2406, -0.2614, -0.0230, -0.2334, -0.3113, -0.1930, -0.1664, -0.2398, -0.3514, -0.2636, -0.1754, +0.1389, +0.0401, +0.0478, +0.0277, -0.0695, -0.0086, -0.1618, +0.2286, -0.1440, +0.1581, -0.0142, +0.2421, -0.0396, -0.3297, +0.1494, -0.3490, +0.0522, +0.1803, +0.2010, -0.0700, -0.1020, +0.0126, +0.0985, +0.4564, -0.9869, +0.4354, +0.1019, -0.2100, +0.0896, -0.0418, -0.1470, -0.6701, -0.1253, -0.0466, -0.5191, +0.0922, -0.1019, +0.1983, -0.1689, +0.0613, +0.1169, -0.0128, -0.4549, +0.2831, +0.1717, +0.1657, +0.6473, -0.0489, +0.4133, +0.1272],
-[ -0.1649, +0.3595, -0.1018, -0.2451, -0.1059, -0.2183, +0.0321, +0.2026, +0.3835, -0.4291, -0.1033, +0.0628, -0.0075, +0.3700, -0.0673, -0.3885, -0.2072, +0.0783, +0.0155, -0.1216, +0.1363, +0.2228, -0.4028, -0.3663, +0.2848, -0.2209, -0.1416, -0.3134, -0.0327, -0.0167, -0.0050, +0.1597, -0.0961, -0.2168, -0.1929, -0.4492, -0.0239, -0.0554, +0.3182, -0.2570, -0.0276, -0.2450, +0.1675, -0.1146, +0.0406, +0.0083, +0.3763, +0.3331, -0.1138, -0.0384, -0.1075, -0.1307, +0.7358, -0.0440, +0.0448, -0.8095, +0.1581, -0.2983, -0.2206, +0.1737, +0.0761, +0.1185, +0.3687, +0.0213, -0.7444, -0.2477, -0.0400, -0.1679, -0.1437, -0.1774, +0.0707, -0.3777, -0.0090, -0.2117, +0.2812, +0.1159, -0.1425, -0.4042, -0.0190, -0.4525, +0.0406, +0.0125, -0.0717, -0.0850, +0.5492, -0.2095, -0.2514, -0.0894, -0.1617, +0.1320, +0.5583, +0.0113, +0.1968, -0.7115, -0.1437, -0.1520, -0.4391, +0.2490, -0.0100, -0.2297, +0.0209, +0.1460, -0.3519, -0.0173, -0.0711, -0.1591, -0.3104, +0.1723, +0.0971, +0.0788, +0.3080, -0.2091, -0.0183, +0.4434, +0.1019, +0.0348, -0.2908, +0.2420, +0.5102, +0.2919, -0.0464, +0.0460, +0.0233, +0.1660, -0.1202, -0.2951, +0.1735, -0.0185],
-[ +0.1634, -0.3169, -0.1324, +0.0502, -0.6239, +0.0555, +0.0211, +0.0921, -0.0013, -0.1419, +0.0632, +0.2059, +0.1216, -0.0172, +0.3665, -0.0805, -0.0796, +0.2272, +0.0931, +0.2847, +0.2629, -0.2724, -0.4270, -0.3100, +0.2210, +0.4631, +0.3028, -0.2282, +0.1676, -0.6001, +0.0974, +0.1097, -0.0096, +0.2315, +0.0054, +0.1062, +0.1074, +0.3050, -0.5204, -0.2651, -0.6917, +0.1531, -0.0189, +0.0602, +0.0373, +0.3394, +0.1720, +0.1038, +0.1990, -0.0107, +0.3361, +0.2242, +0.2207, -0.1006, -0.1221, -0.4280, -0.0186, -0.7557, -0.0749, -0.2288, -0.0474, +0.0275, +0.0316, -0.1601, +0.0462, +0.0927, -0.3655, -0.1558, -0.3117, +0.0820, -0.0712, -0.7471, +0.4260, +0.2970, -0.2324, +0.1872, -0.2711, -0.4186, +0.2332, -0.4264, +0.2156, -0.4412, +0.1897, +0.0445, -0.2522, +0.0740, -0.3054, -0.1679, +0.0561, +0.0893, +0.1132, +0.3704, -0.0683, +0.1545, -0.1077, -0.0547, +0.0933, +0.1020, +0.2662, -0.6865, +0.0276, -0.2674, +0.0357, -0.3108, -0.4783, +0.2114, -0.1678, -0.1909, +0.1531, +0.0703, -0.4706, +0.1802, -0.0411, -0.2016, +0.0814, +0.1414, -0.3811, +0.0172, -0.1926, +0.0396, +0.0064, +0.0637, +0.4441, -0.2017, +0.2727, +0.0266, -0.6768, -0.1469],
-[ -0.4334, +0.4022, +0.3103, -0.0775, +0.3432, +0.2280, +0.2167, +0.0161, -0.0377, +0.3427, +0.1773, -0.0010, +0.0084, -0.3900, +0.0397, -0.2535, -0.3968, +0.0300, -0.0638, -0.3266, +0.0582, -0.3348, +0.3936, -0.2502, -0.0383, -0.2508, -0.1750, +0.1348, +0.3072, -0.0949, +0.0587, -0.4842, -0.2063, +0.3357, -0.3240, +0.4859, +0.2623, +0.2962, -0.2773, -0.0593, +0.1301, +0.2364, +0.3923, +0.0414, -0.4935, -0.0941, -0.3768, +0.3842, -0.0718, +0.0742, -0.0573, -0.4293, +0.0743, -0.2978, -0.0422, +0.1087, -0.4377, -0.3464, -0.0827, +0.0915, +0.0008, +0.3214, -0.1166, -0.0198, -0.1859, -0.2302, -0.2074, -0.0078, -0.2070, +0.0302, +0.1794, -0.0882, +0.0121, -0.2374, -0.1987, -0.3892, -0.4104, -0.0611, +0.1686, +0.0921, -0.4782, -0.3420, -0.8396, -0.3065, +0.0760, +0.1691, -0.2897, -0.1100, +0.4519, -0.6548, +0.3574, -0.2755, -0.3936, -0.0137, -0.0957, +0.3792, +0.1755, -0.0097, -0.2697, -0.0520, -0.1111, +0.0483, +0.0760, -0.2787, -0.0091, -0.0703, -0.0605, -0.4374, -0.0477, +0.2326, +0.0533, -0.4199, -0.1989, +0.0147, -0.1653, +0.1292, -0.1568, +0.3050, -0.0993, -0.0980, +0.1212, -0.0170, +0.0798, -0.3524, -0.0280, -0.0236, -0.1151, +0.1826],
-[ -0.2467, +0.1172, -0.0152, +0.0993, -0.2194, +0.1785, +0.0350, -0.1104, -0.3253, -0.6443, +0.1784, +0.0353, -0.0128, -0.2158, +0.1635, -0.2837, +0.2682, -0.1172, -0.2201, -0.0922, +0.3524, +0.2740, +0.3523, +0.0294, -0.1040, +0.5053, -0.0675, -0.1428, -0.2636, -0.1438, +0.0137, -0.1672, -0.0066, +0.3998, -0.0263, -0.0804, +0.1891, +0.3853, -0.0451, +0.0422, +0.0247, -0.0488, -0.2068, +0.2859, -0.3719, +0.3085, +0.3887, -0.1576, +0.2532, +0.0055, +0.3574, -0.0552, +0.0684, -0.3958, -0.0227, -0.0263, +0.3915, -0.0799, -0.0883, -0.2491, +0.3389, -0.1571, -0.0407, +0.3617, -0.0372, -0.1463, -0.1914, +0.0403, -0.3653, -0.2513, +0.2132, -0.4592, +0.2080, +0.0221, +0.1709, -0.0067, +0.1605, +0.0515, +0.0210, +0.1372, +0.1040, -0.4406, +0.5372, +0.1172, -0.3725, -0.3438, +0.0618, -0.1765, +0.3595, +0.2272, +0.0550, +0.1535, -0.0240, -0.1351, +0.1215, +0.1343, -0.0918, -0.3227, +0.0299, +0.2198, -0.4449, -0.2217, -0.3357, +0.4860, -0.3386, +0.1844, +0.2087, -0.1809, -0.0116, -0.0124, +0.2560, -0.0801, -0.0154, +0.2344, -0.1114, -0.0739, +0.3299, +0.1055, +0.3951, -0.1211, -0.3680, +0.3612, -0.6091, +0.0490, +0.0631, +0.2087, +0.1592, +0.1056],
-[ +0.2029, +0.0557, -0.0085, -0.3595, -0.1618, -0.1130, -0.0428, -0.1348, -0.2826, +0.1473, -0.1350, +0.1554, -0.0454, -0.5012, -0.4408, +0.1510, +0.1154, -0.2376, +0.2249, +0.0750, -0.4768, +0.5343, -0.1295, +0.0161, -0.5796, -0.2848, +0.2328, -0.4933, -0.2101, -0.1309, -0.6023, +0.1038, -0.2965, +0.2144, +0.3466, +0.0884, +0.3949, +0.1081, +0.4113, -0.0865, -0.2316, -0.1709, +0.2065, +0.0104, +0.0048, +0.1482, +0.0008, +0.0607, -0.3910, -0.1948, +0.1229, -0.2527, -0.3891, -0.0286, -0.2299, -0.3915, -0.0672, -0.0426, +0.3480, +0.3049, +0.0798, -0.2610, -0.4881, -0.4540, -0.0310, +0.0497, +0.1947, +0.0685, -0.1108, +0.1231, +0.0725, -0.1682, +0.4444, -0.4213, -0.5869, +0.4549, -0.1048, +0.1328, -0.4244, +0.1140, -0.3106, -0.0655, +0.2712, +0.1341, +0.2651, -0.0830, -0.0978, -0.2112, -0.1133, +0.1298, +0.0131, +0.5820, +0.0212, -0.0882, -0.0126, +0.0561, +0.0849, +0.0870, -0.2993, +0.0438, +0.1446, -0.4625, -0.4951, -0.2186, -0.1318, +0.1579, -0.2303, -0.2380, +0.1778, +0.5354, -0.4924, +0.2349, +0.0470, -0.3649, -0.5210, +0.0764, +0.0834, -0.4999, +0.0301, -0.1041, +0.0504, +0.0143, -0.1836, +0.2100, -0.6752, -0.2314, +0.4647, -0.1310],
-[ -0.1335, -0.6320, -0.0721, -0.1399, +0.2147, -0.2856, +0.0098, +0.1405, +0.4249, -0.2522, -0.1856, -0.1044, +0.0052, -0.0444, -0.2619, +0.1746, +0.0588, +0.2658, +0.1085, +0.2029, +0.2338, +0.1926, -0.1297, +0.0238, -0.3790, +0.0980, +0.3171, -0.1165, -0.2144, +0.3379, -0.2969, -0.4162, +0.1183, -0.0417, +0.0213, +0.1795, -0.6973, -0.0106, +0.1144, -0.4240, -0.0772, +0.1514, -0.0282, +0.0907, -0.0655, -0.0164, +0.2066, -0.3083, +0.0271, +0.5376, +0.2761, -0.1558, +0.1819, +0.0723, -0.0501, +0.0505, -0.4723, -0.3211, -0.0367, -0.3155, -0.4286, +0.0182, +0.2657, -0.2361, +0.1894, -0.4548, -0.1447, -0.1170, -0.1283, +0.2184, +0.1186, -0.4415, -0.0122, +0.3546, -0.2868, -0.0750, -0.2940, +0.1859, +0.1716, +0.2779, +0.5894, +0.1930, +0.2021, -0.1281, -0.1225, +0.1017, +0.2843, +0.2552, -0.5806, +0.1193, +0.2005, +0.0839, +0.0274, -0.0806, -0.2124, -0.0267, -0.0070, -0.3080, +0.4123, -0.0053, +0.0142, -0.0142, +0.1642, +0.3051, -0.3333, -0.1631, -0.0933, +0.1235, +0.2134, +0.0818, -0.3749, -0.2464, -0.0994, +0.1438, +0.5946, -0.5342, -0.2824, +0.2526, -0.0492, +0.2793, -0.0208, -0.0858, +0.2623, +0.2215, -0.1924, -0.0963, -0.2523, -0.0009],
-[ -0.0965, -0.2704, +0.3668, +0.0120, +0.1126, +0.0029, -0.0023, -0.0716, +0.0513, +0.1389, +0.3988, -0.2024, +0.0216, +0.0985, +0.1697, -0.5774, -0.4878, -0.1582, -0.2562, -0.0928, +0.2712, +0.0256, +0.0846, -0.3739, -0.0232, +0.2041, -0.1263, -0.1368, -0.2477, +0.4192, -0.2340, +0.1585, +0.2562, +0.0991, +0.2600, +0.1384, -0.1755, +0.1171, -0.4825, +0.2500, +0.3398, -0.1792, -0.1377, -0.0633, -0.3367, -0.0944, -0.3369, -0.0393, -0.0290, +0.1388, -0.3144, -0.5235, +0.0624, +0.2081, -0.1346, +0.3517, -0.1641, -0.2767, +0.3720, +0.1985, -0.5782, -0.0537, +0.2983, +0.2773, +0.2039, +0.3844, -0.0659, -0.1036, +0.1812, +0.0295, -0.1573, -0.1218, +0.2601, -0.5374, +0.0723, +0.2074, +0.0874, -0.3085, -0.4962, -0.1246, +0.2095, +0.1047, +0.1184, -0.3327, +0.2405, +0.4445, -0.0445, +0.0202, -0.3354, -0.3245, -0.0287, +0.0117, -0.3978, +0.2340, +0.1290, -0.1872, +0.2734, -0.2626, +0.2791, +0.2888, +0.4021, +0.1303, +0.2716, -0.0656, +0.1747, -0.2927, -0.0966, -0.3251, +0.1773, -0.0566, -0.7090, +0.0475, -0.2062, +0.1276, +0.1696, -0.0822, +0.3346, +0.0305, +0.0433, +0.1581, +0.2455, +0.7108, -0.0827, +0.0132, +0.0526, +0.0960, -0.5570, +0.1225],
-[ +0.0388, -0.0636, +0.1128, -0.7107, +0.0510, +0.0457, +0.2695, +0.0538, +0.0499, -0.3330, -0.1929, -0.0447, -0.3854, -0.0374, +0.1305, +0.0504, +0.2096, -0.1844, -0.0142, -0.1926, -0.5354, +0.0787, -0.1043, +0.3655, -0.4451, -0.5379, +0.0621, +0.2261, +0.0861, +0.0017, -0.3028, +0.3339, -0.0214, -0.3797, -0.0736, -0.2597, -0.2715, -0.1934, +0.0972, +0.0316, +0.1169, -0.1531, -0.1452, -0.2641, +0.4219, +0.0188, -0.0380, -0.1284, +0.3214, -0.1688, +0.0353, +0.1345, -0.0009, -0.3808, -0.2310, -0.3112, +0.1768, -0.1447, +0.0555, -0.1069, +0.0140, +0.2427, -0.2623, -0.1330, -0.4790, -0.5952, -0.1756, +0.2288, -0.1291, -0.3195, +0.1972, +0.1825, +0.4229, -0.4074, +0.0268, -0.0891, +0.0307, -0.3039, -0.1674, -0.2262, +0.2759, +0.0243, -0.0882, -0.2424, +0.0466, +0.1849, +0.2599, -0.3188, -0.0019, +0.0316, -0.1839, +0.1146, -0.0135, +0.1848, -0.1582, +0.2988, -0.2181, -0.1353, +0.2797, +0.1535, -0.4733, +0.3432, -0.1280, -0.0376, +0.1161, +0.3127, -0.0292, +0.1098, +0.0416, -0.1454, -0.6312, +0.0712, +0.1358, -0.1406, +0.3819, -0.4414, -0.2037, -0.4202, +0.3249, +0.0824, -0.1337, +0.4004, +0.1487, -0.0552, -0.0084, -0.1390, -0.0482, -0.1248],
-[ -0.4128, +0.2052, +0.2958, -0.3893, -0.0600, +0.3388, +0.1471, +0.6266, +0.0719, +0.0795, +0.1113, -0.0794, +0.2958, -0.3836, +0.2189, -0.2763, -0.1984, -0.0548, +0.0141, +0.3920, +0.1112, +0.1945, -0.3078, -0.1977, +0.4840, +0.0353, -0.2194, -0.0675, +0.3084, -0.0209, -0.4920, -0.2000, +0.0816, +0.2593, +0.2055, +0.0129, +0.3046, +0.2836, -0.1813, +0.2242, +0.0291, +0.5517, -0.3370, -0.1868, -0.3485, +0.0305, -0.1064, +0.2045, +0.0184, -0.3670, -0.0152, -0.0200, -0.1716, -0.1810, +0.3369, -0.3953, -0.1427, -0.2410, +0.1023, -0.3459, +0.2171, +0.1283, +0.0246, -0.0337, +0.0616, +0.2949, -0.0022, +0.2681, -0.1617, +0.0665, +0.2323, +0.2869, +0.1649, +0.0549, +0.0304, +0.3420, +0.3354, -0.1135, -0.2278, -0.3374, -0.2583, +0.1136, -0.0953, +0.4171, -0.0457, -0.2206, -0.0775, +0.5886, -0.3775, -0.0945, -0.1287, -0.0535, -0.1528, -0.2011, +0.3860, +0.0621, +0.3707, +0.2414, +0.2101, +0.2129, +0.0745, +0.2882, -0.0609, +0.0956, +0.6585, +0.2371, +0.3142, +0.3645, -0.3500, +0.4032, -0.1893, +0.3913, -0.1542, +0.5176, -0.2579, +0.1003, +0.0392, -0.0504, -0.0099, +0.1852, -0.6551, +0.5900, +0.0159, -0.3024, +0.0359, -0.0668, +0.5517, -0.1909],
-[ +0.3670, -0.2043, -0.3874, +0.1384, -0.3181, -0.3793, +0.4070, -0.0632, -0.0811, -0.4977, -0.1542, +0.2034, +0.0090, +0.0183, +0.1164, +0.1852, +0.0746, +0.2922, -0.5590, -0.1761, -0.0964, +0.0395, -0.1406, +0.4059, -0.2998, -0.0835, +0.0505, -0.2801, -0.3259, -0.1370, -0.0225, -0.1448, -0.2951, +0.0185, +0.1420, -0.0444, +0.0485, +0.1125, +0.0880, +0.0358, +0.1630, +0.0944, -0.0179, -0.0282, +0.0427, +0.1591, -0.2212, -0.0059, -0.2907, +0.3376, -0.1032, -0.0613, -0.0754, -0.0883, +0.1277, -0.2644, +0.0250, +0.2450, +0.2345, -0.1500, +0.0214, -0.3306, -0.3280, -0.4140, -0.1308, +0.1845, +0.3871, -0.1751, -0.5124, -0.2345, -0.3059, +0.0198, -0.3429, +0.1973, +0.2410, +0.0830, +0.1969, +0.1841, +0.1586, +0.5007, -0.0386, +0.4823, +0.0990, -0.1071, +0.7270, -0.5509, -0.1579, -0.0578, -0.1482, -0.2949, +0.1369, -0.1196, -0.2340, -0.0337, +0.2561, +0.2443, +0.2854, +0.1953, +0.6365, +0.3849, -0.2038, +0.1991, +0.3220, -0.5066, +0.2866, -0.4086, +0.2213, +0.1634, +0.4147, +0.3091, -0.0201, +0.0549, -0.2503, +0.0361, -0.4524, -0.0050, -0.2277, +0.1714, -0.3072, -0.2726, -0.0663, +0.1505, +0.0956, +0.1795, +0.2184, +0.0895, -0.0352, -0.1389],
-[ -0.3348, -0.2786, -0.2106, -0.5730, +0.4078, +0.4301, +0.3458, +0.3719, -0.3752, -0.7945, +0.1194, +0.2255, -0.2442, +0.4542, +0.0496, +0.3049, -0.3019, -0.1939, -0.2180, -0.0326, -0.0967, -0.0724, -0.0132, -0.1313, -0.2640, +0.3037, +0.0211, +0.1566, -0.1398, -0.3756, +0.2154, -0.0992, -0.0184, +0.2347, +0.1184, -0.0317, -0.1532, -0.1048, -0.1554, +0.7122, -0.1325, -0.5138, -0.2219, +0.2559, +0.3198, -0.0820, +0.1997, +0.0260, +0.1107, -0.3232, -0.1882, +0.2708, +0.0517, -0.0525, -0.0100, -0.0401, -0.3590, +0.4664, -0.0902, -0.0504, -0.1897, -0.2423, -0.1299, -0.0916, +0.3512, +0.0399, -0.0183, +0.4090, +0.3299, -0.3154, -0.0441, +0.1673, -0.2959, -0.3447, -0.0845, +0.1023, +0.0251, -0.0797, -0.4498, -0.1061, -0.2575, +0.4544, -0.2686, -0.1497, +0.1097, -0.3093, -0.1853, -0.2578, +0.0300, +0.2576, +0.1469, -0.0733, +0.0148, -0.0595, -0.1906, +0.1903, -0.1623, -0.0291, -0.9437, +0.2876, +0.0216, +0.2890, +0.0375, -0.1492, -0.3442, -0.0061, +0.3488, +0.3416, +0.4879, -0.3436, -0.3196, -0.4589, -0.0626, +0.1611, -0.4217, +0.3166, -0.0914, +0.2433, +0.1901, -0.1086, -0.2327, +0.2995, -0.0638, +0.0670, +0.0415, +0.2278, +0.2642, -0.0850],
-[ +0.4386, +0.0676, -0.2674, +0.1742, +0.1818, -0.0317, +0.1438, +0.3393, +0.2597, +0.1952, -0.0306, -0.3890, -0.1543, -0.3078, -0.0870, +0.1543, -0.3517, -0.0337, -0.3475, +0.0875, -0.1180, -0.8558, +0.2351, -0.3425, +0.2135, -0.3808, -0.5150, -0.1233, +0.2568, +0.3028, +0.2748, -0.1705, +0.0912, -0.3502, -0.0125, -0.2252, +0.0556, +0.0496, +0.0618, +0.4268, +0.1870, +0.2768, +0.3715, -0.2413, -0.3389, +0.3985, -0.1171, -0.1966, -0.1881, +0.2652, -0.3795, -0.1719, -0.5104, +0.4924, +0.3802, +0.0183, -0.0325, -0.2123, +0.1092, -0.2778, +0.0937, +0.1390, -0.0038, -0.2063, +0.3351, -0.1438, +0.2943, -0.1989, -0.5708, -0.2186, +0.2609, +0.0052, -0.0960, +0.0196, -0.0849, -0.2720, +0.2187, +0.1293, -0.1299, -0.1866, -0.0398, +0.1556, -0.0259, -0.0590, +0.0550, -0.3297, -0.0573, -0.1482, -0.3060, +0.1401, +0.1256, +0.3440, -0.1418, +0.0503, -0.4561, +0.2492, +0.3486, +0.1667, -0.0210, -0.0506, -0.0107, -0.3938, -0.2330, -0.0178, +0.0308, +0.1686, -0.1246, -0.0050, -0.0322, -0.1045, -0.4248, -0.1345, -0.0218, +0.1072, +0.2226, -0.0004, -0.2046, +0.2163, +0.2451, -0.2167, -0.3689, +0.0503, +0.0823, -0.4537, -0.1243, -0.2189, +0.0481, +0.0286],
-[ +0.2334, +0.3500, +0.0662, -0.5046, -0.0597, +0.2471, -0.2703, +0.1399, -0.7505, -0.2562, +0.1958, -0.1235, -0.0242, +0.1839, -0.2893, -0.0599, +0.1254, -0.0912, -0.2353, -0.0842, -0.0949, -0.3746, +0.1217, -0.0073, -0.3354, +0.1315, +0.1889, +0.0823, -0.1858, +0.0864, +0.0734, -0.0304, +0.0318, -0.0612, +0.3508, -0.3706, +0.4253, +0.0354, -0.0071, +0.2244, +0.1871, -0.0562, -0.3139, -0.1369, +0.1179, +0.0226, -0.3849, +0.0362, +0.2879, -0.1569, +0.0192, +0.1190, -0.5616, -0.1535, +0.2427, -0.1210, +0.1751, -0.2340, +0.1810, +0.0469, +0.2542, +0.1152, +0.5797, -0.3496, +0.2892, -0.4287, -0.4724, -0.0397, -0.2464, +0.3701, +0.2956, +0.1254, -0.2646, -0.5452, +0.2122, +0.0656, +0.3347, -0.1340, +0.2442, +0.5514, +0.0956, -0.2359, -0.0320, +0.0060, -0.3456, +0.1637, -0.1336, -0.3153, +0.2063, +0.3379, -0.1048, +0.1892, +0.0051, -0.2549, +0.1573, +0.2851, +0.2117, +0.0171, -0.5138, -0.2967, -0.1822, -0.3411, +0.4851, +0.2196, -0.0956, -0.2143, -0.1333, -0.1878, -0.0897, -0.3669, +0.0232, -0.5985, +0.0040, +0.0890, -0.2406, +0.1359, -0.2536, +0.3302, +0.1070, +0.2824, +0.1760, -0.2326, -0.1464, -0.1637, -0.0883, -0.1651, -0.0040, +0.1147],
-[ +0.3286, +0.1446, -0.4889, -0.2560, +0.0087, -0.0032, +0.2922, -0.0571, -0.2620, +0.3276, +0.1989, -0.2671, +0.4530, +0.1760, +0.2313, +0.1735, -0.2025, +0.0857, -0.1717, +0.0649, +0.4153, -0.2159, -0.3218, +0.1366, +0.1428, +0.2280, +0.0951, -0.3740, +0.0134, +0.1685, -0.4610, +0.2619, +0.2539, +0.6643, -0.0249, +0.2896, +0.2262, -0.0896, -0.4443, -0.4768, -0.1166, +0.2017, +0.1794, +0.1467, -0.0412, -0.1558, -0.6156, -0.1934, +0.1678, -0.4609, +0.0233, +0.0560, -0.3037, +0.0028, -0.2147, -0.1994, -0.1285, +0.1422, -0.3720, +0.4516, +0.1110, -0.0126, -0.2277, -0.0637, +0.1997, +0.0929, -0.2787, -0.1123, +0.0398, -0.0013, +0.0914, -0.0602, +0.0658, -0.3143, -0.1310, +0.1215, -0.6516, +0.1930, -0.3655, +0.0721, -0.1805, +0.2513, -0.1496, +0.3213, -0.0998, -0.8379, -0.2334, +0.3020, -0.5952, +0.1214, +0.0053, -0.0599, +0.1029, -0.2348, -0.3246, +0.1276, -0.2573, -0.2010, +0.2362, +0.0115, -0.0638, -0.8319, -0.4884, +0.2041, +0.5310, -0.4298, -0.4542, +0.1823, -0.1613, -0.0605, -0.1559, -0.1895, -0.0180, -0.1241, +0.0350, -0.0068, +0.0332, +0.1763, -0.6629, +0.0312, -0.3316, +0.3880, -0.0538, -0.0834, +0.1576, -0.0561, +0.2621, +0.4432],
-[ +0.0147, +0.2064, -0.1060, -0.1746, +0.2711, -0.0502, -0.0490, +0.0768, -0.2528, -0.1784, -0.0798, +0.1602, -0.0534, -0.1266, -0.0137, +0.0807, +0.1191, +0.1377, +0.3625, -0.2101, -0.2833, +0.4921, -0.0155, +0.2985, -0.1394, +0.0707, -0.1297, +0.2470, -0.1117, -0.2487, +0.2999, +0.3454, +0.6182, -0.1765, +0.2013, +0.3832, +0.1082, +0.2044, +0.1132, +0.2920, +0.1542, -0.0685, +0.2194, -0.6517, +0.4470, +0.0458, -0.5681, -0.3213, +0.0855, -0.0332, -0.0109, -0.3474, +0.1339, -0.1649, +0.1788, -0.0983, +0.0417, -0.2880, +0.0338, -0.2320, -0.1456, +0.3784, +0.0509, +0.4927, +0.2587, -0.4095, -0.4250, +0.1030, +0.1446, -0.2185, -0.5015, +0.0271, +0.1479, -0.1742, -0.1102, +0.1514, -0.4440, +0.2041, +0.0649, -0.1766, -0.6038, +0.0087, +0.3342, +0.2130, -0.2297, +0.0348, -0.2462, +0.0589, -0.1637, -0.2169, +0.0430, -0.0695, -0.1463, +0.1773, -0.2813, -0.2043, -0.3637, -0.0631, -0.5325, -0.1955, -0.2975, -0.0015, -0.7195, +0.2291, -0.2418, -0.2807, +0.1495, -0.3170, -0.0369, +0.2704, +0.2877, -0.1725, +0.1326, +0.0250, -0.6804, +0.2416, +0.1008, -0.4565, -1.0737, +0.0460, +0.4516, +0.3291, -0.2031, -0.0634, -0.2550, +0.0027, +0.1835, -0.0018],
-[ +0.2131, -0.1562, +0.2594, +0.3605, +0.0794, -0.2570, -0.1648, -0.1512, +0.2541, +0.0463, +0.2055, -0.0796, +0.3198, -0.3074, -0.1550, -0.6142, -0.1965, +0.1646, -0.1567, -0.0085, -0.6113, +0.1408, -0.1080, -0.0539, -0.1120, -0.2428, +0.1481, -0.0837, +0.1244, -0.6752, +0.1054, -0.4174, -0.0913, +0.0177, -0.2791, -0.1516, +0.2192, +0.2722, -0.0131, -0.1560, +0.2537, +0.1266, +0.0385, +0.5191, +0.1330, +0.1316, -0.3468, -0.6043, -0.0150, -0.4329, -0.2545, +0.1611, -0.2530, -0.1260, +0.1557, -0.0315, -0.3780, +0.1580, +0.4637, +0.0735, +0.4587, +0.0042, +0.3587, -0.2023, +0.2841, +0.1234, -0.0320, +0.2958, +0.1814, +0.2309, +0.2298, +0.3475, +0.3997, -0.0162, +0.1529, +0.2248, -0.3285, +0.0518, +0.0312, -0.3026, +0.3310, -0.2357, -0.2514, -0.0588, +0.1067, +0.6822, +0.0420, +0.0773, -0.0075, +0.1280, +0.2329, -0.3757, -0.3127, -0.8525, -0.4980, +0.2605, -0.2104, -0.2117, -0.2872, -0.1171, +0.6722, +0.2380, +0.1887, +0.0774, +0.0733, -0.3621, -0.3701, +0.0127, -0.2220, -0.1010, +0.0380, -0.0259, -0.0563, +0.4471, -0.2937, -0.0447, -0.2557, -0.0682, -0.0725, +0.1128, -0.0947, +0.0128, -0.0694, +0.1380, +0.0983, -0.1230, +0.2008, -0.2720],
-[ -0.0453, -0.0346, -0.3839, +0.3868, +0.0220, -0.1853, -0.2074, -0.0472, +0.1150, -0.3498, -0.0552, -0.6694, -0.2392, -0.0460, +0.2246, -0.1476, -0.1392, +0.2510, -0.1887, -0.1917, -0.2042, +0.2376, -0.0070, +0.2963, -0.0532, -0.0655, -0.3930, -0.1404, +0.0261, -0.2433, +0.0650, -0.1541, +0.0865, +0.0560, +0.2193, +0.1140, -0.3042, +0.4085, -0.6852, +0.1022, -0.3513, +0.1058, +0.0876, +0.2140, +0.0388, -0.2567, -0.6992, -0.0034, -0.6875, -0.1999, +0.3151, -0.1613, -0.0835, +0.1652, +0.0957, -0.1271, +0.1856, -0.1912, +0.1145, -0.2005, -0.8172, +0.0768, -0.1519, -0.1698, -0.0191, +0.2869, +0.1435, -0.7058, +0.2418, -0.0436, -0.1621, +0.2957, +0.2039, +0.1225, -0.1435, +0.1232, -0.1169, +0.1711, -0.4111, -0.0042, -0.0948, +0.2611, -0.2258, +0.0432, -0.0917, +0.0722, -0.0662, -0.3754, +0.2176, -0.1570, -0.0478, +0.0801, -0.1957, -0.4505, -0.2235, -0.0037, -0.1842, +0.1064, +0.0296, -0.1689, +0.1312, +0.1572, +0.2111, -0.2654, +0.0155, -0.1454, +0.1102, +0.1019, -0.2846, -0.1864, -0.4023, -0.8319, -0.0978, -0.0292, +0.0817, -0.0044, +0.2086, -0.2492, +0.1939, -0.2225, -0.0161, +0.4218, -0.3132, -0.2500, +0.0394, +0.0810, -0.2824, -0.0876],
-[ +0.0521, +0.0338, -0.3186, -0.1781, -0.0083, -0.1596, +0.2465, +0.0134, +0.0067, -0.1868, -0.1395, -0.1180, +0.1019, -0.2491, -0.0086, -0.1539, +0.3759, +0.1831, +0.2938, -0.2207, -0.0184, -0.6517, +0.0625, +0.1342, -0.0452, -0.2810, -0.3562, +0.3716, -0.2575, -0.2819, +0.1850, +0.2124, +0.5566, -0.2076, +0.2125, +0.1027, -0.2377, +0.0428, +0.2231, -0.0640, -0.2934, -0.3954, -0.3368, +0.3551, -0.1121, +0.0294, +0.0512, -0.0854, +0.0062, +0.1703, +0.1667, +0.0405, +0.1268, -0.1969, -0.3350, +0.3519, -0.2240, -0.1787, +0.0476, +0.5824, -0.2556, +0.0716, +0.2466, -0.5204, +0.1523, -0.1415, +0.0159, +0.0313, +0.0817, -0.2416, +0.2747, -0.5057, +0.1327, -0.0017, -0.0146, -0.0602, +0.1821, +0.1724, -0.2857, +0.1645, -0.2909, -0.2520, +0.2880, -0.0180, +0.3563, +0.3581, -0.3516, -0.1451, +0.2524, -0.2041, -0.5919, +0.1345, -0.3076, -0.2650, -0.2368, -0.1035, -0.4026, -0.0506, -0.2451, -0.2891, -0.0012, +0.0543, +0.0361, -0.4953, +0.2972, +0.5363, -0.1967, +0.2217, -0.0397, -0.0310, -0.2884, +0.0688, +0.1345, -0.2273, +0.0899, -0.0058, -0.2192, -0.7858, -0.2073, -0.3786, -0.1811, +0.0313, +0.5153, -0.0858, -0.6176, -0.3263, +0.0589, -0.3380],
-[ +0.1447, +0.2487, -0.6313, -0.1172, +0.3038, -0.0346, +0.3458, -0.3545, +0.0515, -0.0315, +0.3545, +0.4222, +0.2183, -0.2905, -0.4228, +0.1554, -0.1838, +0.0974, -0.1378, -0.0138, -0.6740, -0.1164, -0.3584, -0.3029, +0.3508, -0.7293, +0.0589, +0.1094, -0.1223, +0.0556, +0.3249, -0.0600, +0.0921, -0.3111, -0.0515, +0.1411, +0.1957, -0.3911, +0.4253, +0.1002, -0.2081, +0.1676, -0.2270, +0.4213, -0.0185, +0.0843, -0.2100, +0.3430, -0.3339, -0.3463, +0.0952, +0.1126, +0.3449, +0.2709, +0.0589, +0.1621, +0.0565, -0.0319, -0.6499, +0.0244, -0.1855, -0.1559, +0.0487, +0.3415, +0.1673, +0.3028, -0.3281, +0.4202, +0.0914, -0.4351, +0.1292, +0.1558, -0.0536, +0.0330, +0.2806, -0.0259, -0.2538, -0.0138, -0.1472, +0.5026, -0.0253, -0.3732, +0.1224, -0.4254, -0.1082, -0.3270, -0.3147, +0.1014, -0.2948, -0.0454, -0.1176, -0.0191, +0.1183, +0.0991, -0.0198, -0.1597, -0.3980, +0.0045, -0.4451, +0.2247, -0.5023, -0.2342, -0.2534, -0.0949, -0.3167, -0.4225, +0.1585, -0.0170, -0.0155, -0.3302, -0.0495, +0.5261, +0.1370, +0.0982, -0.4810, +0.0509, -0.1396, +0.0714, -0.1373, -0.2343, +0.1735, -0.3991, +0.0299, -0.1299, -0.4131, -0.1460, -0.1579, -0.6897],
-[ +0.3441, +0.0737, -0.0593, +0.0654, -0.1225, -0.4470, +0.0438, +0.0068, -0.2765, +0.2492, +0.4912, +0.2499, +0.3068, +0.0180, -0.0732, +0.5831, -0.5952, +0.2953, -0.3798, +0.0246, -0.5543, -0.2677, -0.0940, -0.0550, +0.3922, +0.4636, +0.2015, -0.4508, -0.0827, -0.1641, +0.2124, -0.0723, -0.0722, +0.3228, -0.1877, -0.0485, +0.3905, +0.3360, +0.1375, -0.6253, +0.0363, -0.1901, +0.0090, +0.1640, +0.4249, +0.0625, +0.1969, +0.1006, -0.0418, -0.1701, +0.1958, -0.1299, -0.0117, +0.2508, +0.0986, -0.0891, -0.2224, -0.0778, -0.0769, +0.0503, -0.0035, -0.2170, -0.2238, +0.0978, -0.1376, +0.0552, -0.2644, -0.1994, +0.0275, -0.0587, -0.3096, +0.1249, +0.1441, -0.2852, +0.0708, +0.4758, +0.3501, +0.0984, -0.1571, +0.4909, +0.0790, +0.3450, +0.1971, -0.3667, -0.2532, +0.4407, -0.4904, -0.4967, -0.3008, -0.2038, +0.2675, +0.4027, -0.3156, +0.0270, -0.2254, -0.4563, -0.1682, +0.0739, -0.1076, -0.3718, -0.4797, -0.0824, +0.0357, +0.0902, -0.2714, -0.1323, -0.0632, +0.3007, +0.1690, +0.1473, -0.1669, +0.3348, +0.1822, +0.0872, -0.2891, -0.3508, +0.2752, +0.2002, -0.2944, +0.3862, -0.0587, -0.0842, +0.0930, +0.5323, +0.2875, -0.0869, +0.0191, +0.2297],
-[ -0.6072, +0.1593, +0.2208, +0.2001, -0.2024, +0.4413, -0.0058, -0.1402, -0.0808, +0.1493, -0.0617, +0.2193, +0.1257, +0.2183, +0.1666, +0.1011, -0.0891, -0.0807, +0.1919, -0.2049, +0.4302, -0.2231, +0.0180, +0.5705, +0.1127, -0.8658, +0.2152, +0.2400, -0.0795, -0.1434, -0.0897, +0.0144, +0.2679, -0.0472, +0.3482, -0.1740, -0.1166, -0.0111, +0.2472, +0.0246, -0.4565, +0.1551, -0.1582, -0.5669, +0.2494, -0.1287, -0.1204, +0.0194, +0.2248, -0.1516, +0.0207, +0.1093, +0.0377, -0.0904, -0.3342, -0.1444, +0.0697, -0.7370, +0.0026, +0.3587, -0.3404, -0.1049, +0.1460, +0.2110, -0.0948, +0.0207, -0.5619, -0.0783, -0.1985, -0.1016, +0.4217, -0.1562, +0.0041, -0.1838, -0.2449, -0.0854, +0.0799, -0.0302, +0.1423, +0.3082, +0.3283, -0.0281, +0.0788, +0.0031, +0.0979, -0.2028, +0.1922, -0.2306, +0.3849, -0.0142, +0.1072, -0.0440, +0.2191, -0.0470, -0.0593, +0.1763, +0.3983, -0.1238, -0.1037, -0.1137, +0.2317, +0.0110, +0.0663, -0.0086, +0.3465, -0.1617, -0.1074, -0.0111, -0.1016, -0.1653, -0.5738, -0.1034, +0.0073, -0.3014, +0.1830, -0.5022, -0.1954, +0.2247, +0.3253, -0.5072, +0.1528, +0.1081, +0.1963, +0.2882, -0.1681, -0.3225, +0.1462, -0.1778],
-[ -0.0621, -0.0065, -0.3092, -0.5112, -0.0462, +0.2084, +0.1376, -0.1595, +0.1336, +0.0280, -0.3018, -0.3498, +0.2132, -0.1355, -0.0954, +0.1179, -0.3046, -0.2161, -0.1197, +0.2271, +0.0295, +0.0027, +0.1243, -0.0162, +0.0080, +0.2658, -0.2266, +0.1659, -0.0576, +0.0842, -0.2875, -0.0643, -0.1392, +0.1416, +0.2400, -0.1915, +0.4021, -0.1661, +0.0662, -0.0546, -0.6020, -0.1279, -0.0794, -0.3350, +0.0300, +0.4654, -0.1535, -0.2146, -0.2576, +0.2092, -0.3546, -0.3744, -0.2862, +0.1899, -0.0562, +0.0341, -0.1427, -0.2849, +0.3981, -0.5012, -0.5592, -0.0965, +0.2206, +0.1673, -0.0776, -0.0799, -0.0701, +0.0430, +0.3948, +0.1132, -0.1944, -0.2089, +0.3454, -0.3165, +0.0127, -0.6068, -0.0567, -0.0150, +0.1678, +0.1062, +0.4325, +0.4888, -0.2010, +0.0061, +0.3314, -0.0006, +0.0562, +0.0097, +0.0471, +0.0274, -0.1399, +0.0915, -0.1559, -0.0540, +0.0179, -0.0970, -0.0034, +0.0097, -0.0536, -0.0886, +0.0977, -0.0228, +0.0384, +0.0912, -0.2899, -0.1391, +0.0680, +0.3766, -0.0591, +0.2232, +0.0645, +0.1108, +0.0218, -0.0100, +0.0267, +0.1913, -0.1655, +0.0788, -0.0509, +0.1814, +0.3006, -0.1914, -0.2365, +0.0325, +0.2767, -0.1839, +0.1656, +0.2733],
-[ -0.3155, +0.0389, +0.4308, +0.1264, -0.1675, -0.1606, +0.1710, +0.0357, -0.0301, -0.4734, -0.2261, -0.2828, -0.0484, +0.0398, -0.1375, +0.3210, +0.1318, -0.0164, +0.4136, -0.2305, -0.1101, -0.1665, -0.1446, -0.2818, +0.1191, +0.1567, -0.0592, -0.1728, -0.0280, -0.3277, +0.0417, +0.0186, +0.1433, -0.2331, +0.3428, -0.2597, -0.2454, +0.2911, +0.3652, -0.4929, -0.3262, -0.0204, -0.0260, +0.0530, +0.0388, +0.3999, -0.2114, -0.1950, +0.1543, +0.3246, +0.0052, +0.0575, -0.3312, +0.2627, +0.2212, -0.1697, -0.1365, +0.1331, +0.5793, -0.0025, -0.4241, -0.0567, -0.1132, +0.0464, -0.1080, +0.0713, -0.3824, -0.1196, -0.0296, -0.1167, +0.2810, -0.0735, -0.0077, +0.0522, -0.6794, -0.3256, +0.2814, +0.2920, -0.1246, -0.1849, +0.1548, -0.0411, -0.2095, -0.3796, +0.2976, -0.0762, -0.2796, +0.1759, -0.1947, -0.3021, +0.0684, -0.4101, +0.2244, -0.2481, -0.0010, +0.1781, +0.1309, +0.0754, -0.0103, +0.3149, -0.0591, -0.3657, +0.3807, -0.0334, -0.0809, -0.3037, +0.1025, -0.2377, +0.1171, -0.3675, +0.0805, -0.0576, +0.2433, +0.1461, +0.0423, -0.2294, -0.0224, -0.3102, +0.0088, -0.3047, +0.3373, +0.3147, -0.3534, -0.3323, +0.1021, +0.1079, -0.2814, +0.1050],
-[ -0.0245, -0.3205, -0.0550, -0.1720, +0.1572, -0.3884, -0.3543, +0.3351, -0.0099, +0.3584, +0.1196, -0.1128, -0.2587, +0.0681, -0.0158, +0.1732, -0.4172, -0.3108, +0.0267, +0.1163, -0.1939, -0.3101, -0.0248, +0.0025, -0.1209, -0.2918, +0.0999, -0.2748, -0.4083, +0.1218, +0.0835, -0.0999, +0.3580, +0.0629, +0.0313, -0.1036, +0.1496, +0.0291, -0.0168, +0.0395, -0.3607, -0.0815, +0.2716, +0.0342, -0.0334, +0.2555, +0.1654, +0.2385, -0.7064, +0.2392, +0.1459, -0.0964, -0.3108, +0.1539, -0.0590, -0.6246, -0.1621, -0.0648, +0.3419, -0.3539, -0.1544, +0.0877, -0.2943, -0.0809, +0.2675, +0.0130, +0.0175, -0.2230, +0.0429, -0.1819, -0.0576, +0.1783, -0.4099, +0.2766, -0.0295, -0.1116, +0.0644, +0.3015, -0.1678, -0.0302, -0.1903, -0.0368, +0.1126, +0.0354, +0.2034, -0.1899, +0.1751, +0.1841, -0.3028, +0.0064, -0.6946, +0.0640, +0.0450, -0.0954, +0.1070, -0.4622, +0.0043, +0.3927, -0.0924, +0.0170, +0.1991, +0.1029, -0.4010, -0.5260, +0.3099, +0.1169, -0.3201, +0.1383, +0.0304, +0.4974, +0.0375, -0.2105, +0.4277, -0.0385, -0.1893, +0.2602, +0.1801, -0.3028, +0.3519, -0.0072, +0.0575, -0.0439, -0.0147, +0.0971, -0.1810, +0.2790, +0.3070, +0.1567],
-[ -0.3593, +0.3125, +0.2294, +0.1004, -0.0686, +0.2577, +0.0183, +0.0088, -0.0294, -0.0669, +0.0566, +0.2798, -0.0858, -0.0387, +0.0556, -0.2810, +0.0240, -0.5967, -0.2381, -0.1677, -0.0648, -0.4832, +0.0483, -0.1887, -0.1410, -0.0185, +0.0323, -0.8195, -0.2986, -0.1578, +0.0644, +0.0243, -0.5457, -0.7528, +0.2299, +0.1152, -0.1551, -0.0403, +0.0335, -0.4697, +0.4705, +0.2231, +0.0153, -0.3863, -0.1568, -0.1220, -0.7400, +0.0445, +0.0043, -0.0574, +0.1877, -0.5959, -0.0730, +0.2549, +0.1350, +0.1365, +0.2877, -0.2223, -0.3385, -0.2589, +0.0974, -0.0737, -0.1565, -0.2140, +0.1631, +0.2298, +0.3280, -0.1305, -0.5843, +0.0501, +0.0569, +0.2176, -0.0486, +0.1723, -0.0183, -0.2988, -0.1125, -0.0802, -0.0333, -0.6227, -0.1824, -0.2171, -0.0956, +0.0165, +0.1714, +0.0483, +0.3055, -0.0871, +0.0996, -0.4671, +0.3062, -0.1808, +0.2514, -0.0150, +0.1948, +0.0196, +0.5776, +0.2378, +0.0446, +0.2286, +0.4647, -0.4668, +0.0440, -0.0914, -0.4420, +0.2602, +0.1791, +0.1920, -0.3575, +0.1086, -0.1176, -0.0526, -0.1220, +0.0907, +0.1720, +0.2100, -0.1284, -0.0736, -0.2041, -0.0051, -0.2761, -0.2553, +0.0368, -0.1468, -0.3486, -0.3645, +0.2823, -0.1184],
-[ -0.5915, -0.1844, -0.3926, +0.2582, +0.1572, -0.0428, -0.0333, -0.1803, +0.2298, +0.2510, +0.0504, +0.4947, +0.0043, -0.2448, -0.3863, +0.1712, +0.4349, -0.2526, +0.0374, +0.1115, -0.0840, +0.0980, +0.0218, +0.1006, +0.0466, +0.2759, +0.0063, +0.1454, +0.0132, +0.3720, +0.1462, -0.0060, +0.1965, +0.0738, -0.0544, +0.3279, -0.0334, +0.2048, -0.2162, -0.1511, -0.1620, +0.0853, -0.0094, +0.0964, +0.4726, -0.1591, -0.5189, +0.3182, -0.6680, -0.2251, +0.0435, +0.3286, -0.0167, -0.1225, -0.0941, -0.0467, +0.3194, +0.1592, +0.0540, +0.1801, +0.1991, -0.1422, +0.0651, +0.0313, +0.0565, +0.2132, +0.0259, -0.1215, -0.0465, +0.2803, +0.2929, +0.2781, -0.0417, +0.1751, -0.4823, +0.0149, -0.3763, +0.1523, -0.3554, +0.0224, -0.0570, -0.5339, +0.0914, +0.2395, +0.2099, -0.2714, -0.5664, -0.0861, -0.2449, -0.1557, -0.0394, -0.0997, +0.0458, +0.1191, -0.1428, +0.0270, +0.1114, +0.0614, -0.0379, -0.2785, +0.0696, +0.0675, -0.0510, +0.0598, -0.1880, -0.1675, +0.0851, -0.2465, -0.1332, -0.0188, +0.3592, +0.0251, -0.3794, +0.0634, +0.1697, +0.2868, -0.0108, -0.4742, +0.0380, -0.0434, -0.3096, -0.3023, -0.4648, +0.2064, -0.3723, +0.1903, +0.4308, -0.1828],
-[ +0.0533, -0.3794, +0.0423, -0.1411, -0.0702, +0.1252, +0.0546, +0.1258, +0.4106, -0.0027, -0.0846, +0.0810, +0.0087, -0.3069, +0.0778, +0.2796, +0.1095, -0.2539, +0.1197, +0.0380, +0.0192, +0.0596, -0.1093, +0.1209, -0.2235, -0.0996, +0.0827, -0.1329, -0.3149, -0.0009, -0.2465, -0.0712, -0.4329, -0.8865, +0.2083, +0.0827, -0.2544, -0.0157, -0.0426, -0.0675, +0.2012, +0.1082, -0.1642, -0.2945, -0.0814, -0.4239, +0.0364, -0.1153, -0.5297, +0.1528, -0.1251, -0.2883, -0.1123, -0.2345, -0.1243, +0.0758, +0.7976, -0.0334, -0.0996, +0.1035, -0.1435, -0.3511, -0.3324, +0.3685, -0.2246, +0.1072, -0.1100, -0.0016, -0.1830, +0.0871, -0.0546, +0.0046, -0.2693, +0.2749, -0.0977, -0.3543, +0.0312, +0.0677, +0.2466, +0.0712, +0.0769, +0.2314, -0.2621, +0.1475, +0.0944, +0.0745, -0.6371, -0.5103, -0.7600, -0.0428, -0.0085, +0.0334, -0.4792, +0.1178, +0.1895, +0.2825, -0.1221, -0.3944, -0.3124, -0.1355, +0.4852, +0.1503, +0.0985, +0.0310, -0.0247, -0.1419, +0.0191, +0.0767, +0.1392, +0.0055, +0.0104, -0.0360, -0.2649, -0.0748, -0.1387, +0.1615, -0.4313, -0.0540, +0.0122, -0.1171, -0.5336, -0.0798, -0.1408, -0.2159, +0.3831, -0.0502, -0.1978, -0.1882],
-[ -0.0209, -0.0106, -0.1195, -0.0162, -0.1540, +0.0713, -0.2198, -0.4215, +0.0070, +0.2775, +0.2773, +0.1619, +0.0935, +0.5805, -0.4682, -0.0517, -0.3038, -0.3515, -0.0305, -0.0407, +0.0964, +0.1052, -0.0705, -0.1846, +0.2016, +0.1809, -0.0402, +0.0914, +0.0949, +0.0608, -0.5812, +0.0606, -0.2100, +0.0656, +0.1924, +0.0935, -0.6964, +0.0585, -0.0135, -0.2383, +0.3479, -0.1264, +0.1433, +0.0711, +0.2887, +0.0683, -0.1336, -0.0104, +0.2000, -0.0962, -0.2787, -0.0522, -0.3700, +0.0234, -0.2526, +0.0739, -0.7853, +0.0755, -0.0885, +0.0962, -0.4285, +0.0612, -0.2318, -0.3520, -0.2696, +0.2609, +0.0439, +0.3858, +0.0346, -0.0265, -0.0480, +0.1523, -0.1361, +0.2122, +0.0862, -0.2789, -0.1964, +0.0047, -0.2021, -0.4251, -0.2270, +0.0885, -0.3531, -0.1673, +0.1966, +0.3255, +0.3677, +0.2451, +0.2206, +0.1645, -0.0509, +0.2135, -0.3057, +0.1289, +0.3612, +0.0751, -0.2921, +0.0211, +0.1665, -0.1668, -0.4720, +0.0643, +0.1883, -0.2529, -0.2803, +0.2548, +0.0644, +0.3636, -0.1947, +0.1404, -0.4078, +0.1706, +0.2401, +0.2231, -0.1344, +0.3388, -0.0723, +0.0942, -0.3626, +0.0288, +0.1905, -0.5602, +0.5321, +0.3668, -1.0004, +0.0396, -0.1636, +0.4003],
-[ -0.6009, -0.1764, +0.1790, -0.4413, -0.2962, -0.2103, -0.3839, +0.5148, -0.0473, -0.0155, -0.7608, -0.0242, +0.0403, -0.0810, +0.6040, -0.2872, +0.1655, +0.5840, +0.3057, -0.2255, -0.3538, -0.0057, +0.1084, -0.0653, -0.3629, +0.0327, -0.2162, +0.4229, -0.3050, -0.3602, +0.2457, -0.0923, -0.3345, +0.0993, -0.1577, +0.2566, -0.2755, +0.0090, +0.6055, -0.2832, +0.1900, -0.4449, -0.2049, +0.0905, +0.3360, -0.1946, +0.0111, +0.3941, -0.0312, +0.1419, -0.1522, -0.2697, +0.1142, +0.1145, -0.0213, +0.3917, +0.0264, +0.2655, +0.5183, +0.0405, +0.5094, +0.3597, -0.2183, -0.2867, +0.0580, +0.1505, -0.1060, -0.4326, +0.3122, -0.2913, -0.2615, -0.2251, +0.2661, -0.0916, +0.0263, +0.2415, -0.0010, -0.1383, +0.0939, -0.1808, +0.4885, -0.5949, +0.0661, -0.0190, -0.2434, +0.0903, +0.0335, +0.2637, -0.1724, +0.1309, +0.3296, -0.0518, +0.2669, -0.4770, +0.1438, +0.0770, -0.1400, -0.1650, +0.0405, +0.1128, +0.4488, -0.4113, +0.7159, +0.4405, -0.2670, -0.2373, +0.1552, -0.3004, -1.0047, -0.4442, -0.1569, -0.1711, +0.1751, +0.1856, -0.2171, -0.4630, +0.3209, +0.1233, +0.0427, -0.1323, +0.0847, +0.4391, -0.0433, -0.3804, +0.0234, +0.1642, +0.1413, -0.4204],
-[ -0.0382, +0.0697, +0.1954, +0.1232, -0.3950, +0.0410, -0.0058, -0.2217, +0.2788, -0.0926, +0.0316, -0.2992, +0.1791, -0.0543, -0.0835, -0.3470, -0.6962, -0.2087, +0.3590, -0.0578, +0.5484, +0.1435, +0.1078, -0.3716, +0.1744, -0.1441, +0.0480, +0.3284, +0.3241, +0.0057, +0.1665, -0.6800, -0.0559, -0.8574, -0.3013, +0.0994, -0.1789, -0.0773, -0.1086, -0.6569, -0.3416, -0.4008, +0.2978, +0.4831, -0.6239, -0.0037, -0.4366, +0.1802, -0.0730, +0.4826, -0.3240, -0.1030, -0.4562, -0.3693, -0.6823, +0.0320, -0.3837, -0.1544, -0.1656, +0.0836, -0.1672, +0.0018, -0.1044, +0.0743, +0.3075, -0.0115, +0.0808, -0.3066, -0.3586, -0.0228, +0.1209, +0.1033, -0.3932, +0.2474, +0.2178, +0.1313, -0.5326, +0.0827, -0.2049, -0.3722, -0.0023, +0.4377, +0.0418, -0.2483, -0.0836, +0.1767, +0.2034, -0.0476, -0.1573, +0.5566, +0.2577, +0.0562, -0.1836, -0.1882, +0.5193, +0.0079, -0.3756, +0.0340, -0.1755, +0.2817, -0.3039, +0.2948, -0.5376, -0.0007, -0.5880, -0.5485, +0.0770, +0.1617, +0.1887, +0.1492, -0.0807, -0.3650, -0.0540, -0.2106, +0.0963, +0.0005, +0.1230, +0.0178, -0.1458, -0.1242, -0.3049, +0.1069, +0.2919, +0.4823, -0.1985, +0.7479, -0.0910, +0.0032],
-[ +0.0999, +0.1129, +0.0788, +0.0146, -0.2431, -0.0529, -0.0087, +0.0799, -0.0451, -0.0487, -0.1577, +0.1812, -0.0007, +0.2515, -0.2335, -0.0300, -0.0498, -0.1109, -0.4123, +0.0599, +0.3430, +0.0924, -0.3990, +0.0617, -0.3780, +0.2513, -0.1506, -0.1866, +0.2113, -0.0043, +0.1018, +0.0475, -0.1532, +0.1009, +0.2183, +0.0201, +0.0020, +0.1105, -0.2671, +0.2815, +0.1835, -0.4436, -0.0833, -0.0476, -0.2875, -0.1545, +0.4175, -0.4003, -0.5049, -0.0427, +0.1898, +0.1642, -0.6990, -0.4362, +0.4377, -0.0246, +0.0071, -0.1784, +0.0141, -0.2318, -0.7877, +0.1683, +0.0151, +0.1172, -0.4099, +0.0956, +0.2033, +0.1802, -0.2204, -0.4969, -0.2697, +0.0227, -0.3113, +0.3833, -0.2007, -0.0491, +0.3474, +0.0419, +0.1888, +0.1764, -0.0694, +0.0286, +0.2823, +0.0565, +0.2045, +0.0872, +0.0970, +0.4547, +0.3809, +0.1010, -0.0356, -0.4323, +0.0784, -0.4963, +0.0527, -0.3812, -1.2797, -0.0429, -0.1506, -0.3298, -0.0177, -0.2223, -0.0632, +0.0620, +0.2290, +0.0297, +0.2258, -0.2569, -0.9111, -0.1175, -0.1230, +0.1327, +0.0528, +0.1498, -0.2203, -0.4755, +0.0978, -0.0368, +0.2662, -0.0755, +0.1348, +0.1874, -0.6464, -0.0296, -0.0794, +0.2649, -0.1350, +0.2607],
-[ -0.1078, -0.3764, -0.1381, +0.0869, -0.2514, +0.0132, +0.0976, +0.1634, +0.0764, +0.4871, +0.2087, +0.1099, -0.1876, -0.0077, +0.2282, +0.0318, -0.0299, -0.1394, +0.3569, +0.1685, +0.3756, +0.0565, -0.3884, -0.0255, -0.3361, -0.1637, -0.0515, -0.1319, +0.0730, -0.1038, -0.0948, -0.4817, +0.2756, +0.0562, -0.1065, -0.4606, +0.2205, +0.2330, -0.0423, +0.4746, -0.1326, +0.0192, +0.0178, +0.0128, +0.0501, +0.3476, +0.0619, -0.3693, +0.1192, +0.3615, +0.6273, -0.0511, -0.1759, +0.0573, +0.3286, -0.1206, -0.6524, +0.0031, -0.1262, -0.2288, +0.3611, -0.0265, -0.2484, +0.4420, -0.2119, -0.4760, -0.1120, -0.1045, -0.2260, -0.1096, +0.1383, +0.2693, -0.0881, +0.5958, -0.2183, -0.3405, +0.1038, +0.2003, +0.3021, -0.0557, -0.2225, -0.2724, +0.1702, +0.1224, +0.2801, +0.3151, -0.0497, -0.1870, +0.0490, +0.3350, -0.2218, -0.4137, +0.3848, -0.0899, -0.0908, -0.2358, +0.4977, +0.1214, -0.0100, +0.1173, -0.2396, -0.2299, +0.2137, +0.0491, -0.7133, -0.0605, -0.0278, +0.2408, +0.0260, -0.0671, +0.1543, -0.3159, -0.2227, +0.1132, -0.2261, -0.0250, -0.1055, +0.0683, +0.2335, +0.3028, +0.0236, -0.4458, +0.0361, -0.5405, -0.0442, -0.6218, +0.1025, +0.0115],
-[ -0.1324, +0.4260, -0.0147, -0.5004, -0.0002, +0.0140, +0.2995, +0.2757, -0.1943, -0.3776, +0.0813, +0.1067, -0.2905, -0.2673, -0.4926, -0.2956, +0.4968, -0.0698, +0.3007, +0.1967, +0.0180, -0.6847, +0.1337, -0.0526, +0.2531, +0.1462, +0.2974, -0.4869, +0.1167, -0.1194, +0.0620, +0.2449, +0.2284, +0.0841, +0.0588, +0.0418, +0.0891, -0.0507, -0.3089, -0.2124, -0.7492, -0.0292, +0.1146, -0.4990, +0.2225, -0.0327, +0.1191, +0.4086, -0.3497, +0.0704, -0.4547, +0.6996, +0.2663, -0.1322, +0.1495, +0.1802, -0.2279, +0.3308, -0.0674, +0.1613, -0.1077, +0.0122, -0.0466, +0.1396, -0.3371, -0.4765, -0.2150, -0.0451, +0.1198, -0.1538, -0.1045, -0.7362, +0.0373, +0.2297, -0.8950, +0.3760, -0.3753, +0.2895, +0.5398, -0.1854, +0.1583, +0.4056, +0.4843, -0.1372, +0.5370, +0.3985, +0.1525, -0.1650, +0.0182, -0.3630, +0.1980, +0.1669, -0.0329, -0.2845, +0.1200, +0.2052, +0.3971, -0.1553, +0.4036, -0.3132, +0.2581, +0.5021, -0.0966, -0.1518, -0.3456, -0.1915, -0.0816, +0.0773, -0.4633, +0.4096, -0.1858, +0.0532, +0.3825, -0.1854, -0.1189, +0.2893, -0.1457, +0.4268, +0.0553, -0.4428, -0.0553, -0.2409, +0.4323, -0.2580, -0.5131, +0.1144, -0.5439, -0.0324],
-[ -0.0951, -0.2398, -0.1207, +0.1439, -0.0112, +0.0403, +0.2109, +0.2822, +0.0714, -0.0061, -0.3167, +0.0310, -0.0433, -0.3120, -0.3933, +0.1612, +0.1771, -0.1223, +0.2668, +0.2125, +0.2258, -0.1501, -0.3047, -0.3328, -0.0758, -0.3413, -0.0997, -0.0709, -0.1279, -0.2422, -0.3422, +0.1265, -0.7878, -0.0616, -0.1220, -0.0724, +0.2619, -0.4331, +0.0029, +0.0384, +0.0974, -0.2454, +0.0472, +0.1363, -0.1616, +0.0008, +0.2507, +0.1707, +0.2489, -0.0522, +0.2306, +0.0220, +0.0743, -0.0148, +0.1893, -0.3129, -0.0313, +0.0656, +0.1938, +0.5220, +0.4117, +0.0448, +0.1463, -0.1240, +0.1775, +0.0772, -0.6103, -0.1047, +0.0278, -0.4253, -0.0560, -0.1347, -0.0628, +0.1269, +0.0191, -0.2100, -0.2395, -0.0466, -0.3006, -0.2604, +0.3735, +0.2593, -0.1534, -0.0976, -0.4843, -0.4349, -0.1046, -0.0600, +0.1310, -0.1107, -0.5161, -0.3044, -0.2743, -0.0216, +0.1310, -0.3426, -0.1695, +0.1092, +0.2327, +0.0663, +0.0718, +0.1479, +0.1967, +0.0784, -0.1789, -0.1532, -0.3373, -0.3602, +0.0155, +0.3476, -0.1938, +0.1991, -0.1335, -0.2120, -0.0719, -0.4957, -0.1461, -0.0870, +0.0535, +0.0260, -0.1487, -0.0610, -0.0131, +0.0925, +0.0041, +0.0706, -0.3249, +0.3076],
-[ +0.0541, +0.4655, -0.4223, -0.2331, -0.0581, +0.5284, +0.0901, -0.0378, +0.2620, -0.2267, +0.2851, +0.1581, +0.2739, +0.4589, +0.2652, +0.1516, -0.2050, -0.0756, +0.0852, +0.1785, +0.0971, -0.1604, +0.0089, +0.1134, -0.2514, +0.4193, +0.0698, -0.1063, +0.1228, -0.4191, -0.0360, +0.2030, +0.0081, +0.1340, -0.1340, +0.1388, +0.4455, +0.0481, -0.4398, -0.0168, -0.3045, -0.0132, +0.0051, -0.2227, -0.6544, -0.0354, -0.2273, +0.4308, +0.2649, -0.4759, -0.2885, +0.1836, -0.3740, +0.1777, +0.0127, +0.0164, -0.4780, +0.3226, +0.3391, +0.3711, -0.1510, -0.5826, -0.0895, -0.1212, -0.0941, -0.2657, -0.0334, +0.1040, +0.1568, -0.2225, -0.2873, +0.3292, -0.0350, -0.1347, +0.3132, +0.3021, -0.1590, +0.1355, -0.3929, +0.1691, +0.2215, +0.4122, -0.1927, +0.1729, -0.6266, -0.2215, +0.1797, -0.1774, +0.0737, +0.0295, -0.0419, +0.2605, +0.2356, +0.0833, -0.2404, +0.3106, +0.1529, -0.2097, +0.1342, -0.3574, +0.4464, -0.0297, +0.0385, +0.0653, -0.7114, -0.3072, -0.0939, -0.0451, -0.1536, +0.1754, -0.2410, -0.3136, -0.1038, -0.2600, -0.0292, +0.1328, -0.1258, -0.1659, -0.1376, -0.4014, +0.0359, +0.0221, -0.2341, -0.2213, -0.0071, -0.2549, +0.1757, +0.2961],
-[ -0.0045, +0.3948, +0.2514, +0.1126, -0.0968, -0.0414, +0.2683, -0.7427, -0.2207, -0.1312, +0.3067, +0.4822, -0.3512, +0.1159, -0.0726, -0.0937, +0.2098, +0.1605, +0.0238, -0.0439, +0.1858, -0.2014, -0.2361, -0.2284, -0.0099, +0.5000, +0.2455, +0.0184, +0.0253, -0.4009, -0.4215, -0.7544, -0.3624, -0.0567, -0.3579, +0.0272, +0.4209, -0.0857, +0.1130, -0.2006, -0.4367, +0.0771, +0.0491, +0.4899, -0.3251, +0.0659, -0.5332, +0.1157, -0.5820, +0.1902, +0.1078, -0.3355, -0.4025, +0.0392, +0.2063, +0.1495, +0.0616, +0.1051, -0.4266, +0.0420, +0.0316, +0.0614, -0.2423, +0.3125, -0.0700, +0.0286, +0.3859, -0.3231, +0.0262, -0.2398, -0.1127, +0.2679, -0.4434, +0.3665, +0.1111, -0.1690, +0.0793, +0.4125, -0.0157, -0.2707, -0.4898, -0.0642, +0.3456, +0.2465, -0.5142, -0.2889, -0.2712, -0.2100, +0.2719, +0.2298, -0.0976, +0.1110, +0.3158, -0.0420, -0.0406, -0.0493, -0.4078, +0.0645, +0.5344, +0.3139, -0.1080, +0.1376, -0.2784, -0.0195, +0.3964, -0.0877, -0.0800, -0.1061, -0.0690, -0.1506, -0.1644, -0.0561, -0.3988, -0.2351, -0.2194, +0.1311, -0.0139, -0.0584, -0.0780, -0.5172, +0.1721, -0.3860, -0.2823, +0.2836, -0.0941, -0.2243, +0.1657, -0.4716],
-[ -0.0641, -0.3698, -0.2212, +0.1342, -0.3151, +0.0310, -0.2151, +0.0262, -0.1678, +0.3159, +0.1253, -0.2815, +0.1199, +0.0624, +0.1208, +0.3487, -0.3874, -0.1471, -0.1021, +0.2997, -0.5750, -0.3173, +0.4029, -0.2965, -0.2111, -0.5049, +0.0513, -0.0693, -0.0425, +0.1383, -0.1910, -0.9026, -0.5273, -0.4481, -0.3645, +0.0307, -0.0129, +0.0054, +0.1593, +0.0492, -0.1182, +0.0122, +0.2354, +0.1718, +0.2423, -0.0851, +0.1524, -0.0100, +0.0852, -0.2707, +0.1983, -0.0776, -0.5558, +0.1277, +0.1845, +0.4677, +0.1273, -0.2698, +0.3344, -0.1939, -0.1121, -0.0507, +0.3284, -0.0188, +0.2441, +0.1043, +0.0416, -0.4772, -0.2314, +0.1646, +0.0371, +0.3291, -0.2173, +0.0456, +0.1533, -0.0692, +0.4015, +0.0198, -0.2382, +0.0169, +0.0245, -0.0967, -0.1479, -0.1204, +0.2310, -0.0040, +0.1312, +0.0790, -0.1959, -0.4960, +0.2153, -0.2277, +0.1761, -0.1988, -0.0739, -0.0226, +0.2609, -0.2217, -0.6110, -0.2360, -0.0289, +0.4274, +0.0961, +0.1861, +0.0216, +0.2856, -0.0471, +0.0139, +0.2482, -0.2179, -0.0888, +0.1368, -0.0699, -0.1128, +0.0713, +0.2249, -0.1332, -0.0250, -0.1889, +0.0095, -0.0816, +0.0571, +0.5398, +0.2336, +0.2598, +0.1348, +0.2462, -0.4051],
-[ -0.1438, -0.2210, -0.2563, +0.0057, -0.0217, -0.0290, -0.0967, +0.3873, +0.0832, -0.6249, -0.1031, +0.0495, -0.0176, +0.1595, +0.2288, -0.1882, +0.2508, -0.4344, +0.1012, -0.3476, +0.3677, -0.1171, +0.0703, -0.0809, +0.0032, -0.0119, -0.0557, +0.0087, -0.3490, +0.3963, -0.5019, +0.0933, -0.0076, +0.0988, +0.1388, +0.1707, +0.3001, -0.2023, +0.2833, -0.3746, +0.0634, -0.3222, +0.0022, -0.2720, -0.0643, -0.1532, -0.1900, -0.2513, +0.3039, +0.1634, -0.3249, -0.2999, +0.1867, -0.0237, +0.0407, -0.1726, +0.1812, -0.1945, +0.0753, -0.0624, +0.2736, -0.1881, +0.3375, +0.0451, -0.4780, +0.1311, -0.3083, +0.0327, +0.0122, +0.1714, -0.1143, +0.2245, +0.1845, -0.1023, -0.0519, -0.2336, -0.5005, -0.0854, +0.3170, -0.1398, -0.0307, +0.1428, -0.0750, -0.1836, -0.3896, +0.2932, -0.3616, +0.1044, -0.1114, +0.3557, +0.0386, +0.1663, +0.1116, -0.1692, +0.2538, -0.0329, +0.1425, -0.1310, +0.3025, +0.2110, -0.1981, -0.5602, +0.0119, +0.0663, -0.0021, -0.0495, +0.0595, -0.2126, -0.2603, +0.1909, -0.0732, -0.3379, +0.3198, +0.1815, +0.2507, -0.2851, +0.2290, +0.0121, +0.2947, +0.1516, -0.4416, +0.3535, +0.0362, +0.4227, +0.2058, -0.3077, -0.7662, +0.0039],
-[ -0.0084, +0.1321, -0.0739, +0.1690, -0.2521, -0.1354, -0.2330, +0.3076, -0.3387, +0.3118, -0.1261, -0.5501, -0.1610, -0.1947, -0.1845, -0.4091, -0.0699, -0.1083, +0.1431, +0.0793, -0.3411, -0.4424, -0.3152, -0.2997, +0.0218, +0.0610, -0.3120, +0.5040, -0.1015, +0.2065, +0.2869, -0.5926, -0.4347, -0.1448, +0.1443, +0.0241, -0.0808, -0.3136, +0.0794, +0.1769, -0.2137, -0.3096, +0.1118, -0.2514, +0.0731, -0.1291, +0.3789, +0.3855, +0.1416, +0.2163, +0.1692, -0.0849, -0.5013, +0.2453, -0.2681, +0.1146, -0.0248, +0.5772, -0.0399, -0.1557, +0.4552, -0.0198, -0.4703, -0.2443, +0.1341, -0.1853, +0.2554, -0.3664, -0.0049, -0.1806, +0.1591, +0.4685, -0.3846, +0.3275, -0.5392, -0.0238, +0.2383, +0.1893, -0.2952, -0.1149, +0.3631, +0.0357, -0.3412, +0.5988, -0.0815, -0.0911, +0.0158, +0.0341, +0.0265, +0.2634, -0.0081, -0.2504, -0.3421, +0.2368, +0.5963, +0.1872, +0.0543, -0.0797, +0.1321, -0.0278, -0.4313, +0.1046, -0.0670, -0.0294, -0.0356, -0.2410, +0.0999, +0.3321, +0.0379, -0.1456, +0.2748, -0.0311, +0.2177, -0.1558, +0.0286, -0.1212, -0.0144, +0.1093, -0.0799, -0.5326, +0.3965, -0.1177, -0.2089, -0.2105, -0.5678, -0.0271, +0.0421, -0.1457],
-[ -0.4219, -0.0642, +0.1520, +0.2730, +0.0215, +0.2991, -0.0341, +0.3181, +0.1450, -0.2327, +0.0440, +0.2632, +0.3848, +0.2312, +0.3035, -0.4698, +0.3574, +0.1646, -0.1934, -0.2782, +0.4133, +0.0815, -0.3259, +0.3120, -0.0893, +0.0461, +0.2430, -0.1055, +0.3371, +0.2021, -0.0185, +0.0365, +0.5522, +0.1110, -0.0574, +0.1748, -0.5135, +0.3464, -0.0352, +0.2477, -0.5143, +0.0434, -0.0307, +0.0653, -0.1172, -0.1443, -0.0161, +0.2203, +0.1484, -0.1537, -0.0051, -0.2373, -0.0219, -0.4247, -0.2263, -0.0316, +0.3961, -0.1794, -0.1073, -0.0504, +0.1702, -0.2868, -0.0476, -0.2767, +0.2287, -0.4326, -0.1071, +0.0696, -0.7776, +0.2128, -0.1849, +0.3147, +0.2155, -0.2478, -0.0849, +0.3377, -0.4766, +0.0997, +0.0508, -0.3671, +0.0700, +0.2319, +0.1564, -0.0436, +0.1947, +0.1576, +0.1914, +0.1839, +0.1461, -0.1716, -0.2761, -0.1924, -0.0864, -0.4610, -0.0227, -0.1417, -0.3146, +0.1264, -0.2383, -0.1555, -0.3563, +0.0651, +0.2672, +0.1644, -0.0204, -0.3279, -0.2122, +0.1154, -0.1318, -0.1615, +0.0484, -0.4275, -0.5074, +0.2201, -0.5123, -0.3129, +0.2558, -0.0904, -0.1861, +0.1214, -0.4799, +0.1607, +0.2893, -0.2543, -0.3875, +0.4410, +0.0593, -0.0176],
-[ -0.1470, -0.2327, +0.0815, -0.1459, -0.2291, -0.0562, +0.1376, +0.1604, -0.0832, +0.2067, +0.0586, -0.0354, +0.2460, -0.0497, -0.2480, -0.6084, -0.2743, -0.5487, -0.0208, -0.0933, +0.1163, -0.1184, -0.3381, +0.3618, -0.2309, +0.0550, -0.1798, -0.0875, +0.2540, -0.4719, +0.0159, -0.0701, -0.1830, -0.1771, -0.0436, -0.0899, -0.1044, +0.1469, -0.1417, +0.1335, -0.0024, -0.2346, +0.2030, -0.2100, +0.2577, -0.0560, -0.2534, -0.2908, +0.6886, +0.0102, +0.0461, +0.0156, +0.1817, -0.1090, -0.2347, -0.6208, -0.0059, -0.7716, -0.3923, +0.0970, -0.3165, +0.0535, -0.3916, +0.1415, +0.3424, -0.1105, -0.3802, +0.0150, +0.4469, -0.2943, +0.0476, -0.3771, +0.3636, -0.0410, -0.0079, +0.2929, +0.3688, -0.4768, +0.2274, +0.1870, +0.0247, +0.1752, -0.0923, +0.3461, -0.0168, +0.0372, +0.2772, -0.2258, +0.2398, -0.0877, -0.0927, -0.0272, +0.3592, -0.4846, -0.1541, +0.2650, -0.0134, -0.1856, -0.1688, +0.2972, +0.3202, +0.2967, +0.0885, +0.1266, -0.3913, +0.6079, -0.1323, +0.2003, +0.0828, -0.4133, -0.0906, +0.2161, -0.0804, -0.0228, +0.0707, -0.2550, -0.1726, +0.2102, +0.3182, -0.2587, +0.0575, -0.0176, +0.0198, -0.1165, -0.5896, +0.1733, -0.3348, -0.1469],
-[ -0.3824, +0.2283, +0.2410, +0.2186, -0.5470, +0.1103, -0.0149, -0.2098, -0.1996, +0.2482, -0.3463, -0.1121, +0.3371, -0.0417, +0.0075, -0.0541, +0.2727, +0.2832, +0.2670, +0.3552, -0.4192, -0.0801, -1.0397, +0.2101, -0.2077, +0.3952, +0.1731, -0.3074, -0.0472, -0.1154, +0.2872, -0.0417, -0.0287, +0.2925, -0.4077, +0.0301, +0.3340, +0.2400, -0.1239, -0.4566, -0.1001, -0.2440, +0.3035, -0.1512, +0.5552, -0.0397, -0.2366, -0.1716, +0.1308, -0.6144, -0.3075, +0.1430, +0.0632, -0.4414, -0.4012, -0.2610, -0.1726, +0.0840, +0.3784, -0.1463, -0.1945, -0.1464, +0.0453, -0.6733, +0.1245, -0.1531, -0.0880, -0.0046, +0.1832, +0.2703, +0.2005, +0.2362, +0.1479, -0.1326, +0.2796, +0.3101, +0.0988, +0.0696, +0.1107, +0.1591, +0.3960, +0.1939, -0.1844, -0.0916, -0.4749, -0.0713, +0.1138, -0.3296, +0.0143, +0.1719, +0.1194, -0.1216, +0.1262, -0.0051, +0.1966, -0.0664, -0.2489, -0.3240, +0.1552, -0.3418, -0.2673, +0.0230, +0.0407, +0.1522, -0.0475, +0.1207, -0.2826, -0.0798, -0.5290, -0.0987, +0.1027, -0.0802, +0.3484, -0.1592, +0.2472, -0.1101, -0.1823, -0.0829, -0.5066, -0.1147, -0.0391, -0.0087, -0.3388, +0.1701, -0.3465, -0.0286, -0.5400, -0.1208],
-[ +0.2132, -0.2038, -0.3343, +0.3540, +0.1567, -0.0095, -0.0718, -0.2499, -0.1994, +0.2980, -0.5719, -0.0183, +0.1170, +0.1715, -0.0344, -0.2624, +0.2696, -0.0722, -0.2631, +0.1950, -0.2201, -0.2901, -0.2445, -0.1541, -0.1788, +0.0809, +0.0669, -0.0549, -0.0294, -0.2629, -0.2968, -0.2379, +0.0772, +0.2484, -0.1016, +0.1574, -0.1376, -0.1910, +0.0483, +0.0839, -0.1902, +0.3949, +0.1495, +0.2443, -0.1737, -0.3951, -0.0341, -0.1647, +0.3102, -0.1957, +0.1148, -0.1085, +0.2525, -0.2577, -0.2769, -0.0665, -0.1045, -0.0036, +0.4137, -0.1179, -0.0173, -0.1624, +0.1537, +0.0199, -0.4035, -0.7585, -0.1749, +0.0859, -0.5522, -0.2950, +0.2526, -0.0636, +0.2784, -0.0519, -0.0059, -0.0829, -0.2314, +0.0356, +0.0620, -0.3004, +0.3659, +0.1431, +0.0440, +0.0523, +0.0418, -0.3607, -0.0321, +0.5865, -0.3718, -0.0894, +0.0159, -0.3719, +0.1833, -0.2633, -0.0643, +0.1656, +0.1638, -0.0804, +0.0640, -0.2463, -0.2730, +0.1763, +0.5623, -0.1374, +0.0886, +0.1344, -0.3440, -0.1357, -0.6086, +0.0246, +0.1226, -0.1262, -0.0284, -0.1652, +0.2808, +0.0982, +0.1970, -0.0293, +0.0909, -0.2475, +0.1229, +0.0832, +0.2307, -0.0334, -0.0804, +0.0204, -0.2117, -0.0586],
-[ +0.0675, -0.2419, -0.0014, -0.4854, +0.0023, +0.2432, -0.0517, +0.1820, +0.4027, +0.0418, +0.0799, +0.0445, -0.0124, +0.0331, +0.2243, -0.2098, -0.2624, +0.2788, -0.3206, +0.0902, -0.2575, +0.0033, -0.2722, -0.4836, -0.1144, -0.1933, +0.2316, +0.0758, +0.1769, +0.1349, +0.1459, -0.2154, -0.5491, -0.3184, -0.2450, +0.1040, +0.1301, -0.1167, -0.3166, +0.0286, +0.2324, -0.1594, +0.0272, -0.0249, +0.1742, -0.0705, -0.6673, +0.0315, -0.0686, -0.0554, +0.4494, -0.1243, +0.0745, -0.1677, +0.1072, -0.4070, +0.1072, +0.2513, +0.0360, -0.2995, +0.2032, -0.3525, +0.3108, -0.2647, -0.0185, -0.5729, -0.5350, +0.1348, -0.1505, -0.1331, +0.1911, +0.0579, +0.1075, +0.5838, +0.0835, +0.1951, -0.0697, -0.0039, -0.0510, -0.0248, -0.0074, +0.0340, +0.1015, +0.2119, +0.3729, -0.2766, -0.3635, -0.6286, -0.0736, +0.1996, +0.1481, +0.3434, +0.1094, -0.1140, +0.5084, -0.5502, -0.0116, -0.4196, +0.0949, -0.3190, +0.1712, +0.3119, -0.1757, +0.1424, -0.5219, +0.0941, -0.1334, +0.3036, +0.1787, +0.2328, -0.2946, -0.3538, +0.1910, +0.2116, +0.0395, +0.0577, -0.1220, +0.1180, -0.1978, +0.0592, -0.0584, +0.0025, -0.1686, -0.0445, -0.2022, -0.1837, -0.2602, -0.1407],
-[ -0.1744, -0.8762, -0.3103, +0.2088, +0.0916, +0.1287, +0.1121, -0.0153, +0.4726, +0.2825, -0.2776, +0.0350, -0.4953, -0.2063, -0.0148, +0.2523, -0.1347, +0.5798, -0.2609, +0.0847, +0.0427, -0.3157, +0.1366, +0.0639, -1.1886, -0.3338, +0.2632, +0.2140, +0.1212, +0.0615, +0.1265, -0.3571, -0.3810, -0.1950, +0.1283, +0.4208, -0.0645, +0.2335, -0.0536, -0.1666, -0.5196, -0.1766, +0.0389, -0.0928, +0.2835, -0.2057, -0.1431, -0.1885, -0.1333, +0.3195, +0.5281, +0.1723, +0.2516, -0.4471, -0.0755, -0.1637, -0.1736, +0.2543, -0.4973, +0.3659, -0.4391, +0.1213, -0.2301, +0.3803, +0.0656, -0.0887, +0.2067, +0.1039, -0.4810, -0.0604, +0.1715, +0.1020, +0.1995, -0.3312, -0.0330, +0.0063, +0.2141, +0.1343, +0.1104, -0.2821, +0.0149, -0.0748, -0.6820, +0.1135, -0.2427, +0.0882, -0.3350, -0.4962, +0.0746, -0.5144, -0.2352, -0.6495, +0.1126, -0.0372, +0.1189, +0.1819, -0.2603, +0.2579, +0.0144, -0.0856, +0.0396, +0.4175, -0.3289, +0.0564, -0.5482, -0.3679, -0.2993, +0.2652, -0.3313, -0.0960, -1.0742, +0.1309, -0.0777, +0.0461, +0.1375, -0.2558, +0.3850, -0.0150, -0.0683, -0.2016, +0.1779, -0.0040, -0.5633, +0.4249, +0.0947, -0.1701, -0.1790, +0.0456],
-[ +0.2227, +0.3859, -0.5481, +0.3966, -0.1252, -0.1814, -0.3651, +0.0602, -0.0624, -0.1084, -0.0863, -0.1190, -0.3369, -0.2076, -0.0288, +0.0967, +0.1341, -0.1406, +0.1152, +0.1108, +0.1126, +0.0225, +0.0296, -0.2515, +0.0096, -0.3407, +0.1904, +0.0932, +0.1056, -0.2407, -0.3035, -0.6642, +0.0766, -0.0051, -0.1253, -0.0573, -0.1765, +0.0353, -0.0813, -0.0554, +0.0684, -0.1930, +0.3949, +0.5141, -0.2099, -0.1756, +0.2932, +0.0988, -0.3515, -0.0981, +0.2816, -0.2699, -0.0574, +0.1006, +0.1862, -0.2341, +0.0580, +0.0033, -0.5301, +0.1795, -0.4353, +0.2311, -0.4071, +0.0076, -0.3294, +0.1999, -0.0014, +0.0322, -0.0437, +0.2237, +0.1607, -0.0705, +0.1966, +0.1185, +0.0895, +0.0366, +0.2373, +0.3228, -0.0158, +0.1706, +0.2027, +0.2311, +0.1457, -0.0654, -0.1269, +0.1568, -0.1764, +0.2731, -0.1151, +0.1550, +0.0696, -0.3907, -0.0029, +0.0559, -0.0434, +0.2866, -0.5386, -0.0351, +0.1053, -0.4544, +0.4387, -0.2036, +0.3323, +0.1084, +0.1890, -0.1239, -0.0291, +0.0868, -0.2892, -0.4491, -0.0075, +0.2157, -0.4047, -0.1612, +0.1290, -0.2041, -0.3116, -0.0338, +0.3411, +0.3371, +0.0646, +0.1989, -0.4181, +0.0404, -0.6931, -0.5505, -0.1889, -0.0642],
-[ +0.2256, +0.2926, -0.4043, -0.3903, -0.4751, -0.2227, -0.0575, -0.0882, +0.2724, -0.2748, -0.0479, +0.0765, +0.3881, +0.1026, +0.4699, +0.0094, +0.1006, -0.4406, -0.7706, +0.0133, +0.1709, -0.1822, -0.1068, -0.4774, -0.1233, +0.2721, +0.1207, -0.1251, +0.3195, +0.2374, -0.1329, -0.1427, +0.0076, +0.0051, -0.1095, -0.0654, -0.0352, -0.5934, -0.0047, -0.6171, +0.1857, +0.1955, -0.1583, -0.2563, +0.0400, -0.0183, -0.0950, -0.0957, -0.0747, +0.0212, +0.2658, -0.2555, -0.1685, +0.0820, +0.0191, +0.1119, -0.1408, +0.1895, -0.3520, -0.1373, -0.0728, +0.1701, -0.2122, -0.4124, -0.1474, +0.0735, +0.4498, +0.0624, -0.4918, +0.2062, -0.2238, -0.1642, -0.4840, +0.1531, -0.1195, -0.7067, +0.1031, -0.1102, +0.1100, -0.1363, +0.2572, -0.3112, -0.0680, -0.0723, -0.1689, +0.0442, +0.0321, +0.0800, +0.0119, +0.0997, +0.0725, -0.0631, -0.0758, +0.2844, -0.2049, +0.2828, +0.2275, -0.1323, +0.0606, -0.0013, -0.3762, +0.4734, -0.0862, +0.1600, -0.2358, -0.2673, +0.1551, -0.3200, -0.3787, +0.2681, +0.1187, -0.6766, -0.3171, -0.1608, +0.2374, +0.1025, -0.1801, -0.0285, +0.5813, +0.0297, -0.1882, -0.1819, +0.3774, -0.4983, +0.0110, -0.1292, -0.0681, -0.3819],
-[ +0.3995, +0.0792, +0.2270, -0.1042, +0.0255, +0.0016, +0.0451, -0.4750, +0.2975, -0.0082, +0.1990, -0.2409, -0.1112, -0.0032, -0.0150, +0.0236, +0.0402, -0.4979, +0.0779, -0.8938, +0.1598, -0.2129, -0.1096, -0.0302, +0.1266, +0.2907, +0.1035, -0.0407, -0.0064, +0.6170, +0.1004, -0.2439, +0.2264, +0.1643, +0.3614, -0.1352, -0.0361, +0.2193, -0.3154, -0.0397, +0.1876, +0.1772, -0.0195, -0.2464, -0.1978, +0.0346, +0.1175, +0.2480, -0.2430, -0.1466, +0.1590, -0.7108, +0.2289, -0.1052, +0.1022, +0.2594, -0.2415, -0.4879, -0.1105, +0.2639, +0.2423, -0.2152, -0.3059, +0.0374, -0.1305, -0.1193, -0.0154, +0.0652, +0.0368, -0.1518, -0.0899, +0.1403, +0.4033, -0.4159, -0.1961, -0.2257, -0.7238, -0.1221, -0.2337, +0.1632, -0.1829, +0.1615, +0.0519, -0.1620, +0.0202, +0.2269, -0.0179, +0.1654, +0.2221, +0.1940, +0.2173, -0.1658, -0.0575, -0.2079, +0.0749, +0.2243, +0.2232, -0.2720, +0.2174, +0.1650, +0.0177, -0.9978, -0.1015, -0.1992, +0.1488, +0.0473, +0.0417, -0.1459, -0.1290, -0.4732, +0.0117, +0.0948, -0.4470, +0.3781, -0.2532, +0.2187, +0.1776, +0.3040, -0.1388, +0.1961, -0.3581, +0.0463, -0.2575, -0.2168, -0.1670, +0.0914, +0.1767, +0.0329],
-[ -0.0719, -0.0129, +0.1824, +0.1606, +0.0118, +0.4255, -0.3841, +0.0168, -0.2329, +0.2727, -0.0545, -0.0857, +0.2463, -0.0496, -0.1933, +0.1361, -0.3163, -0.1022, -0.4908, +0.2080, -0.8547, -0.0581, +0.0596, +0.0500, -0.0236, -0.4260, +0.1134, +0.3017, +0.3550, +0.2028, +0.0589, -0.1067, -0.2976, -0.0816, -0.2182, -0.3664, -0.4302, +0.0603, -0.2987, -0.0127, +0.1153, +0.5534, -0.5987, +0.1623, +0.2119, +0.1387, +0.4423, +0.2260, +0.2509, +0.0003, +0.1126, -0.3886, +0.4243, -0.2974, -0.4794, -0.1321, +0.0050, -0.3510, -0.1899, +0.1342, -0.0394, +0.2204, +0.2973, +0.0876, +0.0616, +0.0392, -0.0947, +0.4138, +0.1118, +0.1043, -0.1129, -0.1313, -0.2991, -0.0102, -0.5176, -0.2947, +0.2615, -0.4811, -0.5075, +0.4473, +0.2060, +0.3958, -0.0906, -0.3490, +0.2906, -0.1646, +0.2291, +0.2641, -0.0809, -0.4005, +0.4230, +0.1208, +0.1348, -0.3537, -0.8684, -0.3071, -0.2783, +0.4847, +0.2391, +0.3747, +0.0634, +0.0961, -0.6026, +0.2197, -0.1453, -0.5520, -0.2687, -0.0875, -0.2119, -0.1724, -0.2896, +0.3976, -0.1967, +0.3804, -0.1371, +0.0116, -0.0573, +0.1395, -0.2590, +0.5540, +0.4139, -0.1111, +0.0032, -0.5963, +0.1533, +0.1480, -0.0091, -0.0380],
-[ +0.0012, +0.1069, +0.2834, +0.5471, +0.3943, -1.0956, -0.6526, +0.1492, -0.2587, +0.2581, -0.2517, +0.1173, -0.3567, -0.1059, -0.3055, -0.5180, -0.3182, -0.4056, +0.3925, -0.7240, +0.4440, -0.3679, +0.2120, -0.4817, -0.2700, -0.2675, -0.0082, +0.1994, -0.0305, +0.0769, -0.1151, +0.2111, +0.2388, -0.2470, -0.5172, +0.1661, -0.3072, -0.6651, +0.3812, +0.2448, +0.3609, +0.0592, -0.4010, -0.0854, +0.0913, -0.2651, -0.2003, +0.0285, -0.1954, -0.0110, -0.1873, +0.0350, -0.6736, +0.1600, +0.2878, +0.2839, +0.1939, +0.1168, +0.1899, -0.5686, +0.1056, +0.1304, -0.1370, -0.0459, +0.2497, -0.3285, +0.1665, -0.2200, -0.2023, +0.0026, +0.0299, +0.1613, -0.1322, +0.3270, -0.3678, -0.4051, +0.1920, -0.4154, -0.3370, -0.3895, -0.4571, +0.2233, +0.7171, -0.3209, -0.0292, -0.0030, +0.1388, -0.0513, -0.3499, +0.3362, +1.1707, +0.2713, -0.2278, -0.0987, -0.0367, -0.4828, +0.0630, +0.0861, -0.2023, -0.0871, -0.3521, +0.0436, -0.1448, -0.0160, +0.2777, +0.2555, +0.0985, +0.3363, -0.3503, +0.2365, +0.1922, -0.3820, -0.0583, -0.5146, -0.2775, -0.2208, -0.6312, -0.3039, +0.0200, +0.0497, +0.2308, -0.1536, +0.0240, -0.1044, +0.1552, -0.0842, -0.2783, -0.6521],
-[ -0.1033, -0.2561, -0.4736, -0.0597, -0.0797, -0.4603, +0.4766, +0.1068, +0.2594, -0.0076, -0.1516, -0.0376, -0.2234, -0.3159, +0.0309, -0.1892, -0.1140, +0.0944, +0.2417, -0.0854, -0.2391, -0.2417, -0.1581, -0.1739, +0.2623, -0.0809, -0.1402, -0.3131, -0.0720, -0.0981, -0.3073, +0.0374, -0.2073, -0.0267, +0.3198, -0.0897, +0.0588, +0.1556, -0.2769, +0.1468, -0.1361, +0.1517, +0.0508, +0.1800, -0.0042, -0.1437, +0.1092, +0.1007, -0.2394, -0.1057, -0.0724, +0.1075, -0.2697, -0.0019, +0.1269, -0.4539, -0.0310, -0.5206, +0.0402, +0.2359, +0.1970, -0.0350, -0.1356, -0.1909, -0.2260, -0.2991, +0.1422, +0.0233, -0.1608, +0.1696, +0.2657, -0.0255, +0.1677, +0.1096, -0.1565, -0.2521, -0.2247, +0.4512, -0.1818, -0.3770, +0.0591, +0.0206, +0.2336, -0.3824, -0.1396, -0.0481, -0.4078, -0.0919, +0.2656, -0.4486, -0.3153, +0.3548, +0.0438, -0.1504, -0.2451, -0.0608, +0.2721, +0.5385, -0.5558, -0.0335, -0.1426, -0.1339, -0.1453, -0.3019, -0.0639, +0.2590, +0.0014, -0.1803, +0.0016, +0.1237, +0.0215, -0.4817, -0.3749, -0.3583, -0.0471, +0.3784, +0.0463, -0.1954, +0.3093, +0.0892, +0.1876, -0.2148, -0.4419, -0.0425, +0.0657, -0.0078, -0.0399, +0.0840],
-[ +0.2048, -0.0109, +0.1986, +0.0436, +0.0085, -0.2514, +0.0744, +0.3315, -0.2824, -0.1131, +0.2103, +0.2959, +0.1904, +0.1686, -0.2302, +0.0652, +0.2257, -0.0390, -0.1976, +0.4371, +0.3736, +0.1314, -0.0126, +0.3901, +0.2941, +0.3069, -0.0508, +0.1621, +0.0574, +0.0418, +0.0242, -0.0419, +0.1573, +0.0410, +0.0999, -0.4115, -0.5998, -0.2344, -0.0975, -0.2688, +0.3834, +0.1553, -0.1397, +0.3657, -0.0091, +0.3628, -0.1618, +0.2892, +0.0037, -0.2724, -0.1981, -0.2372, +0.1146, -0.3035, -0.1188, -0.0730, -0.0547, +0.2505, +0.2670, -0.2053, -0.1383, -0.1420, +0.2132, -0.1123, -0.0540, -0.0160, +0.0854, -0.0068, +0.1348, +0.0903, +0.2632, -0.2247, +0.2532, +0.0560, -0.3529, +0.0306, -0.0395, +0.0279, -0.1100, -0.0622, +0.2833, +0.4174, +0.3505, +0.1969, +0.2820, -0.2032, +0.4617, +0.1298, +0.4777, -0.0402, -0.2765, +0.2737, -0.1355, -0.0264, -0.1436, +0.1520, -0.0959, +0.2017, -0.0632, +0.4270, +0.2518, +0.4939, +0.1018, +0.0747, +0.1341, +0.0282, +0.2620, +0.0788, -0.3611, -0.2884, +0.0078, +0.2888, +0.3522, +0.2354, -0.2122, -0.2427, +0.2523, +0.1396, -0.0883, -0.3950, -0.2682, -0.0492, -0.0755, -0.2473, +0.4263, +0.1355, -0.0157, +0.1215],
-[ -0.6594, -0.1441, -0.6773, +0.0221, +0.2166, +0.1332, +0.4537, -0.3027, +0.2430, +0.1959, -0.0301, +0.3205, +0.0271, -0.0874, -0.0352, +0.2214, +0.1944, +0.0452, -0.1779, +0.4921, +0.1605, -0.5882, -0.0086, +0.0444, -0.0399, +0.0324, -0.1361, -0.0327, +0.0511, -0.0984, -0.1174, +0.2776, -0.1695, -0.1711, +0.0936, +0.2987, -0.1364, -0.1538, -0.3138, +0.3584, +0.0546, +0.1571, +0.0399, -0.4413, +0.1119, +0.1473, +0.2313, -0.0097, +0.0350, -0.7444, -0.2951, +0.3243, +0.3613, -0.0437, +0.0579, -0.4394, +0.2956, +0.2459, -0.3762, -0.2147, -0.0802, +0.1008, +0.1602, -0.0851, -0.1126, -0.0523, -0.3132, +0.1352, +0.1302, -0.1389, -0.0498, +0.0982, -0.1858, +0.1293, -0.1504, -0.1349, -0.3510, +0.2715, +0.1284, -0.1167, +0.3469, +0.0383, -0.0128, -0.5008, -0.2260, +0.0122, -0.1545, +0.0764, -0.0789, -0.1429, +0.0672, +0.1962, +0.1719, +0.3646, -0.4545, -0.0100, -0.4631, +0.1818, -0.0828, +0.0147, -0.1522, -0.3076, +0.0254, +0.1547, +0.1381, -0.0803, +0.1292, -0.1365, +0.1041, -0.1373, +0.0217, +0.1911, +0.1273, -0.5073, -0.1208, +0.0419, -0.1274, -0.1256, -0.1218, +0.2354, +0.2424, -0.5111, -0.0158, +0.3000, -0.0153, -0.1388, -0.3299, -0.2895],
-[ -0.0294, -0.4273, -0.5489, +0.0763, +0.1031, +0.1471, -0.0484, -0.1350, -0.0842, +0.4926, -0.1590, +0.1943, -0.1764, -0.3718, -0.1390, -0.1777, +0.0206, +0.1419, +0.0295, -0.0456, +0.3345, -0.0964, +0.1943, +0.3729, +0.2595, -0.1374, +0.1387, -0.1465, +0.2086, +0.1584, +0.0832, +0.2783, +0.2321, +0.0113, +0.0094, -0.1108, +0.5348, -0.0977, +0.1038, +0.0583, +0.3153, -0.0785, -0.1228, +0.1034, -0.2553, +0.2126, -0.1070, -0.3386, -0.0340, +0.0104, -0.2674, +0.0326, +0.0932, +0.2535, -0.0153, +0.2262, +0.1104, -0.0296, -0.7565, +0.3795, +0.0197, +0.2188, +0.2597, +0.1066, -0.1249, +0.2491, +0.0502, +0.1698, -0.2272, +0.1036, +0.0705, -0.2946, +0.0419, +0.3711, -0.1070, -0.1108, +0.3419, -0.1523, +0.2069, -0.4476, -0.2259, -0.0181, -0.3392, +0.0217, -0.1096, -0.1765, -0.1857, +0.0584, -0.4739, -0.2082, -0.3502, +0.0002, -0.2312, +0.4239, +0.0566, +0.2188, +0.0941, +0.4267, +0.3656, -0.4763, +0.1702, +0.2638, +0.2592, -0.1975, -0.0054, +0.0141, -0.4314, -0.2415, -0.1606, +0.1459, -0.0972, +0.1166, +0.0096, +0.0501, -0.1138, +0.3070, +0.2190, +0.1775, -0.6364, +0.0455, +0.1728, -0.4195, -0.1555, -0.0181, -0.0655, -0.2914, +0.1061, +0.1944]
+weights_dense2_b = np.array([
+ -0.1167, -0.0510, +0.1155, +0.2151, -0.0416, +0.1452, -0.0794, +0.1217,
+ -0.0268, +0.1016, +0.1274, -0.0271, -0.1298, +0.0793, +0.0404, +0.0955,
+ -0.0855, -0.0578, +0.3129, +0.0950, -0.0090, -0.0090, +0.2334, +0.1715,
+ +0.1043, +0.0024, -0.0009, +0.0342, +0.0742, +0.1323, +0.0760, -0.0173,
+ -0.0577, +0.1013, +0.0974, -0.0338, +0.0429, +0.3263, +0.1869, +0.1798,
+ -0.0126, -0.1002, +0.1193, +0.1248, -0.1544, +0.1357, -0.0956, +0.1405,
+ +0.1551, +0.4303, +0.1871, -0.0234, +0.1528, +0.3371, +0.3916, +0.2319,
+ +0.1516, +0.1534, +0.1397, -0.1125, -0.0907, +0.0794, -0.0481, +0.1252,
+ -0.0279, +0.0712, -0.0944, +0.2633, +0.0062, -0.0458, +0.2715, +0.1041,
+ -0.1381, -0.0402, +0.1133, -0.0761, +0.1408, +0.2070, -0.0576, -0.1057,
+ -0.0464, +0.1069, -0.0581, +0.2263, +0.0632, -0.0277, +0.0625, +0.2455,
+ +0.1857, -0.0172, -0.0332, -0.0384, +0.1591, +0.1721, +0.1568, +0.1680,
+ +0.0232, +0.1134, +0.2353, +0.0235, +0.1007, -0.0667, -0.1689, +0.1512,
+ +0.1154, -0.0607, +0.3318, +0.1063, +0.2589, +0.3722, -0.0955, +0.1107,
+ +0.0735, +0.0284, +0.2233, -0.0427, +0.1083, +0.2224, +0.1169, +0.3346,
+ -0.0581, +0.1114, +0.0446, +0.0422, +0.1618, +0.1712, +0.1250, +0.0345
])
-weights_dense2_b = np.array([ -0.1167, -0.0510, +0.1155, +0.2151, -0.0416, +0.1452, -0.0794, +0.1217, -0.0268, +0.1016, +0.1274, -0.0271, -0.1298, +0.0793, +0.0404, +0.0955, -0.0855, -0.0578, +0.3129, +0.0950, -0.0090, -0.0090, +0.2334, +0.1715, +0.1043, +0.0024, -0.0009, +0.0342, +0.0742, +0.1323, +0.0760, -0.0173, -0.0577, +0.1013, +0.0974, -0.0338, +0.0429, +0.3263, +0.1869, +0.1798, -0.0126, -0.1002, +0.1193, +0.1248, -0.1544, +0.1357, -0.0956, +0.1405, +0.1551, +0.4303, +0.1871, -0.0234, +0.1528, +0.3371, +0.3916, +0.2319, +0.1516, +0.1534, +0.1397, -0.1125, -0.0907, +0.0794, -0.0481, +0.1252, -0.0279, +0.0712, -0.0944, +0.2633, +0.0062, -0.0458, +0.2715, +0.1041, -0.1381, -0.0402, +0.1133, -0.0761, +0.1408, +0.2070, -0.0576, -0.1057, -0.0464, +0.1069, -0.0581, +0.2263, +0.0632, -0.0277, +0.0625, +0.2455, +0.1857, -0.0172, -0.0332, -0.0384, +0.1591, +0.1721, +0.1568, +0.1680, +0.0232, +0.1134, +0.2353, +0.0235, +0.1007, -0.0667, -0.1689, +0.1512, +0.1154, -0.0607, +0.3318, +0.1063, +0.2589, +0.3722, -0.0955, +0.1107, +0.0735, +0.0284, +0.2233, -0.0427, +0.1083, +0.2224, +0.1169, +0.3346, -0.0581, +0.1114, +0.0446, +0.0422, +0.1618, +0.1712, +0.1250, +0.0345])
+weights_final_w = np.array(
+ [[
+ -0.1409, +0.0606, +0.1558, +0.5906, +0.5491, +0.1037, +0.2666, +0.4064,
+ -0.1780, -0.1288, +0.2905, -0.0481, -0.5252, -0.0515, -0.1952, -0.2929,
+ -0.0497
+ ],
+ [
+ +0.0158, +0.4308, +0.0786, -0.3480, +0.1021, +0.1913, +0.1547,
+ +0.1592, -0.0808, +0.0128, -0.2508, -0.1756, -0.2529, +0.0993,
+ -0.2782, +0.0571, +0.0573
+ ],
+ [
+ -0.1413, +0.6745, -0.1781, +0.6893, +0.2538, +0.0843, -0.4969,
+ -0.0122, -0.1461, +0.0613, +0.4610, -0.0686, -0.1554, +0.0358,
+ +0.7842, +0.8608, -0.2391
+ ],
+ [
+ +0.3327, +0.1319, +0.0541, -0.4871, -0.1690, +0.0081, +0.0060,
+ -0.9171, -0.5084, +0.1018, +0.0639, +0.3623, -0.0782, +0.0496,
+ -0.4079, -0.1013, -0.0690
+ ],
+ [
+ -0.1719, -0.5059, -0.0022, +0.0316, -0.1060, -0.1596, +0.1947,
+ -0.2249, -0.0501, -0.0164, -0.1673, +0.0620, +0.1306, -0.1154,
+ +0.0134, -0.1069, +0.2493
+ ],
+ [
+ -0.2346, +0.0917, -0.1643, +0.0898, -0.1338, +0.0732, -0.5332,
+ -0.2103, -0.0308, +0.0225, +0.1221, +0.0586, -0.0287, -0.0555,
+ +0.0552, -0.2873, +0.1732
+ ],
+ [
+ +0.0078, -0.2411, +0.0115, -0.0742, -0.1178, +0.1171, -0.0948,
+ +0.3466, +0.2447, +0.0874, -0.1674, -0.0233, -0.0612, -0.1248,
+ +0.2984, +0.0560, +0.1363
+ ],
+ [
+ -0.1943, +0.0462, -0.1835, -0.0322, -0.2255, +0.1333, -0.0341,
+ -0.0194, -0.1684, -0.0375, +0.0923, -0.5920, -0.0684, -0.0811,
+ -0.1885, +0.5146, -0.1201
+ ],
+ [
+ +0.0040, -0.3660, -0.0910, -0.3053, -0.1338, +0.1778, +0.0173,
+ -0.0107, -0.1345, -0.2165, +0.0183, +0.1342, +0.0417, -0.0796,
+ -0.0200, -0.0786, -0.1461
+ ],
+ [
+ -0.5645, -0.2610, +0.2043, +0.1721, +0.1131, +0.0955, +0.0937,
+ -0.1056, +0.2781, -0.4071, -0.1843, +0.0631, +0.3708, +0.0396,
+ -0.3982, -0.1707, +0.1564
+ ],
+ [
+ -0.0622, +0.0038, +0.0096, +0.0226, +0.0439, -0.0897, -0.1817,
+ -0.3580, +0.2459, +0.1132, +0.2129, +0.3670, +0.0517, +0.1534,
+ -0.3811, -0.0477, +0.1431
+ ],
+ [
+ +0.2554, -0.4012, +0.3759, -0.1304, -0.1030, -0.0129, -0.0969,
+ -0.5814, +0.0760, -0.0088, +0.3026, -0.7977, -0.0522, -0.0449,
+ +0.0758, +0.1155, -0.1630
+ ],
+ [
+ -0.0743, +0.3703, -0.0521, -0.2735, -0.3417, +0.2092, -0.2046,
+ -0.0951, -0.2670, -0.1099, -0.0294, +0.2757, -0.1194, +0.0273,
+ -0.0331, +0.2194, +0.0728
+ ],
+ [
+ +0.2312, +0.0036, +0.1780, -0.3389, -0.2833, +0.0260, +0.1729,
+ -0.1030, -0.1111, +0.0063, +0.2100, +0.4117, -0.7115, -0.1786,
+ +0.8551, +0.1716, -0.0773
+ ],
+ [
+ +0.1959, +0.0468, +0.2011, +0.4497, +0.0857, -0.1043, +0.1021,
+ +0.3576, -0.1589, +0.1530, -0.0072, -0.1953, -0.0723, -0.0808,
+ -0.3258, +0.0552, -0.1157
+ ],
+ [
+ +0.1692, -0.0429, +0.3505, -0.2750, -0.0736, -0.0205, +0.0846,
+ -0.5475, -0.1184, -0.0072, -0.4119, -0.8117, -0.0360, +0.0525,
+ -0.1883, +0.2046, +0.0638
+ ],
+ [
+ -0.4179, +0.0260, -0.0094, -0.0674, -0.0135, +0.1656, -0.1452,
+ -0.1412, -0.2059, -0.0320, +0.0643, +0.7900, +0.1409, +0.1683,
+ +0.0902, +0.6712, -0.1028
+ ],
+ [
+ -0.1260, -0.0781, -0.2611, -0.4299, -0.1694, +0.0456, -0.2589,
+ +0.0977, +0.2175, +0.1608, -0.0726, -0.1199, -0.0643, -0.0807,
+ -0.2578, +0.0418, +0.0794
+ ],
+ [
+ -0.0710, +0.0952, +0.1524, -0.1494, +0.2991, -0.0303, +0.2806,
+ -0.3902, +0.0998, +0.0087, +0.0793, +0.0698, +0.3036, -0.1031,
+ +0.5591, -0.2511, -0.0032
+ ],
+ [
+ -0.3243, +0.1407, +0.0284, +0.2512, +0.0649, +0.1074, +0.0614,
+ +0.1656, -0.0323, -0.0300, -0.0337, +0.3358, +0.4145, +0.1301,
+ -0.3915, +0.4564, +0.0143
+ ],
+ [
+ -0.0180, -0.1358, +0.6130, +0.5182, +0.8529, -0.0636, +0.2505,
+ -0.1218, +0.4277, +0.1034, -0.2595, +0.7339, -0.2152, -0.0591,
+ +0.0851, +0.5327, +0.1450
+ ],
+ [
+ -0.0368, +0.0113, -0.4927, +0.0034, -0.0075, -0.0934, -0.2917,
+ +0.3486, -0.1152, +0.2371, +0.0748, -0.8024, +0.4637, +0.1016,
+ +0.1304, -0.0077, -0.1941
+ ],
+ [
+ +0.0605, -0.1355, -0.6414, -0.1896, +0.5742, +0.0283, +0.9086,
+ +0.3295, +0.1147, -0.3647, +0.2802, -0.5572, +0.0236, -0.0349,
+ -0.1923, +0.0162, -0.4518
+ ],
+ [
+ -0.0853, +0.1035, -0.5425, +0.2805, +0.0590, -0.1345, +0.0187,
+ +0.2452, +0.0111, +0.2072, +0.1750, +0.3432, +0.2286, +0.0521,
+ +0.5415, +0.0625, -0.0606
+ ],
+ [
+ -0.4766, +0.1048, +0.4389, -0.3019, +0.0645, +0.2069, +0.1991,
+ -0.3012, +0.1594, -0.0683, +0.0312, +0.0781, +0.0461, -0.0094,
+ +0.1351, +0.2003, +0.0744
+ ],
+ [
+ -0.0465, +0.0243, -0.1611, +0.3793, -0.2330, -0.0357, -0.0081,
+ +0.4627, -0.0759, -0.0259, +0.1757, -0.1862, -0.0835, +0.1172,
+ +0.3056, +0.4952, -0.0942
+ ],
+ [
+ -0.2701, +0.0510, +0.2381, -0.0737, +0.1937, +0.4068, -0.0967,
+ -0.1227, -0.1263, -0.2735, -0.0244, -0.2793, -0.0630, +0.0264,
+ +0.3498, +0.1389, +0.0135
+ ],
+ [
+ -0.2801, -0.6462, +0.0335, +0.1178, -0.1143, -0.3208, -0.0379,
+ -0.3176, +0.2773, -0.0164, -0.0878, +0.3876, +0.4616, -0.0001,
+ -0.7586, -0.1818, +0.2519
+ ],
+ [
+ -0.1604, -0.2381, -0.1973, +0.1941, +0.1536, +0.1481, -0.3189,
+ -0.0488, +0.2997, +0.0428, +0.3616, +0.0550, -0.2651, -0.1053,
+ -0.1929, +0.3982, -0.0761
+ ],
+ [
+ +0.1029, -0.1022, +0.2005, -0.0139, -0.0283, +0.0199, -0.2172,
+ -0.2173, -0.0283, -0.1045, -0.1076, -0.2635, -0.6718, -0.1400,
+ +0.2573, +0.3001, -0.0533
+ ],
+ [
+ -0.0067, -0.3162, -0.1343, +0.1801, -0.3137, -0.0922, -0.1899,
+ -0.0268, -0.3384, +0.0366, +0.0835, +0.2769, +0.2396, -0.0950,
+ -0.6336, -0.5050, +0.0437
+ ],
+ [
+ -0.1502, +0.6180, +0.5293, -0.1594, -0.3031, +0.1568, +0.0698,
+ +0.2979, -0.2607, -0.2205, -0.4064, -0.2533, +0.3110, +0.0833,
+ +0.7056, -0.2191, +0.3289
+ ],
+ [
+ +0.0043, -0.0828, +0.2334, +0.4588, +0.0960, -0.1273, -0.2427,
+ -0.2658, +0.0925, +0.1575, -0.0637, -0.3738, +0.5424, +0.0156,
+ -0.1157, -0.1581, +0.1559
+ ],
+ [
+ -0.1314, +0.2269, -0.3305, +0.1094, +0.0135, +0.0014, +0.1888,
+ -0.0592, +0.3414, +0.1238, +0.1765, -0.7967, -0.1045, -0.0217,
+ +0.4728, +0.5653, -0.3226
+ ],
+ [
+ +0.1118, -0.0546, +0.2576, +0.1919, -0.2431, -0.1106, -0.2890,
+ -0.4040, -0.0316, +0.1152, +0.0519, +0.0852, -0.0289, -0.1102,
+ +0.1200, +0.0895, -0.0724
+ ],
+ [
+ -0.2491, +0.0519, -0.1251, +0.2130, +0.2974, +0.2027, +0.1086,
+ +0.7321, -0.0341, -0.2383, +0.3041, +0.4744, -0.2680, -0.0569,
+ +0.4539, -0.1163, -0.0773
+ ],
+ [
+ -0.0680, +0.2382, +0.4815, +0.3223, +0.2211, +0.2598, +0.1380,
+ +0.0806, -0.0856, -0.3277, -0.0822, -0.0844, +0.1893, +0.1667,
+ +0.2742, -0.4274, +0.1363
+ ],
+ [
+ +0.2455, +0.3247, -0.1894, +0.0728, +0.0442, +0.1078, +0.0101,
+ +0.3493, +0.1237, -0.1016, +0.2452, -0.0271, +0.0936, -0.0146,
+ -0.1208, -0.1444, -0.1091
+ ],
+ [
+ -0.3881, -0.0667, +0.2811, -0.0337, -0.1464, -0.2057, +0.0485,
+ +0.2152, +0.1522, -0.0386, +0.2684, -0.3142, +0.0001, -0.2267,
+ +0.1693, +0.0840, +0.0454
+ ],
+ [
+ +0.1157, +0.1391, -0.3331, -0.0841, +0.1443, -0.3248, +0.1861,
+ -0.1105, +0.5040, +0.2725, +0.1318, +0.8929, -0.4102, -0.2091,
+ -0.1325, +0.0027, +0.0345
+ ],
+ [
+ -0.1702, -0.0969, +0.1766, -0.4914, +0.3428, +0.3769, -0.0861,
+ -0.3353, -0.2301, -0.3608, +0.1352, +0.3887, -0.6166, +0.2975,
+ +0.2477, +0.0185, +0.2741
+ ],
+ [
+ -0.0624, -0.3787, +0.1566, -0.2939, -0.0099, -0.0038, +0.1801,
+ -0.0086, -0.0749, -0.0662, -0.0162, +0.0450, +0.1526, -0.1148,
+ -0.5482, -0.2812, -0.0061
+ ],
+ [
+ +0.2030, -0.0749, -0.2331, +0.1874, -0.0399, -0.1239, -0.0600,
+ -0.2387, +0.0434, +0.0638, -0.1857, -0.3133, -0.0914, +0.1662,
+ +0.0801, +0.0254, -0.0278
+ ],
+ [
+ +0.2227, -0.4864, -0.1767, -0.0561, -0.3654, -0.0922, -0.0595,
+ -0.1754, -0.3475, +0.1481, +0.0721, +0.1068, -0.1546, -0.1122,
+ -0.4169, -0.1415, +0.0642
+ ],
+ [
+ -0.0775, +0.2542, +0.0908, +0.3044, +0.2158, +0.0768, +0.1498,
+ +0.8269, +0.0968, -0.0573, -0.2559, -0.1212, +0.5353, +0.1686,
+ -0.3455, +0.0084, -0.1092
+ ],
+ [
+ +0.0494, +0.1230, -0.2086, -0.0240, -0.1061, +0.0664, -0.0964,
+ +0.0568, -0.0530, +0.3436, +0.5629, -0.1642, -0.2172, -0.2508,
+ +0.2039, +0.0447, -0.1384
+ ],
+ [
+ +0.4154, -0.6111, +0.5973, +0.3750, -0.0209, +0.2669, +0.4349,
+ -0.4379, -0.8619, -0.6603, +0.3843, +0.4447, -0.2610, -0.0537,
+ +0.1169, +0.2802, +0.0680
+ ],
+ [
+ -0.0936, +0.0809, -0.2057, +0.3599, +0.1417, -0.0002, +0.2883,
+ +0.0322, +0.0750, -0.0918, +0.1454, +0.2856, -0.3365, -0.0845,
+ -0.2601, +0.2617, -0.3751
+ ],
+ [
+ +0.1020, +0.1826, +0.0839, -0.3837, +0.0659, -0.0032, -0.0296,
+ -0.0230, -0.2824, +0.1242, +0.1188, -0.1835, -0.1085, +0.0111,
+ +0.1342, +0.4190, +0.0310
+ ],
+ [
+ +0.2220, -0.2676, +0.4179, +0.2384, +0.1995, -0.2100, +0.3456,
+ +0.2269, +0.1355, +0.0217, -0.1118, -0.0870, -0.1239, -0.0094,
+ +0.0859, -0.1708, +0.1544
+ ],
+ [
+ +0.4146, -0.3982, +0.8939, +0.3733, +0.2503, -0.2130, +0.1417,
+ +0.2519, +0.0309, -0.1665, +0.1641, +0.9532, +0.0756, +0.0172,
+ +0.0123, +0.1202, -0.1104
+ ],
+ [
+ +0.1094, +0.0515, +0.0742, -0.7886, -0.3253, +0.1596, +0.0308,
+ -0.5371, -0.3584, +0.0223, -0.0030, -0.2774, -0.5786, -0.0680,
+ +1.1358, -0.2489, +0.0265
+ ],
+ [
+ +0.1768, +0.0361, -0.7746, +0.1206, +0.1003, -0.2079, -0.0938,
+ +0.1311, +0.4703, +0.2785, -0.1427, +0.0731, +0.5649, -0.0821,
+ -0.2307, -0.0683, +0.1924
+ ],
+ [
+ +0.3056, -0.0681, -0.1025, +0.2378, +0.2239, -0.4030, -0.0065,
+ +0.0402, +0.4062, +0.1393, +0.0954, -0.0546, +0.0584, -0.0386,
+ +0.0289, -0.1401, +0.0367
+ ],
+ [
+ -0.1283, -0.1635, +0.1080, -0.0220, -0.1000, -0.1157, +0.2681,
+ +0.1661, +0.0822, -0.2251, +0.0893, +0.2289, -0.1836, +0.1515,
+ +0.0688, -0.0912, +0.0177
+ ],
+ [
+ -0.0910, -0.2656, -0.1346, +0.1549, +0.1084, -0.2611, +0.2446,
+ -0.2851, +0.2948, +0.0284, -0.3582, -1.3187, -0.3781, -0.0681,
+ +0.0803, -0.1766, +0.3008
+ ],
+ [
+ +0.5218, -0.0293, +0.0521, +0.1711, +0.1373, -0.0795, +0.4071,
+ +0.2030, +0.2839, +0.0906, -0.1113, -0.1076, -0.4932, +0.1220,
+ +0.4161, +0.1007, +0.0513
+ ],
+ [
+ -0.0858, +0.2734, -0.1252, -0.5853, -0.1065, -0.1348, +0.3453,
+ -0.4680, -0.0558, +0.1232, -0.4178, +0.8754, -0.3607, -0.1534,
+ +0.5096, +0.2548, -0.0748
+ ],
+ [
+ -0.2429, +0.3803, -0.6319, +0.0077, -0.0364, -0.1513, -0.0297,
+ +0.8310, +0.1646, +0.0311, +0.1827, +0.7492, -0.6287, -0.0933,
+ -0.6411, +1.1034, -0.4511
+ ],
+ [
+ -0.2751, +0.4602, -0.0052, -0.0424, -0.3164, +0.1043, -0.4699,
+ -0.1483, +0.0570, +0.0779, -0.0830, +0.4477, -1.2366, -0.1458,
+ -0.1955, +0.2251, +0.1099
+ ],
+ [
+ +0.4880, +0.1914, -0.5189, -0.2372, +0.2696, -0.2005, -0.1336,
+ +0.3093, +0.0783, +0.2784, -0.0874, -0.4397, -0.5851, -0.1695,
+ +0.3920, -0.7212, +0.0386
+ ],
+ [
+ +0.1577, -0.3636, +0.0606, +0.0595, +0.2361, +0.0218, -0.1914,
+ -0.0020, -0.1269, -0.0906, +0.0464, +0.1972, +0.0890, +0.0563,
+ +0.0631, -0.1230, -0.1953
+ ],
+ [
+ +0.2520, +0.1504, -0.0460, -0.2907, +0.0460, +0.3387, -0.1905,
+ -0.3332, -0.0972, +0.0691, -0.0685, -0.0829, -0.0773, -0.1584,
+ -0.2197, -0.1496, -0.0252
+ ],
+ [
+ -0.4237, +0.0056, -0.0304, -0.2339, +0.3789, +0.2567, +0.3093,
+ -0.1058, +0.2272, -0.2528, +0.0951, +0.4202, +0.1412, -0.0213,
+ +0.2918, -0.0306, -0.0275
+ ],
+ [
+ +0.0543, +0.3421, +0.2451, +0.2349, -0.2259, +0.0387, -0.0617,
+ -0.0643, +0.0109, -0.1121, -0.1300, -0.0021, +0.0711, -0.0751,
+ -0.0576, -0.3440, +0.1992
+ ],
+ [
+ +0.1885, +0.0831, -0.3353, +0.2452, -0.1187, -0.3477, -0.2286,
+ +0.0179, +0.1566, +0.5549, +0.2857, +0.1232, -0.3595, -0.0449,
+ +0.1067, -0.1989, -0.0169
+ ],
+ [
+ -0.1334, -0.2713, +0.3466, +0.0449, -0.1024, +0.1663, -0.1981,
+ -0.3261, -0.2438, -0.1765, -0.1748, +0.5400, -0.2122, -0.0318,
+ -0.5316, +0.4447, -0.0700
+ ],
+ [
+ +0.1094, -0.1033, +0.2346, -0.3173, +0.1897, +0.2990, +0.3480,
+ +0.2799, -0.2819, -0.2969, -0.0594, -0.0003, -0.2630, -0.1162,
+ +0.1140, +0.1733, -0.1270
+ ],
+ [
+ +0.2172, -0.1584, +0.0221, -0.1395, -0.1675, -0.1263, -0.1244,
+ -0.3817, -0.2158, +0.0466, +0.0857, -0.4953, +0.3157, +0.1223,
+ -0.6040, -0.4049, +0.0726
+ ],
+ [
+ -0.1488, -0.0286, +0.1821, +0.0005, -0.1175, -0.0874, -0.1072,
+ +0.0381, -0.0206, +0.0871, -0.1451, -0.0249, +0.1206, +0.2396,
+ +0.2498, -0.2140, -0.1405
+ ],
+ [
+ -0.0111, +0.3861, +0.0429, -0.0130, +0.0538, +0.2012, +0.2013,
+ -0.2428, +0.0409, +0.3693, -0.0229, -0.0916, -0.2249, +0.0734,
+ -0.0359, +0.1811, +0.0051
+ ],
+ [
+ -0.2756, +0.2094, -0.5057, +0.2024, +0.0241, -0.0891, -0.2455,
+ +0.0538, +0.0846, +0.1143, +0.0623, -0.1871, +0.1313, +0.0253,
+ -0.2388, -0.1463, +0.0287
+ ],
+ [
+ +0.1821, +0.4514, -0.0363, +0.2531, -0.1088, -0.0400, -0.1291,
+ +0.1353, +0.1665, +0.3382, -0.4276, -0.1547, -0.1877, +0.1149,
+ -0.0641, -0.4630, +0.1352
+ ],
+ [
+ +0.1122, -0.1090, +0.3136, +0.3880, +0.1287, +0.0237, +0.0728,
+ +0.0179, +0.0349, -0.1230, +0.0111, +0.6014, -0.3108, -0.0339,
+ -0.2139, +0.1688, +0.0408
+ ],
+ [
+ -0.0585, +0.1857, -0.5246, +0.2287, +0.2376, +0.0977, +0.1277,
+ +0.8259, -0.0420, -0.0909, +0.2259, -0.2873, -0.0027, +0.0197,
+ +0.4685, -0.2872, -0.1987
+ ],
+ [
+ -0.0200, -0.2907, +0.1864, -0.1628, -0.1605, +0.1749, -0.2185,
+ -0.1611, -0.1128, -0.0374, +0.2906, +0.3250, +0.4870, +0.0309,
+ -0.3275, +0.0048, -0.1310
+ ],
+ [
+ -0.0080, -0.4754, +0.1296, -0.0301, -0.3817, -0.1197, +0.4911,
+ -0.4934, -0.2824, -0.0310, +0.0279, +0.2155, -0.6603, +0.0401,
+ -0.8678, +0.4578, -0.0707
+ ],
+ [
+ -0.1653, +0.0769, -0.1368, -0.0154, -0.2174, -0.0164, +0.2595,
+ +0.2301, +0.1736, -0.0489, -0.3271, -0.0782, -0.0477, -0.2108,
+ -0.0857, -0.0149, -0.1159
+ ],
+ [
+ -0.0895, +0.3569, +0.0548, +0.3007, +0.2871, +0.1508, -0.0002,
+ +0.3219, +0.1019, +0.1113, -0.0978, +0.2202, -0.2125, -0.0533,
+ +0.6329, +0.2266, +0.0218
+ ],
+ [
+ -0.0314, +0.2153, -0.1019, -0.1699, +0.0126, +0.0158, -0.3012,
+ -0.0264, +0.2299, -0.0200, +0.0445, +0.3879, +0.5208, +0.2000,
+ +0.4442, -0.4519, +0.0081
+ ],
+ [
+ -0.0303, +0.2435, -0.1155, -0.0029, +0.0924, +0.1226, -0.0519,
+ +0.4167, -0.0235, -0.0145, +0.0102, +0.4426, +0.3652, +0.0790,
+ +0.0670, +0.3292, -0.1155
+ ],
+ [
+ -0.4764, +0.1008, +0.2453, +0.6503, -0.2319, -0.2316, +0.1459,
+ -0.3701, +0.4247, +0.1477, +0.0578, +1.2480, +0.2435, -0.2183,
+ +0.2025, -0.5131, +0.0148
+ ],
+ [
+ +0.0369, -0.6000, +0.2335, +0.2427, -0.2383, -0.2967, -0.1404,
+ -0.0762, -0.1701, +0.0050, -0.3853, +0.2045, +0.1601, -0.0450,
+ +0.3609, -0.2774, -0.2418
+ ],
+ [
+ -0.1558, +0.1644, -0.1136, +0.2121, -0.0032, -0.2172, -0.0341,
+ -0.0589, +0.2133, +0.1157, +0.3303, +0.3821, +0.4223, +0.0544,
+ -0.1871, +0.2528, +0.0532
+ ],
+ [
+ -0.1705, +0.0316, +0.0959, -0.4905, -0.1434, -0.4177, -0.0139,
+ +0.0173, +0.2193, +0.0451, -0.4526, -0.1873, +0.4062, +0.0100,
+ -1.2451, +1.2191, -0.2005
+ ],
+ [
+ -0.0578, -0.1543, +0.0090, +0.2091, -0.0905, -0.3092, -0.0324,
+ -0.9097, +0.1443, +0.0027, +0.5500, -0.5892, -0.6884, +0.0737,
+ +0.3726, +0.0123, -0.3109
+ ],
+ [
+ +0.0170, +0.1850, +0.0151, +0.0633, +0.4575, +0.1327, +0.0153,
+ -0.1831, -0.2411, -0.0660, -0.0843, +0.2057, -0.1343, +0.0240,
+ +0.6390, -0.3008, +0.2598
+ ],
+ [
+ +0.2004, -0.2134, -0.3945, -0.3735, +0.0749, -0.0204, +0.1091,
+ +0.0723, -0.3266, -0.0416, -0.1158, -0.0958, +0.0165, -0.0369,
+ +0.3759, -0.0372, -0.0946
+ ],
+ [
+ -0.0773, -0.0728, -0.4872, -0.3943, -0.2244, -0.1453, -0.0684,
+ -0.0067, -0.2013, +0.1170, +0.1176, +0.1532, -0.1420, -0.0700,
+ -0.0435, +0.1984, -0.1804
+ ],
+ [
+ +0.3493, +0.5615, +0.4853, -0.0299, +0.3986, +0.2032, +0.1871,
+ +0.3303, -0.0351, -0.0214, -0.3183, +0.2865, -0.1298, +0.1266,
+ +0.2793, -0.0451, -0.0698
+ ],
+ [
+ +0.3691, -0.0414, +0.1429, -0.1778, +0.3977, -0.0978, -0.3099,
+ -0.2705, +0.1606, -0.0288, -0.1289, -0.1052, -0.0404, +0.0166,
+ -0.5058, -0.4936, -0.0004
+ ],
+ [
+ +0.1870, -0.4584, +0.1216, -0.0170, +0.2037, -0.1470, +0.3353,
+ +0.1069, -0.0034, -0.4070, +0.3482, -0.5598, -0.1958, +0.0897,
+ +0.1491, -0.0716, +0.1305
+ ],
+ [
+ +0.0389, +0.0905, +0.1360, -0.1183, +0.2531, +0.1238, -0.2772,
+ +0.2455, +0.4092, -0.0462, -0.0588, -0.0419, +0.1674, +0.0068,
+ -0.1061, +0.0287, -0.0828
+ ],
+ [
+ +0.1001, -0.4006, +0.0288, -0.3762, -0.0410, +0.2275, +0.1096,
+ -0.1166, -0.1334, -0.4214, -0.4301, +0.3060, -0.2374, +0.0423,
+ -0.3930, -0.2825, +0.1954
+ ],
+ [
+ +0.1034, +0.6710, +0.3191, +0.3582, -0.1224, +0.1598, -0.1600,
+ +0.0934, -0.1515, +0.0675, +0.2047, +0.1186, -0.1772, +0.0256,
+ -0.1494, +0.0952, +0.1113
+ ],
+ [
+ -0.4012, -0.1076, +0.0205, -0.5024, +0.0729, +0.1485, +0.0070,
+ +0.1607, -0.0114, -0.1145, -0.1079, +0.3810, +0.1917, -0.0099,
+ +0.0344, +0.3523, -0.0808
+ ],
+ [
+ -0.2240, +0.1399, +0.1148, +0.2574, +0.0202, +0.0974, +0.0275,
+ +0.4080, +0.2255, +0.0175, +0.0463, -0.1122, -0.6143, -0.1468,
+ -0.5921, +0.6715, +0.0307
+ ],
+ [
+ -0.3402, -0.2659, -0.1670, +0.3877, +0.1549, -0.0218, +0.0430,
+ +0.1702, +0.0147, -0.0137, +0.0798, -0.2539, -0.0238, -0.0276,
+ +0.1152, -0.1507, -0.0094
+ ],
+ [
+ -0.0436, +0.2453, -0.0635, -0.0957, +0.0092, +0.2026, +0.0469,
+ -0.0911, -0.0252, -0.0527, +0.1833, -0.0522, -0.3532, -0.0643,
+ +0.8052, -0.2086, +0.1393
+ ],
+ [
+ +0.1356, +0.2174, -0.4187, -0.1698, -0.3939, -0.3418, +0.0977,
+ -0.4303, -0.1747, +0.3483, -0.3828, +0.6477, -0.0193, -0.0432,
+ -0.3092, +0.0965, +0.0512
+ ],
+ [
+ -0.0526, +0.0788, -0.0251, -0.0711, +0.1021, -0.0033, -0.1653,
+ -0.4175, +0.6269, +0.1131, -0.0403, -0.9119, -0.0319, +0.0312,
+ -0.7391, +0.4969, -0.2035
+ ],
+ [
+ +0.0237, -0.3621, +0.6398, -0.4092, -0.3548, +0.1151, -0.2588,
+ +0.1652, -0.9864, -0.0429, -0.2583, -0.7839, -0.1742, -0.1615,
+ -0.5220, +0.3167, +0.0245
+ ],
+ [
+ +0.2773, -0.2533, -0.1067, +0.1248, -0.0263, -0.0443, -0.6161,
+ -0.1194, +0.0183, -0.0374, -0.0112, +0.0789, -0.4672, -0.0865,
+ -0.3901, +0.1714, -0.0693
+ ],
+ [
+ +0.3108, +0.0953, -0.1789, -0.1484, +0.0256, +0.0596, +0.3846,
+ -0.1545, -0.1468, +0.0058, +0.0122, +0.0373, +0.1194, +0.1557,
+ +0.2206, -0.2213, +0.0944
+ ],
+ [
+ -0.3364, +0.0759, +0.0602, +0.0081, -0.1324, -0.1008, +0.0013,
+ -0.6405, +0.2720, +0.0274, -0.0404, -0.1801, +0.1287, -0.0663,
+ +0.4262, +0.3619, -0.0217
+ ],
+ [
+ -0.4219, -0.0153, -0.1689, -0.4714, -0.3856, +0.1550, -0.0396,
+ +0.3023, -0.2935, +0.0254, -0.0017, +0.1311, +0.0634, -0.1347,
+ -0.5716, +0.1617, -0.0855
+ ],
+ [
+ +0.1646, +0.1777, -0.1430, -0.0439, +0.0316, -0.1789, +0.2856,
+ +0.1370, +0.2351, +0.2530, -0.3670, -0.1025, -0.2779, +0.0917,
+ +0.1178, +0.3486, -0.0894
+ ],
+ [
+ -0.2763, +0.1173, -0.0395, -0.3646, -0.2316, +0.0089, +0.0877,
+ -0.2104, -0.1127, +0.0016, +0.0464, +0.0721, +0.0388, +0.0491,
+ +0.3302, +0.0052, -0.0643
+ ],
+ [
+ +0.1751, -0.3577, +0.0741, -0.0451, -0.0270, -0.0501, +0.1754,
+ -0.4259, +0.0053, -0.1944, +0.0852, -0.5543, +0.3060, +0.2323,
+ +0.5691, -0.0617, +0.0329
+ ],
+ [
+ -0.1774, +0.0011, +0.2617, +0.1197, +0.0459, -0.0254, +0.1981,
+ +0.3108, +0.0400, -0.1453, -0.0713, -0.3316, +0.1455, -0.0747,
+ +0.2722, +0.3458, -0.0431
+ ],
+ [
+ +0.2174, +0.0580, -0.3161, +0.3940, -0.2644, -0.1984, -0.1044,
+ +0.2935, +0.0019, +0.3177, -0.0683, -0.4946, +0.2040, +0.2826,
+ -0.1606, -0.4582, +0.2052
+ ],
+ [
+ +0.0825, -0.2587, -0.6098, -0.7666, -0.1891, +0.1545, -0.1752,
+ -0.1813, -0.3137, -0.1742, -0.0400, +0.3352, -0.3175, +0.0617,
+ +0.2097, -0.1684, -0.0412
+ ],
+ [
+ -0.1112, +0.2379, -0.0920, -0.0707, -0.0307, +0.0797, -0.1313,
+ -0.1122, -0.3038, +0.0529, -0.3645, -0.2686, +0.0730, -0.0592,
+ -0.0104, +0.1403, +0.0906
+ ],
+ [
+ +0.3680, +0.0528, +0.1097, +0.1391, -0.0911, +0.0238, +0.0677,
+ +0.1313, -0.3832, -0.0146, +0.3670, -0.3521, -0.0276, +0.1317,
+ +0.1161, -0.2734, +0.0763
+ ],
+ [
+ +0.1579, +0.1185, +0.2387, -0.5239, -0.3156, -0.0856, +0.1244,
+ -0.2377, -0.0763, +0.1003, -0.1049, -0.3365, +0.0325, -0.0759,
+ -0.1114, -0.1658, -0.1217
+ ],
+ [
+ -0.1804, -0.4128, +0.1567, +0.5702, -0.3200, +0.0408, -0.0244,
+ -0.0840, -0.0527, -0.1145, +0.1109, +0.2210, +0.3458, +0.0023,
+ -0.3264, -0.4558, +0.1183
+ ],
+ [
+ +0.0659, -0.1952, -0.1324, +0.1010, -0.2289, -0.1007, +0.0708,
+ +0.1144, -0.0813, +0.0920, +0.3396, +0.0104, +0.1072, -0.0226,
+ -0.1626, -0.1254, +0.1932
+ ],
+ [
+ +0.1231, +0.2101, -0.1953, -0.3647, +0.4056, -0.1017, -0.0869,
+ -0.1301, +0.1228, -0.0524, -0.0305, +0.0722, -0.0188, +0.0059,
+ -0.0921, -0.0607, +0.1297
+ ],
+ [
+ +0.3724, +0.0801, +0.2260, +0.3577, +0.0365, -0.1573, +0.4085,
+ +0.1012, +0.2122, +0.1751, -0.0605, +0.3211, +0.3520, +0.0157,
+ -0.3718, +0.2995, -0.2521
+ ],
+ [
+ +0.0650, -0.0647, +0.2336, -0.0282, -0.0795, +0.1878, +0.1919,
+ +0.1609, +0.0767, -0.2512, +0.1858, -0.4086, +0.2826, +0.1826,
+ +0.1671, +0.0621, +0.1772
+ ],
+ [
+ +0.2919, -0.1500, +0.1861, -0.1115, -0.0102, -0.2352, -0.0982,
+ +0.1106, +0.3164, +0.0698, -0.4432, +0.2496, +0.0924, +0.0937,
+ -0.2256, -0.2866, +0.0928
+ ],
+ [
+ -0.1124, +0.0442, +0.3579, +0.1774, +0.1772, +0.2148, +0.2384,
+ +0.2642, -0.0853, -0.7385, +0.1676, -0.0897, -0.0031, +0.0578,
+ -0.0487, -0.0222, +0.1840
+ ],
+ [
+ -0.1470, +0.0944, +0.3412, +0.3212, +0.2143, +0.3426, -0.1407,
+ -0.0518, -0.3807, -0.0837, -0.0714, +0.2675, -0.3793, -0.3674,
+ -0.3998, +0.0780, +0.0363
+ ],
+ [
+ -0.3876, -0.0642, +0.0959, -0.2092, -0.0610, +0.2080, +0.1597,
+ -0.1985, +0.0557, -0.1315, -0.1643, +0.2609, +0.4146, -0.0175,
+ +0.2486, -0.1299, +0.0421
+ ],
+ [
+ -0.2262, -0.1184, +0.2385, -0.7373, -0.0148, +0.1660, +0.2681,
+ -0.0921, +0.1252, -0.2751, -0.1190, -0.8493, +0.1025, +0.1227,
+ -0.4286, +0.5744, -0.0405
+ ],
+ [
+ -0.0374, +0.0379, -0.4226, -0.1330, +0.1566, +0.0088, -0.0520,
+ -0.0289, -0.1716, +0.0312, +0.0962, +0.3347, +0.5196, +0.0220,
+ -0.1559, -0.3106, +0.2403
+ ],
+ [
+ +0.0513, +0.4744, -0.0200, +0.2514, +0.3022, +0.0020, +0.4068,
+ +0.9192, +0.1873, +0.0072, +0.2791, +0.2587, +0.2999, +0.2515,
+ +0.2632, -0.2145, -0.1129
+ ],
+ [
+ -0.0104, +0.0656, +0.3292, -0.1732, -0.1230, +0.2711, +0.1398,
+ -0.5466, -0.4228, -0.0740, +0.2116, +0.3474, +0.0030, -0.0176,
+ +0.3739, -0.1911, -0.0056
+ ]])
-weights_final_w = np.array([
-[ -0.1409, +0.0606, +0.1558, +0.5906, +0.5491, +0.1037, +0.2666, +0.4064, -0.1780, -0.1288, +0.2905, -0.0481, -0.5252, -0.0515, -0.1952, -0.2929, -0.0497],
-[ +0.0158, +0.4308, +0.0786, -0.3480, +0.1021, +0.1913, +0.1547, +0.1592, -0.0808, +0.0128, -0.2508, -0.1756, -0.2529, +0.0993, -0.2782, +0.0571, +0.0573],
-[ -0.1413, +0.6745, -0.1781, +0.6893, +0.2538, +0.0843, -0.4969, -0.0122, -0.1461, +0.0613, +0.4610, -0.0686, -0.1554, +0.0358, +0.7842, +0.8608, -0.2391],
-[ +0.3327, +0.1319, +0.0541, -0.4871, -0.1690, +0.0081, +0.0060, -0.9171, -0.5084, +0.1018, +0.0639, +0.3623, -0.0782, +0.0496, -0.4079, -0.1013, -0.0690],
-[ -0.1719, -0.5059, -0.0022, +0.0316, -0.1060, -0.1596, +0.1947, -0.2249, -0.0501, -0.0164, -0.1673, +0.0620, +0.1306, -0.1154, +0.0134, -0.1069, +0.2493],
-[ -0.2346, +0.0917, -0.1643, +0.0898, -0.1338, +0.0732, -0.5332, -0.2103, -0.0308, +0.0225, +0.1221, +0.0586, -0.0287, -0.0555, +0.0552, -0.2873, +0.1732],
-[ +0.0078, -0.2411, +0.0115, -0.0742, -0.1178, +0.1171, -0.0948, +0.3466, +0.2447, +0.0874, -0.1674, -0.0233, -0.0612, -0.1248, +0.2984, +0.0560, +0.1363],
-[ -0.1943, +0.0462, -0.1835, -0.0322, -0.2255, +0.1333, -0.0341, -0.0194, -0.1684, -0.0375, +0.0923, -0.5920, -0.0684, -0.0811, -0.1885, +0.5146, -0.1201],
-[ +0.0040, -0.3660, -0.0910, -0.3053, -0.1338, +0.1778, +0.0173, -0.0107, -0.1345, -0.2165, +0.0183, +0.1342, +0.0417, -0.0796, -0.0200, -0.0786, -0.1461],
-[ -0.5645, -0.2610, +0.2043, +0.1721, +0.1131, +0.0955, +0.0937, -0.1056, +0.2781, -0.4071, -0.1843, +0.0631, +0.3708, +0.0396, -0.3982, -0.1707, +0.1564],
-[ -0.0622, +0.0038, +0.0096, +0.0226, +0.0439, -0.0897, -0.1817, -0.3580, +0.2459, +0.1132, +0.2129, +0.3670, +0.0517, +0.1534, -0.3811, -0.0477, +0.1431],
-[ +0.2554, -0.4012, +0.3759, -0.1304, -0.1030, -0.0129, -0.0969, -0.5814, +0.0760, -0.0088, +0.3026, -0.7977, -0.0522, -0.0449, +0.0758, +0.1155, -0.1630],
-[ -0.0743, +0.3703, -0.0521, -0.2735, -0.3417, +0.2092, -0.2046, -0.0951, -0.2670, -0.1099, -0.0294, +0.2757, -0.1194, +0.0273, -0.0331, +0.2194, +0.0728],
-[ +0.2312, +0.0036, +0.1780, -0.3389, -0.2833, +0.0260, +0.1729, -0.1030, -0.1111, +0.0063, +0.2100, +0.4117, -0.7115, -0.1786, +0.8551, +0.1716, -0.0773],
-[ +0.1959, +0.0468, +0.2011, +0.4497, +0.0857, -0.1043, +0.1021, +0.3576, -0.1589, +0.1530, -0.0072, -0.1953, -0.0723, -0.0808, -0.3258, +0.0552, -0.1157],
-[ +0.1692, -0.0429, +0.3505, -0.2750, -0.0736, -0.0205, +0.0846, -0.5475, -0.1184, -0.0072, -0.4119, -0.8117, -0.0360, +0.0525, -0.1883, +0.2046, +0.0638],
-[ -0.4179, +0.0260, -0.0094, -0.0674, -0.0135, +0.1656, -0.1452, -0.1412, -0.2059, -0.0320, +0.0643, +0.7900, +0.1409, +0.1683, +0.0902, +0.6712, -0.1028],
-[ -0.1260, -0.0781, -0.2611, -0.4299, -0.1694, +0.0456, -0.2589, +0.0977, +0.2175, +0.1608, -0.0726, -0.1199, -0.0643, -0.0807, -0.2578, +0.0418, +0.0794],
-[ -0.0710, +0.0952, +0.1524, -0.1494, +0.2991, -0.0303, +0.2806, -0.3902, +0.0998, +0.0087, +0.0793, +0.0698, +0.3036, -0.1031, +0.5591, -0.2511, -0.0032],
-[ -0.3243, +0.1407, +0.0284, +0.2512, +0.0649, +0.1074, +0.0614, +0.1656, -0.0323, -0.0300, -0.0337, +0.3358, +0.4145, +0.1301, -0.3915, +0.4564, +0.0143],
-[ -0.0180, -0.1358, +0.6130, +0.5182, +0.8529, -0.0636, +0.2505, -0.1218, +0.4277, +0.1034, -0.2595, +0.7339, -0.2152, -0.0591, +0.0851, +0.5327, +0.1450],
-[ -0.0368, +0.0113, -0.4927, +0.0034, -0.0075, -0.0934, -0.2917, +0.3486, -0.1152, +0.2371, +0.0748, -0.8024, +0.4637, +0.1016, +0.1304, -0.0077, -0.1941],
-[ +0.0605, -0.1355, -0.6414, -0.1896, +0.5742, +0.0283, +0.9086, +0.3295, +0.1147, -0.3647, +0.2802, -0.5572, +0.0236, -0.0349, -0.1923, +0.0162, -0.4518],
-[ -0.0853, +0.1035, -0.5425, +0.2805, +0.0590, -0.1345, +0.0187, +0.2452, +0.0111, +0.2072, +0.1750, +0.3432, +0.2286, +0.0521, +0.5415, +0.0625, -0.0606],
-[ -0.4766, +0.1048, +0.4389, -0.3019, +0.0645, +0.2069, +0.1991, -0.3012, +0.1594, -0.0683, +0.0312, +0.0781, +0.0461, -0.0094, +0.1351, +0.2003, +0.0744],
-[ -0.0465, +0.0243, -0.1611, +0.3793, -0.2330, -0.0357, -0.0081, +0.4627, -0.0759, -0.0259, +0.1757, -0.1862, -0.0835, +0.1172, +0.3056, +0.4952, -0.0942],
-[ -0.2701, +0.0510, +0.2381, -0.0737, +0.1937, +0.4068, -0.0967, -0.1227, -0.1263, -0.2735, -0.0244, -0.2793, -0.0630, +0.0264, +0.3498, +0.1389, +0.0135],
-[ -0.2801, -0.6462, +0.0335, +0.1178, -0.1143, -0.3208, -0.0379, -0.3176, +0.2773, -0.0164, -0.0878, +0.3876, +0.4616, -0.0001, -0.7586, -0.1818, +0.2519],
-[ -0.1604, -0.2381, -0.1973, +0.1941, +0.1536, +0.1481, -0.3189, -0.0488, +0.2997, +0.0428, +0.3616, +0.0550, -0.2651, -0.1053, -0.1929, +0.3982, -0.0761],
-[ +0.1029, -0.1022, +0.2005, -0.0139, -0.0283, +0.0199, -0.2172, -0.2173, -0.0283, -0.1045, -0.1076, -0.2635, -0.6718, -0.1400, +0.2573, +0.3001, -0.0533],
-[ -0.0067, -0.3162, -0.1343, +0.1801, -0.3137, -0.0922, -0.1899, -0.0268, -0.3384, +0.0366, +0.0835, +0.2769, +0.2396, -0.0950, -0.6336, -0.5050, +0.0437],
-[ -0.1502, +0.6180, +0.5293, -0.1594, -0.3031, +0.1568, +0.0698, +0.2979, -0.2607, -0.2205, -0.4064, -0.2533, +0.3110, +0.0833, +0.7056, -0.2191, +0.3289],
-[ +0.0043, -0.0828, +0.2334, +0.4588, +0.0960, -0.1273, -0.2427, -0.2658, +0.0925, +0.1575, -0.0637, -0.3738, +0.5424, +0.0156, -0.1157, -0.1581, +0.1559],
-[ -0.1314, +0.2269, -0.3305, +0.1094, +0.0135, +0.0014, +0.1888, -0.0592, +0.3414, +0.1238, +0.1765, -0.7967, -0.1045, -0.0217, +0.4728, +0.5653, -0.3226],
-[ +0.1118, -0.0546, +0.2576, +0.1919, -0.2431, -0.1106, -0.2890, -0.4040, -0.0316, +0.1152, +0.0519, +0.0852, -0.0289, -0.1102, +0.1200, +0.0895, -0.0724],
-[ -0.2491, +0.0519, -0.1251, +0.2130, +0.2974, +0.2027, +0.1086, +0.7321, -0.0341, -0.2383, +0.3041, +0.4744, -0.2680, -0.0569, +0.4539, -0.1163, -0.0773],
-[ -0.0680, +0.2382, +0.4815, +0.3223, +0.2211, +0.2598, +0.1380, +0.0806, -0.0856, -0.3277, -0.0822, -0.0844, +0.1893, +0.1667, +0.2742, -0.4274, +0.1363],
-[ +0.2455, +0.3247, -0.1894, +0.0728, +0.0442, +0.1078, +0.0101, +0.3493, +0.1237, -0.1016, +0.2452, -0.0271, +0.0936, -0.0146, -0.1208, -0.1444, -0.1091],
-[ -0.3881, -0.0667, +0.2811, -0.0337, -0.1464, -0.2057, +0.0485, +0.2152, +0.1522, -0.0386, +0.2684, -0.3142, +0.0001, -0.2267, +0.1693, +0.0840, +0.0454],
-[ +0.1157, +0.1391, -0.3331, -0.0841, +0.1443, -0.3248, +0.1861, -0.1105, +0.5040, +0.2725, +0.1318, +0.8929, -0.4102, -0.2091, -0.1325, +0.0027, +0.0345],
-[ -0.1702, -0.0969, +0.1766, -0.4914, +0.3428, +0.3769, -0.0861, -0.3353, -0.2301, -0.3608, +0.1352, +0.3887, -0.6166, +0.2975, +0.2477, +0.0185, +0.2741],
-[ -0.0624, -0.3787, +0.1566, -0.2939, -0.0099, -0.0038, +0.1801, -0.0086, -0.0749, -0.0662, -0.0162, +0.0450, +0.1526, -0.1148, -0.5482, -0.2812, -0.0061],
-[ +0.2030, -0.0749, -0.2331, +0.1874, -0.0399, -0.1239, -0.0600, -0.2387, +0.0434, +0.0638, -0.1857, -0.3133, -0.0914, +0.1662, +0.0801, +0.0254, -0.0278],
-[ +0.2227, -0.4864, -0.1767, -0.0561, -0.3654, -0.0922, -0.0595, -0.1754, -0.3475, +0.1481, +0.0721, +0.1068, -0.1546, -0.1122, -0.4169, -0.1415, +0.0642],
-[ -0.0775, +0.2542, +0.0908, +0.3044, +0.2158, +0.0768, +0.1498, +0.8269, +0.0968, -0.0573, -0.2559, -0.1212, +0.5353, +0.1686, -0.3455, +0.0084, -0.1092],
-[ +0.0494, +0.1230, -0.2086, -0.0240, -0.1061, +0.0664, -0.0964, +0.0568, -0.0530, +0.3436, +0.5629, -0.1642, -0.2172, -0.2508, +0.2039, +0.0447, -0.1384],
-[ +0.4154, -0.6111, +0.5973, +0.3750, -0.0209, +0.2669, +0.4349, -0.4379, -0.8619, -0.6603, +0.3843, +0.4447, -0.2610, -0.0537, +0.1169, +0.2802, +0.0680],
-[ -0.0936, +0.0809, -0.2057, +0.3599, +0.1417, -0.0002, +0.2883, +0.0322, +0.0750, -0.0918, +0.1454, +0.2856, -0.3365, -0.0845, -0.2601, +0.2617, -0.3751],
-[ +0.1020, +0.1826, +0.0839, -0.3837, +0.0659, -0.0032, -0.0296, -0.0230, -0.2824, +0.1242, +0.1188, -0.1835, -0.1085, +0.0111, +0.1342, +0.4190, +0.0310],
-[ +0.2220, -0.2676, +0.4179, +0.2384, +0.1995, -0.2100, +0.3456, +0.2269, +0.1355, +0.0217, -0.1118, -0.0870, -0.1239, -0.0094, +0.0859, -0.1708, +0.1544],
-[ +0.4146, -0.3982, +0.8939, +0.3733, +0.2503, -0.2130, +0.1417, +0.2519, +0.0309, -0.1665, +0.1641, +0.9532, +0.0756, +0.0172, +0.0123, +0.1202, -0.1104],
-[ +0.1094, +0.0515, +0.0742, -0.7886, -0.3253, +0.1596, +0.0308, -0.5371, -0.3584, +0.0223, -0.0030, -0.2774, -0.5786, -0.0680, +1.1358, -0.2489, +0.0265],
-[ +0.1768, +0.0361, -0.7746, +0.1206, +0.1003, -0.2079, -0.0938, +0.1311, +0.4703, +0.2785, -0.1427, +0.0731, +0.5649, -0.0821, -0.2307, -0.0683, +0.1924],
-[ +0.3056, -0.0681, -0.1025, +0.2378, +0.2239, -0.4030, -0.0065, +0.0402, +0.4062, +0.1393, +0.0954, -0.0546, +0.0584, -0.0386, +0.0289, -0.1401, +0.0367],
-[ -0.1283, -0.1635, +0.1080, -0.0220, -0.1000, -0.1157, +0.2681, +0.1661, +0.0822, -0.2251, +0.0893, +0.2289, -0.1836, +0.1515, +0.0688, -0.0912, +0.0177],
-[ -0.0910, -0.2656, -0.1346, +0.1549, +0.1084, -0.2611, +0.2446, -0.2851, +0.2948, +0.0284, -0.3582, -1.3187, -0.3781, -0.0681, +0.0803, -0.1766, +0.3008],
-[ +0.5218, -0.0293, +0.0521, +0.1711, +0.1373, -0.0795, +0.4071, +0.2030, +0.2839, +0.0906, -0.1113, -0.1076, -0.4932, +0.1220, +0.4161, +0.1007, +0.0513],
-[ -0.0858, +0.2734, -0.1252, -0.5853, -0.1065, -0.1348, +0.3453, -0.4680, -0.0558, +0.1232, -0.4178, +0.8754, -0.3607, -0.1534, +0.5096, +0.2548, -0.0748],
-[ -0.2429, +0.3803, -0.6319, +0.0077, -0.0364, -0.1513, -0.0297, +0.8310, +0.1646, +0.0311, +0.1827, +0.7492, -0.6287, -0.0933, -0.6411, +1.1034, -0.4511],
-[ -0.2751, +0.4602, -0.0052, -0.0424, -0.3164, +0.1043, -0.4699, -0.1483, +0.0570, +0.0779, -0.0830, +0.4477, -1.2366, -0.1458, -0.1955, +0.2251, +0.1099],
-[ +0.4880, +0.1914, -0.5189, -0.2372, +0.2696, -0.2005, -0.1336, +0.3093, +0.0783, +0.2784, -0.0874, -0.4397, -0.5851, -0.1695, +0.3920, -0.7212, +0.0386],
-[ +0.1577, -0.3636, +0.0606, +0.0595, +0.2361, +0.0218, -0.1914, -0.0020, -0.1269, -0.0906, +0.0464, +0.1972, +0.0890, +0.0563, +0.0631, -0.1230, -0.1953],
-[ +0.2520, +0.1504, -0.0460, -0.2907, +0.0460, +0.3387, -0.1905, -0.3332, -0.0972, +0.0691, -0.0685, -0.0829, -0.0773, -0.1584, -0.2197, -0.1496, -0.0252],
-[ -0.4237, +0.0056, -0.0304, -0.2339, +0.3789, +0.2567, +0.3093, -0.1058, +0.2272, -0.2528, +0.0951, +0.4202, +0.1412, -0.0213, +0.2918, -0.0306, -0.0275],
-[ +0.0543, +0.3421, +0.2451, +0.2349, -0.2259, +0.0387, -0.0617, -0.0643, +0.0109, -0.1121, -0.1300, -0.0021, +0.0711, -0.0751, -0.0576, -0.3440, +0.1992],
-[ +0.1885, +0.0831, -0.3353, +0.2452, -0.1187, -0.3477, -0.2286, +0.0179, +0.1566, +0.5549, +0.2857, +0.1232, -0.3595, -0.0449, +0.1067, -0.1989, -0.0169],
-[ -0.1334, -0.2713, +0.3466, +0.0449, -0.1024, +0.1663, -0.1981, -0.3261, -0.2438, -0.1765, -0.1748, +0.5400, -0.2122, -0.0318, -0.5316, +0.4447, -0.0700],
-[ +0.1094, -0.1033, +0.2346, -0.3173, +0.1897, +0.2990, +0.3480, +0.2799, -0.2819, -0.2969, -0.0594, -0.0003, -0.2630, -0.1162, +0.1140, +0.1733, -0.1270],
-[ +0.2172, -0.1584, +0.0221, -0.1395, -0.1675, -0.1263, -0.1244, -0.3817, -0.2158, +0.0466, +0.0857, -0.4953, +0.3157, +0.1223, -0.6040, -0.4049, +0.0726],
-[ -0.1488, -0.0286, +0.1821, +0.0005, -0.1175, -0.0874, -0.1072, +0.0381, -0.0206, +0.0871, -0.1451, -0.0249, +0.1206, +0.2396, +0.2498, -0.2140, -0.1405],
-[ -0.0111, +0.3861, +0.0429, -0.0130, +0.0538, +0.2012, +0.2013, -0.2428, +0.0409, +0.3693, -0.0229, -0.0916, -0.2249, +0.0734, -0.0359, +0.1811, +0.0051],
-[ -0.2756, +0.2094, -0.5057, +0.2024, +0.0241, -0.0891, -0.2455, +0.0538, +0.0846, +0.1143, +0.0623, -0.1871, +0.1313, +0.0253, -0.2388, -0.1463, +0.0287],
-[ +0.1821, +0.4514, -0.0363, +0.2531, -0.1088, -0.0400, -0.1291, +0.1353, +0.1665, +0.3382, -0.4276, -0.1547, -0.1877, +0.1149, -0.0641, -0.4630, +0.1352],
-[ +0.1122, -0.1090, +0.3136, +0.3880, +0.1287, +0.0237, +0.0728, +0.0179, +0.0349, -0.1230, +0.0111, +0.6014, -0.3108, -0.0339, -0.2139, +0.1688, +0.0408],
-[ -0.0585, +0.1857, -0.5246, +0.2287, +0.2376, +0.0977, +0.1277, +0.8259, -0.0420, -0.0909, +0.2259, -0.2873, -0.0027, +0.0197, +0.4685, -0.2872, -0.1987],
-[ -0.0200, -0.2907, +0.1864, -0.1628, -0.1605, +0.1749, -0.2185, -0.1611, -0.1128, -0.0374, +0.2906, +0.3250, +0.4870, +0.0309, -0.3275, +0.0048, -0.1310],
-[ -0.0080, -0.4754, +0.1296, -0.0301, -0.3817, -0.1197, +0.4911, -0.4934, -0.2824, -0.0310, +0.0279, +0.2155, -0.6603, +0.0401, -0.8678, +0.4578, -0.0707],
-[ -0.1653, +0.0769, -0.1368, -0.0154, -0.2174, -0.0164, +0.2595, +0.2301, +0.1736, -0.0489, -0.3271, -0.0782, -0.0477, -0.2108, -0.0857, -0.0149, -0.1159],
-[ -0.0895, +0.3569, +0.0548, +0.3007, +0.2871, +0.1508, -0.0002, +0.3219, +0.1019, +0.1113, -0.0978, +0.2202, -0.2125, -0.0533, +0.6329, +0.2266, +0.0218],
-[ -0.0314, +0.2153, -0.1019, -0.1699, +0.0126, +0.0158, -0.3012, -0.0264, +0.2299, -0.0200, +0.0445, +0.3879, +0.5208, +0.2000, +0.4442, -0.4519, +0.0081],
-[ -0.0303, +0.2435, -0.1155, -0.0029, +0.0924, +0.1226, -0.0519, +0.4167, -0.0235, -0.0145, +0.0102, +0.4426, +0.3652, +0.0790, +0.0670, +0.3292, -0.1155],
-[ -0.4764, +0.1008, +0.2453, +0.6503, -0.2319, -0.2316, +0.1459, -0.3701, +0.4247, +0.1477, +0.0578, +1.2480, +0.2435, -0.2183, +0.2025, -0.5131, +0.0148],
-[ +0.0369, -0.6000, +0.2335, +0.2427, -0.2383, -0.2967, -0.1404, -0.0762, -0.1701, +0.0050, -0.3853, +0.2045, +0.1601, -0.0450, +0.3609, -0.2774, -0.2418],
-[ -0.1558, +0.1644, -0.1136, +0.2121, -0.0032, -0.2172, -0.0341, -0.0589, +0.2133, +0.1157, +0.3303, +0.3821, +0.4223, +0.0544, -0.1871, +0.2528, +0.0532],
-[ -0.1705, +0.0316, +0.0959, -0.4905, -0.1434, -0.4177, -0.0139, +0.0173, +0.2193, +0.0451, -0.4526, -0.1873, +0.4062, +0.0100, -1.2451, +1.2191, -0.2005],
-[ -0.0578, -0.1543, +0.0090, +0.2091, -0.0905, -0.3092, -0.0324, -0.9097, +0.1443, +0.0027, +0.5500, -0.5892, -0.6884, +0.0737, +0.3726, +0.0123, -0.3109],
-[ +0.0170, +0.1850, +0.0151, +0.0633, +0.4575, +0.1327, +0.0153, -0.1831, -0.2411, -0.0660, -0.0843, +0.2057, -0.1343, +0.0240, +0.6390, -0.3008, +0.2598],
-[ +0.2004, -0.2134, -0.3945, -0.3735, +0.0749, -0.0204, +0.1091, +0.0723, -0.3266, -0.0416, -0.1158, -0.0958, +0.0165, -0.0369, +0.3759, -0.0372, -0.0946],
-[ -0.0773, -0.0728, -0.4872, -0.3943, -0.2244, -0.1453, -0.0684, -0.0067, -0.2013, +0.1170, +0.1176, +0.1532, -0.1420, -0.0700, -0.0435, +0.1984, -0.1804],
-[ +0.3493, +0.5615, +0.4853, -0.0299, +0.3986, +0.2032, +0.1871, +0.3303, -0.0351, -0.0214, -0.3183, +0.2865, -0.1298, +0.1266, +0.2793, -0.0451, -0.0698],
-[ +0.3691, -0.0414, +0.1429, -0.1778, +0.3977, -0.0978, -0.3099, -0.2705, +0.1606, -0.0288, -0.1289, -0.1052, -0.0404, +0.0166, -0.5058, -0.4936, -0.0004],
-[ +0.1870, -0.4584, +0.1216, -0.0170, +0.2037, -0.1470, +0.3353, +0.1069, -0.0034, -0.4070, +0.3482, -0.5598, -0.1958, +0.0897, +0.1491, -0.0716, +0.1305],
-[ +0.0389, +0.0905, +0.1360, -0.1183, +0.2531, +0.1238, -0.2772, +0.2455, +0.4092, -0.0462, -0.0588, -0.0419, +0.1674, +0.0068, -0.1061, +0.0287, -0.0828],
-[ +0.1001, -0.4006, +0.0288, -0.3762, -0.0410, +0.2275, +0.1096, -0.1166, -0.1334, -0.4214, -0.4301, +0.3060, -0.2374, +0.0423, -0.3930, -0.2825, +0.1954],
-[ +0.1034, +0.6710, +0.3191, +0.3582, -0.1224, +0.1598, -0.1600, +0.0934, -0.1515, +0.0675, +0.2047, +0.1186, -0.1772, +0.0256, -0.1494, +0.0952, +0.1113],
-[ -0.4012, -0.1076, +0.0205, -0.5024, +0.0729, +0.1485, +0.0070, +0.1607, -0.0114, -0.1145, -0.1079, +0.3810, +0.1917, -0.0099, +0.0344, +0.3523, -0.0808],
-[ -0.2240, +0.1399, +0.1148, +0.2574, +0.0202, +0.0974, +0.0275, +0.4080, +0.2255, +0.0175, +0.0463, -0.1122, -0.6143, -0.1468, -0.5921, +0.6715, +0.0307],
-[ -0.3402, -0.2659, -0.1670, +0.3877, +0.1549, -0.0218, +0.0430, +0.1702, +0.0147, -0.0137, +0.0798, -0.2539, -0.0238, -0.0276, +0.1152, -0.1507, -0.0094],
-[ -0.0436, +0.2453, -0.0635, -0.0957, +0.0092, +0.2026, +0.0469, -0.0911, -0.0252, -0.0527, +0.1833, -0.0522, -0.3532, -0.0643, +0.8052, -0.2086, +0.1393],
-[ +0.1356, +0.2174, -0.4187, -0.1698, -0.3939, -0.3418, +0.0977, -0.4303, -0.1747, +0.3483, -0.3828, +0.6477, -0.0193, -0.0432, -0.3092, +0.0965, +0.0512],
-[ -0.0526, +0.0788, -0.0251, -0.0711, +0.1021, -0.0033, -0.1653, -0.4175, +0.6269, +0.1131, -0.0403, -0.9119, -0.0319, +0.0312, -0.7391, +0.4969, -0.2035],
-[ +0.0237, -0.3621, +0.6398, -0.4092, -0.3548, +0.1151, -0.2588, +0.1652, -0.9864, -0.0429, -0.2583, -0.7839, -0.1742, -0.1615, -0.5220, +0.3167, +0.0245],
-[ +0.2773, -0.2533, -0.1067, +0.1248, -0.0263, -0.0443, -0.6161, -0.1194, +0.0183, -0.0374, -0.0112, +0.0789, -0.4672, -0.0865, -0.3901, +0.1714, -0.0693],
-[ +0.3108, +0.0953, -0.1789, -0.1484, +0.0256, +0.0596, +0.3846, -0.1545, -0.1468, +0.0058, +0.0122, +0.0373, +0.1194, +0.1557, +0.2206, -0.2213, +0.0944],
-[ -0.3364, +0.0759, +0.0602, +0.0081, -0.1324, -0.1008, +0.0013, -0.6405, +0.2720, +0.0274, -0.0404, -0.1801, +0.1287, -0.0663, +0.4262, +0.3619, -0.0217],
-[ -0.4219, -0.0153, -0.1689, -0.4714, -0.3856, +0.1550, -0.0396, +0.3023, -0.2935, +0.0254, -0.0017, +0.1311, +0.0634, -0.1347, -0.5716, +0.1617, -0.0855],
-[ +0.1646, +0.1777, -0.1430, -0.0439, +0.0316, -0.1789, +0.2856, +0.1370, +0.2351, +0.2530, -0.3670, -0.1025, -0.2779, +0.0917, +0.1178, +0.3486, -0.0894],
-[ -0.2763, +0.1173, -0.0395, -0.3646, -0.2316, +0.0089, +0.0877, -0.2104, -0.1127, +0.0016, +0.0464, +0.0721, +0.0388, +0.0491, +0.3302, +0.0052, -0.0643],
-[ +0.1751, -0.3577, +0.0741, -0.0451, -0.0270, -0.0501, +0.1754, -0.4259, +0.0053, -0.1944, +0.0852, -0.5543, +0.3060, +0.2323, +0.5691, -0.0617, +0.0329],
-[ -0.1774, +0.0011, +0.2617, +0.1197, +0.0459, -0.0254, +0.1981, +0.3108, +0.0400, -0.1453, -0.0713, -0.3316, +0.1455, -0.0747, +0.2722, +0.3458, -0.0431],
-[ +0.2174, +0.0580, -0.3161, +0.3940, -0.2644, -0.1984, -0.1044, +0.2935, +0.0019, +0.3177, -0.0683, -0.4946, +0.2040, +0.2826, -0.1606, -0.4582, +0.2052],
-[ +0.0825, -0.2587, -0.6098, -0.7666, -0.1891, +0.1545, -0.1752, -0.1813, -0.3137, -0.1742, -0.0400, +0.3352, -0.3175, +0.0617, +0.2097, -0.1684, -0.0412],
-[ -0.1112, +0.2379, -0.0920, -0.0707, -0.0307, +0.0797, -0.1313, -0.1122, -0.3038, +0.0529, -0.3645, -0.2686, +0.0730, -0.0592, -0.0104, +0.1403, +0.0906],
-[ +0.3680, +0.0528, +0.1097, +0.1391, -0.0911, +0.0238, +0.0677, +0.1313, -0.3832, -0.0146, +0.3670, -0.3521, -0.0276, +0.1317, +0.1161, -0.2734, +0.0763],
-[ +0.1579, +0.1185, +0.2387, -0.5239, -0.3156, -0.0856, +0.1244, -0.2377, -0.0763, +0.1003, -0.1049, -0.3365, +0.0325, -0.0759, -0.1114, -0.1658, -0.1217],
-[ -0.1804, -0.4128, +0.1567, +0.5702, -0.3200, +0.0408, -0.0244, -0.0840, -0.0527, -0.1145, +0.1109, +0.2210, +0.3458, +0.0023, -0.3264, -0.4558, +0.1183],
-[ +0.0659, -0.1952, -0.1324, +0.1010, -0.2289, -0.1007, +0.0708, +0.1144, -0.0813, +0.0920, +0.3396, +0.0104, +0.1072, -0.0226, -0.1626, -0.1254, +0.1932],
-[ +0.1231, +0.2101, -0.1953, -0.3647, +0.4056, -0.1017, -0.0869, -0.1301, +0.1228, -0.0524, -0.0305, +0.0722, -0.0188, +0.0059, -0.0921, -0.0607, +0.1297],
-[ +0.3724, +0.0801, +0.2260, +0.3577, +0.0365, -0.1573, +0.4085, +0.1012, +0.2122, +0.1751, -0.0605, +0.3211, +0.3520, +0.0157, -0.3718, +0.2995, -0.2521],
-[ +0.0650, -0.0647, +0.2336, -0.0282, -0.0795, +0.1878, +0.1919, +0.1609, +0.0767, -0.2512, +0.1858, -0.4086, +0.2826, +0.1826, +0.1671, +0.0621, +0.1772],
-[ +0.2919, -0.1500, +0.1861, -0.1115, -0.0102, -0.2352, -0.0982, +0.1106, +0.3164, +0.0698, -0.4432, +0.2496, +0.0924, +0.0937, -0.2256, -0.2866, +0.0928],
-[ -0.1124, +0.0442, +0.3579, +0.1774, +0.1772, +0.2148, +0.2384, +0.2642, -0.0853, -0.7385, +0.1676, -0.0897, -0.0031, +0.0578, -0.0487, -0.0222, +0.1840],
-[ -0.1470, +0.0944, +0.3412, +0.3212, +0.2143, +0.3426, -0.1407, -0.0518, -0.3807, -0.0837, -0.0714, +0.2675, -0.3793, -0.3674, -0.3998, +0.0780, +0.0363],
-[ -0.3876, -0.0642, +0.0959, -0.2092, -0.0610, +0.2080, +0.1597, -0.1985, +0.0557, -0.1315, -0.1643, +0.2609, +0.4146, -0.0175, +0.2486, -0.1299, +0.0421],
-[ -0.2262, -0.1184, +0.2385, -0.7373, -0.0148, +0.1660, +0.2681, -0.0921, +0.1252, -0.2751, -0.1190, -0.8493, +0.1025, +0.1227, -0.4286, +0.5744, -0.0405],
-[ -0.0374, +0.0379, -0.4226, -0.1330, +0.1566, +0.0088, -0.0520, -0.0289, -0.1716, +0.0312, +0.0962, +0.3347, +0.5196, +0.0220, -0.1559, -0.3106, +0.2403],
-[ +0.0513, +0.4744, -0.0200, +0.2514, +0.3022, +0.0020, +0.4068, +0.9192, +0.1873, +0.0072, +0.2791, +0.2587, +0.2999, +0.2515, +0.2632, -0.2145, -0.1129],
-[ -0.0104, +0.0656, +0.3292, -0.1732, -0.1230, +0.2711, +0.1398, -0.5466, -0.4228, -0.0740, +0.2116, +0.3474, +0.0030, -0.0176, +0.3739, -0.1911, -0.0056]
+weights_final_b = np.array([
+ +0.0149, +0.1334, -0.1019, -0.0498, +0.0919, -0.2079, +0.1914, -0.0708,
+ +0.0737, -0.1228, +0.0112, -0.0441, +0.0087, -0.1149, +0.0063, +0.0170,
+ -0.0965
])
+# yapf: enable
-weights_final_b = np.array([ +0.0149, +0.1334, -0.1019, -0.0498, +0.0919, -0.2079, +0.1914, -0.0708, +0.0737, -0.1228, +0.0112, -0.0441, +0.0087, -0.1149, +0.0063, +0.0170, -0.0965])
-
-if __name__=="__main__":
- demo_run()
+if __name__ == "__main__":
+ demo_run()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py
index 4bd7752ff..fbd35164d 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedDoublePendulumBulletEnv_v0_2017may.py
@@ -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])
-
- 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
+ "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 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()
-
- 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]
-])
+ 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_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])
+# 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_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]])
+
+weights_final_b = np.array([+0.0190])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py
index 9235d167d..e4e84dd93 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumBulletEnv_v0_2017may.py
@@ -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])
-
- 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
+ "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 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
-
-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]
-])
+ 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_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])
+# 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_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]])
+
+weights_final_b = np.array([+0.0352])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py
index 5ce5bae7f..8c1ccd08d 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_InvertedPendulumSwingupBulletEnv_v0_2017may.py
@@ -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])
-
- 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
+ "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 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()
-
- 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]
-])
+ 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_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])
+# 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_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]])
+
+weights_final_b = np.array([+0.2753])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py
index 952af87ce..b88e19f51 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/enjoy_TF_Walker2DBulletEnv_v0_2017may.py
@@ -2,289 +2,2036 @@
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], 128)
- assert weights_dense2_w.shape == (128, 64)
- assert weights_final_w.shape == (64, 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], 128)
+ assert weights_dense2_w.shape == (128, 64)
+ assert weights_final_w.shape == (64, 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("Walker2DBulletEnv-v0")
- env.render(mode="human")
- pi = SmallReactivePolicy(env.observation_space, env.action_space)
+ env = gym.make("Walker2DBulletEnv-v0")
+ env.render(mode="human")
+ pi = SmallReactivePolicy(env.observation_space, env.action_space)
- env.reset()
+ env.reset()
- while 1:
- frame = 0
- score = 0
- restart_delay = 0
- obs = env.reset()
+ while 1:
+ frame = 0
+ score = 0
+ restart_delay = 0
+ obs = env.reset()
- while 1:
- time.sleep(1./60.)
- a = pi.act(obs)
- obs, r, done, _ = env.step(a)
- score += r
- frame += 1
+ 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
+ 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.5923, +0.0708, -0.2868, -0.5138, -0.1376, +0.3921, +0.3474, +0.2376, +0.6664, +0.1282, +0.1778, +0.2879, -0.3030, +0.1678, +0.1248, +0.1665, -0.1129, -0.5741, +0.1318, +0.4056, +0.2123, +0.1856, +0.3895, +0.0076, +0.4030, +0.1592, +0.2418, +0.0302, -0.2642, -0.0772, -0.5000, -0.0241, +0.3221, +0.1268, -0.1013, +0.1987, +0.2850, -0.3257, -0.1115, -0.3003, +0.0450, -0.2232, -0.1471, +0.5303, +0.6448, +0.0623, +0.4801, +0.1554, -0.0681, -0.4085, +0.6602, +0.1064, +0.1389, +0.6386, +0.5123, -0.3210, -0.0565, +0.2629, +0.5662, -0.2477, -0.1244, +0.0125, +0.1585, +0.0328, +0.0098, +0.0898, +0.4162, -0.0758, -0.4449, +0.4196, +0.0923, +0.4323, -0.2452, -0.1646, +0.8115, +0.3922, +0.2736, -0.2587, +0.6535, +0.1253, +0.0194, +0.3765, +0.2678, +0.4038, -0.1404, -0.2698, +0.1081, +0.0031, +0.4622, -0.1806, -0.2798, -0.2216, +0.2180, -0.0131, -0.3375, +0.2901, +0.2382, -0.0402, +0.4257, -0.2084, -0.1102, +0.6300, +0.0378, +0.5702, +0.0085, -0.4068, +0.5516, +0.1101, +0.4330, +0.0053, +0.0656, +0.6463, +0.2717, -0.5689, -0.2151, +0.1876, +0.6149, +0.1463, +0.2377, +0.4734, -0.5056, +0.5846, +0.1847, +0.4174, -0.0182, -0.0434, +0.4932, +0.1675],
-[ -0.0323, +0.1990, +0.0035, +0.1374, -0.0162, +0.1237, -0.2231, +0.3492, -0.0100, +0.1316, -0.4408, -0.3253, +0.0478, +0.1452, +0.1131, +0.0822, +0.3286, +0.0443, -0.1344, -0.0785, -0.4665, -0.1749, -0.2719, +0.1309, +0.2622, -0.1787, +0.0132, +0.0169, +0.1424, -0.1192, -0.0486, +0.0994, +0.2762, -0.2210, -0.3417, -0.0453, +0.2207, +0.1077, -0.2448, +0.1683, +0.0924, +0.1232, -0.1016, +0.2795, +0.3878, -0.3440, -0.0133, -0.1766, -0.2442, -0.3664, +0.1455, -0.1039, -0.0158, +0.1746, -0.3620, -0.1886, +0.4197, -0.1972, -0.0783, -0.2513, +0.1576, -0.0283, +0.4125, -0.0183, +0.2840, -0.0190, -0.2548, -0.0755, +0.2639, +0.1207, -0.0633, -0.2397, +0.2823, -0.1291, +0.1105, -0.3745, -0.0536, -0.1834, +0.3941, -0.0746, -0.0950, +0.1063, -0.0520, -0.1393, +0.1153, -0.1724, -0.3873, +0.2700, -0.2059, -0.1402, -0.0576, -0.2060, -0.1197, +0.1246, +0.1575, -0.0923, -0.1524, -0.1861, +0.3553, -0.3640, +0.1487, +0.0001, -0.0485, -0.1573, +0.0710, -0.0659, -0.1262, -0.2399, +0.0415, -0.1848, -0.0352, -0.2980, +0.4015, -0.2548, +0.0777, -0.0573, -0.2989, +0.2988, -0.2647, -0.0445, +0.0962, +0.1144, -0.1381, -0.1443, +0.2538, -0.0203, -0.1139, -0.0137],
-[ +0.0101, -0.1099, -0.2746, +0.1418, -0.2257, -0.0753, -0.0880, -0.5336, -0.3857, +0.4742, +0.0142, -0.0733, -0.2721, +0.1913, -0.4624, -0.0272, -0.0448, -0.1782, -0.0153, -0.1250, +0.0004, -0.1004, +0.1810, -0.1565, +0.1465, +0.2069, +0.2239, -0.2894, -0.2431, +0.1741, +0.0018, -0.0586, +0.1388, +0.1907, +0.0643, +0.0112, +0.0272, +0.1716, -0.2055, +0.1644, -0.1780, -0.4091, -0.4636, -0.1947, -0.1812, -0.1876, -0.3228, -0.2501, -0.3992, -0.2498, -0.1115, -0.4160, -0.2285, -0.1908, -0.3892, -0.0788, +0.2413, +0.0193, -0.3308, -0.0670, +0.2808, -0.3637, +0.0275, -0.2128, -0.0328, +0.4001, +0.3251, +0.4071, +0.2900, +0.1178, -0.4016, -0.2668, +0.0388, -0.2220, -0.3311, +0.0219, -0.0518, +0.0345, +0.2008, +0.2282, -0.0269, -0.2531, -0.5376, -0.5342, -0.0932, -0.0678, -0.0573, -0.3451, +0.3746, -0.3500, +0.1244, -0.3478, +0.1564, -0.4525, -0.0010, +0.0473, +0.1666, -0.0538, -0.2431, +0.2113, +0.0891, +0.2253, -0.2024, +0.0722, -0.0958, -0.0994, -0.1086, +0.1991, -0.2600, +0.1181, -0.1903, +0.1795, -0.0618, +0.0945, -0.2850, +0.0669, +0.1276, -0.2620, -0.4172, +0.2954, -0.4614, +0.0665, -0.0353, -0.0430, -0.0465, +0.3755, -0.1195, +0.2084],
-[ +0.0486, -0.0247, +0.1675, +0.3216, -0.2398, +0.2336, -0.1924, -0.7100, +0.4238, -0.2251, -0.1045, -0.0824, -0.1782, +0.0657, -0.3393, -0.0225, -0.0442, -0.1090, +0.2088, +0.0038, -0.0173, -0.1676, +0.5690, -0.0158, -0.4489, -0.0216, +0.2328, +0.2235, +0.0548, +0.5565, -0.0349, -0.2223, +0.3198, +0.0895, -0.2805, -0.3474, -0.3506, -0.1487, -0.1241, +0.1920, +0.2093, +0.0074, -0.3248, -0.0891, -0.3713, -0.0435, -0.1554, +0.4472, +0.7299, -0.0282, -0.0727, +0.2084, -0.6375, +0.1005, -0.1439, +0.4170, +0.2134, -0.0393, -0.1067, -0.0428, +0.0359, -0.5413, -0.1321, -0.4210, +0.5401, +0.1721, -0.0240, -0.2389, -0.0596, -0.2618, +0.0683, +0.0520, +0.2830, -0.0237, +0.7084, +0.0032, +0.6990, +0.0166, -0.1442, +0.5299, -0.1867, -0.2291, -0.1312, +0.0618, -0.2247, -0.2138, +0.5049, +0.1986, -0.0194, +0.1705, +0.0661, +0.3354, -0.5126, +0.1879, +0.1266, +0.1527, -0.1481, +0.0534, +0.4824, +0.2081, +0.2159, +0.1490, -0.0946, -0.3135, +0.0068, +0.2763, -0.3787, +0.5304, +0.2405, -0.2065, -0.3856, -0.3421, -0.0920, -0.2431, +0.1800, -0.1242, -0.2831, -0.4493, -0.5491, +0.0137, +0.3891, -0.1039, -0.2604, -0.5305, -0.4397, +0.2243, +0.3320, -0.5214],
-[ +0.2827, -0.0681, -0.0571, +0.1937, +0.0216, -0.0113, -0.0919, +0.0923, +0.1170, -0.1119, +0.0732, +0.3078, -0.5637, +0.1494, -0.1741, -0.1985, -0.0968, +0.1848, -0.2082, +0.1764, +0.2342, +0.1448, +0.0192, -0.2817, -0.1275, -0.0167, +0.0631, +0.1762, -0.2762, +0.1179, -0.0295, +0.1779, +0.0460, -0.3562, +0.0457, +0.1098, +0.2099, +0.1457, +0.0766, -0.2229, +0.1076, +0.1364, -0.0568, +0.2080, +0.2249, +0.1715, +0.1573, -0.0279, +0.2404, -0.1265, +0.0210, +0.4009, +0.2633, -0.1419, -0.3217, -0.0988, +0.2678, -0.0627, -0.1092, -0.4646, -0.2602, -0.0886, -0.1043, +0.3363, -0.1775, +0.0361, -0.2431, -0.2028, +0.0805, -0.1340, -0.1488, +0.2928, +0.0214, +0.3602, +0.0467, +0.1229, +0.2465, -0.1079, -0.1829, -0.1387, -0.2267, +0.1946, -0.2169, +0.3601, +0.3059, +0.0612, +0.2089, -0.1133, -0.0262, -0.0988, +0.2344, +0.2919, -0.2250, +0.0829, -0.2239, +0.0054, +0.1842, -0.4559, -0.2440, -0.0654, +0.1422, -0.2005, -0.0992, +0.0436, -0.3750, -0.4290, +0.2150, -0.2206, +0.3941, -0.2326, -0.2311, +0.0832, +0.1774, -0.0006, +0.0894, -0.2395, +0.1252, -0.2813, +0.2075, -0.0058, +0.3007, -0.0255, -0.1857, +0.4371, +0.1055, +0.1396, +0.0276, -0.3052],
-[ -0.3549, +0.0244, +0.0128, -0.3312, -0.2543, +0.3405, +0.1028, -0.3751, +0.4624, +0.0440, +0.0182, +0.2063, -0.2831, -0.2593, +0.3181, +0.3479, -0.2162, -0.5026, -0.1913, +0.2037, -0.5378, +0.0117, -0.1922, -0.2390, +0.3209, -0.1556, +0.5278, -0.1576, -0.4052, -0.5298, -0.3115, -0.3645, -0.0674, +0.5300, +0.1836, +0.6099, +0.1260, -0.3193, -0.2892, +0.1283, -0.5849, -0.0597, +0.4373, -0.4667, -0.0563, +0.0303, -0.2873, -0.6184, -0.3731, +0.0120, -0.0374, -0.1511, +0.0177, +0.7742, +0.6095, -0.8566, +0.1299, -0.7749, +0.2235, -0.4156, +0.3176, +0.3276, -0.3272, -0.0117, +0.3580, +0.0025, +0.3159, +0.3943, +0.1240, -0.5251, -0.3494, -0.0956, -0.2783, -0.3312, +0.1153, +0.3601, -0.1687, -0.0901, -0.2105, -0.1598, -0.0696, -0.4319, +0.5911, +0.1031, -0.4128, -0.3107, -0.4399, +0.0569, +0.0503, -0.8104, +0.1960, -0.3432, +0.1123, -0.0527, +0.3002, -0.2125, -0.1912, -0.2889, -0.1487, -0.1293, +0.2371, -0.1723, +0.6543, +0.5766, +0.3827, -0.0465, +0.3146, -0.6999, +0.1115, +0.0831, -0.4371, -0.1094, -0.0659, +0.1174, -0.3606, +0.2013, +0.4883, -0.3268, +0.2838, +0.3358, -0.3129, +0.0897, +0.1626, -0.1402, +0.4700, -0.3773, +0.3199, +0.0778],
-[ -0.0380, -0.0186, -0.0973, -0.0650, -0.0797, -0.0571, -0.2562, +0.3550, +0.0175, -0.2976, +0.1348, -0.1437, -0.2194, -0.0865, -0.1383, +0.1785, +0.2052, +0.1327, +0.3076, -0.0208, -0.5012, -0.3738, -0.0742, +0.0206, -0.0261, -0.0753, -0.0365, +0.2353, +0.2044, +0.1071, -0.1511, +0.1991, +0.1419, +0.2457, +0.2332, +0.2887, +0.0175, -0.0174, -0.3288, +0.0172, -0.2783, +0.1705, +0.0900, -0.1581, +0.0823, +0.1243, +0.0309, +0.1373, -0.1223, +0.0086, +0.3729, +0.0423, +0.2373, +0.4041, -0.2373, +0.3242, -0.3292, +0.2857, -0.1908, -0.1969, +0.4179, +0.0252, -0.0239, -0.3202, -0.2150, +0.0059, +0.1508, +0.3510, -0.2508, +0.2974, -0.3275, +0.1462, -0.3206, -0.3074, -0.1402, +0.3046, -0.1896, -0.1409, -0.1032, -0.2205, +0.0122, +0.0114, +0.0079, +0.0923, -0.0840, +0.1730, -0.1152, +0.3725, -0.1648, +0.0536, -0.1832, +0.0221, -0.0002, +0.1058, +0.0079, +0.0545, -0.4014, -0.0045, -0.0859, +0.1899, -0.1464, +0.0611, +0.1560, +0.2330, -0.0436, -0.0437, -0.0359, -0.1468, +0.4266, -0.4483, +0.1607, -0.0640, +0.3039, +0.1245, +0.0614, -0.0151, +0.1026, +0.4184, -0.3741, -0.1652, -0.1884, +0.0648, +0.0267, -0.0217, +0.1279, -0.1109, +0.2459, -0.1909],
-[ +0.4641, -0.2639, +0.1744, +0.4878, -0.2263, -0.0335, +0.5683, +0.0308, +0.3132, +0.0384, -0.0191, +0.6840, +0.7869, +0.7729, -0.2036, +0.1718, -0.5897, -0.1966, -0.0254, +0.1200, +0.6171, -0.6490, +0.3407, +0.4501, -0.0544, -0.0178, +0.4335, +0.5922, +0.4188, +0.1670, -0.2214, -0.1771, +0.0564, -0.0337, -0.1317, -0.0320, +0.4909, -0.6020, +0.5674, +0.7039, -0.4565, +0.5487, -0.3368, +0.4934, -0.1279, -0.5785, -0.6351, -0.9523, +0.5945, +0.1008, -0.2629, -0.1561, +0.0582, -0.3995, -0.0903, +0.6003, +0.2845, -0.2892, -0.3994, +0.2377, +0.8273, -0.6761, +0.7568, -0.4131, +0.4980, +0.2917, +0.1099, +0.1988, -0.3377, -0.5839, -0.4254, -0.1366, +0.7022, +0.2762, -0.0126, -0.6649, +0.3256, +0.4342, +0.1040, +0.9052, +0.4308, -0.2127, +0.4446, +0.0384, +0.2398, -0.2750, +0.7937, +0.0828, -0.3238, -0.1872, -0.0145, +0.0556, +0.1063, -0.3786, +0.6058, -0.0708, +0.3147, +0.2582, +0.3061, -0.0249, +0.3195, +0.6195, +0.8043, +0.1070, +0.0869, +0.0387, +0.3916, +0.6197, -0.1543, +0.0553, +0.6231, -0.4391, +0.0212, +0.0637, -0.5223, +0.2129, -0.3591, -0.1149, +0.7172, +0.1986, -0.1989, -0.0314, +0.6212, -0.0091, -0.7394, -0.5792, +0.3289, -0.9215],
-[ -0.4254, -0.1010, -0.2326, +0.0115, -0.2136, +0.0043, -0.2096, -0.1871, -0.3127, +0.3810, +0.2582, +0.0857, -0.0747, -0.0162, +0.3173, -0.3385, -0.6953, -0.1816, -0.0029, -0.5805, -0.4907, -0.2431, -0.0356, +0.0890, -0.4312, -0.3004, -0.2911, -0.0044, -0.1303, -0.4609, +0.4219, -0.8413, +0.3006, -0.0198, +0.0991, +0.1724, -0.6699, -0.5464, -0.2279, +0.1663, -0.5687, -0.0257, -0.4929, +0.3131, -0.2199, +0.6044, +0.3898, -0.9848, +0.3623, -0.0672, -0.3914, -0.0168, +0.4831, +0.1769, +0.4379, -0.3998, -0.5295, +0.4740, +0.0720, -0.2860, -0.2657, -0.2048, -0.6462, -0.1063, -0.3977, -0.0696, +0.3865, +0.1880, -0.2615, -0.1497, -0.2452, +0.6668, +0.3959, +0.1580, -0.0861, +0.0015, -0.4241, -0.8260, -0.2909, -0.2317, +0.2107, +0.0659, -0.1037, -0.4058, +0.0144, +0.0817, -0.5299, +0.0591, -0.1258, -0.5378, -0.9845, +0.4663, +0.1014, -0.8416, -0.4150, +0.0328, +0.1150, -0.3711, -0.2761, +0.2032, -0.2557, -0.1680, +0.3407, +0.1772, -0.2910, +0.5103, +0.4964, +0.0582, +0.3356, +0.5211, +0.3697, +0.3797, -0.1063, -0.1224, -0.7502, +0.0040, -1.0549, -0.4150, +0.5061, -0.0295, -0.2924, +0.5322, +0.5314, +0.0182, -0.5597, +0.1434, +0.3410, +0.3369],
-[ +0.3056, +0.0843, +0.0543, -0.4615, -0.4151, -0.0575, -0.8068, -0.2107, +0.8528, +0.1961, +0.2841, -0.2850, -0.0830, -0.2409, +0.0112, +0.0230, +0.0239, +0.5198, +0.4115, +0.0110, -0.0818, +0.4822, +0.3047, -0.1824, +0.3432, +0.0778, +0.0768, +0.0894, +0.2638, -0.3116, -0.1630, -0.5821, -0.0214, -0.0087, +0.3884, +0.1033, -0.2790, -0.1378, -0.2609, -0.2486, +0.1585, -0.4514, -0.2467, -0.4613, -0.1185, +0.5398, -0.0848, +0.1043, -0.1359, -0.0675, -0.3464, +0.2428, -0.2526, +0.2612, +0.4603, +0.0659, -0.3555, +0.3165, +0.0506, -0.0040, -0.4325, -0.0251, -0.1762, +0.6595, -0.2948, -0.3917, +0.1515, +0.0745, -0.2204, -0.0646, +0.4103, +0.3584, +0.4389, +0.2079, +0.0346, +0.1363, -0.7773, +0.2108, -0.2785, -0.4362, -0.7424, +0.3171, +0.3104, +0.0360, -0.0472, -0.0106, -0.0949, +0.3420, +0.4692, +0.3801, -0.6458, +0.0883, +0.1774, -0.4107, -0.5429, -0.0189, -0.4815, +0.0808, -0.4501, +0.0710, +0.0171, -0.2874, -0.1613, -0.0986, +0.4779, -0.0379, -0.0432, -0.1339, +0.2031, -0.1244, -0.4811, +0.0729, +0.2716, +0.2948, -0.4478, -0.1647, +0.3046, +0.0196, -0.3698, -0.2645, +0.0715, +0.1403, +0.0169, -0.1153, -0.2641, -0.0276, +0.1861, +0.3948],
-[ +0.2767, -0.0743, +0.2740, -0.4792, -0.7306, +0.0418, -0.1570, +0.4153, +0.0627, +0.4058, +0.4510, +0.3410, +0.0399, -1.0956, -0.5747, -0.1151, +0.2627, -0.1982, -0.1019, +0.7238, -0.0384, +0.3866, +0.3792, +0.2662, +0.2362, +0.1112, +0.2728, -0.2878, -0.0650, -0.0905, +0.3320, +0.3422, +0.7680, +0.4203, +0.4889, -0.3364, +0.1576, +0.2025, -1.0459, +0.1940, -0.5367, +0.4368, -0.1559, -0.0261, +0.0649, +0.6833, +0.0792, -0.1099, -0.9185, -0.5792, +0.2715, -0.5116, -0.8132, +0.5739, -0.4300, +0.2802, -0.0944, -0.8149, -0.2920, -0.8222, +0.1704, +0.0467, +0.0717, -0.0861, -1.1820, -0.0288, -1.2486, +0.2247, +0.4574, -0.3306, -0.2873, +0.1044, -0.0061, -0.6058, +0.7101, +1.0664, +0.0885, +0.2544, +0.2762, +0.9233, -0.4762, -0.1358, -0.4847, +0.3625, +0.2238, +0.5404, +0.4796, -0.4765, -0.0754, +0.0130, +0.0350, +0.8824, +0.6476, +0.2358, -0.0104, +0.6710, -1.3786, +0.1219, +0.8695, -0.9081, +0.5234, -0.7513, -0.4966, +1.2130, -0.8264, +0.8768, +0.1144, +0.0391, +0.0208, -0.4296, -0.2219, +0.5561, +0.0160, -0.7934, +0.0037, -0.1454, +0.7168, -0.0297, -0.2560, +0.3648, -0.6412, -0.7076, +0.3461, +0.0958, +0.2879, +0.2225, +0.4269, -0.2274],
-[ -1.2371, +0.7142, +1.0170, -0.2385, +0.4375, +0.6428, +0.7528, -0.1837, +0.3177, +1.5337, +0.8810, +1.0799, +0.7406, -0.6905, -0.1914, -0.2182, +0.9355, +0.3845, +0.0422, -0.6012, +0.7606, -0.6731, +0.7571, -0.2129, -0.3527, +0.4415, -1.1536, -1.0436, -0.6994, +0.1156, +0.1110, -0.4602, +1.2682, -0.0122, -0.2747, -0.5565, +1.1461, +0.2052, -0.4670, +0.1062, +0.1336, +0.4687, -0.3789, -0.5272, +0.5302, -0.0505, -0.8930, +0.3562, +0.1406, +0.1925, +0.0953, -1.0493, -0.2918, +0.9845, -0.0997, -0.1381, -0.0345, +0.3173, +0.0242, -0.8146, +0.8637, +0.6093, +0.7513, +0.3913, +0.2520, +0.3459, +0.4740, -0.8409, -0.0319, -0.2245, -1.3980, +0.5117, +0.5224, -0.9587, +0.2602, -0.3061, -0.0077, +0.1915, -0.0583, +0.8455, -0.2225, +0.1052, +1.1755, +0.3301, -1.3673, +0.1438, +0.3685, -1.0758, +1.0890, -0.2946, +0.3831, +0.4291, -0.5933, +0.1440, +0.2730, +0.5047, -1.4292, +0.4666, -0.0684, -1.0907, +0.3267, -0.3991, +0.8139, +0.6090, +0.1770, +0.7682, -0.2264, +0.0630, -0.3205, -0.4079, -0.2719, +0.0128, -0.8448, -1.2259, -1.2494, -0.1504, +0.2575, -0.8282, +0.4063, +1.1256, +0.1730, -0.8418, +0.6516, -0.5008, -0.0957, +0.3784, -0.7828, -0.2556],
-[ +0.4096, -0.4381, +0.0800, +0.4671, +0.2710, +0.3707, +0.1151, +0.0230, -0.1066, -0.6900, -0.1603, -0.3079, -0.0686, -0.6147, -0.3030, -0.1793, -0.7013, +0.1995, +0.2661, +0.2716, -0.0216, -0.7503, -0.5498, -0.1302, -0.3296, +0.3840, +0.0224, -0.1708, -0.1937, -0.2009, -0.5012, -0.4132, -0.1342, +0.2941, -0.3885, +0.0947, +0.0590, +0.1700, -0.4708, -0.1097, -0.0097, +0.3135, +0.2190, -0.6015, +0.0922, -0.0361, -0.3555, +0.0014, +0.2416, +0.7169, +0.0544, +0.0161, -0.4381, -0.0826, -0.2879, -0.2404, -0.3624, -0.3565, -0.0936, +0.1039, +0.0661, -0.2627, +0.1202, -0.3224, -0.5876, -0.3586, +0.1150, -0.3245, +0.3580, +0.0222, +0.3645, -0.1235, -0.1768, +0.1465, -1.0948, +0.0147, +0.3538, +0.2351, -0.3125, +0.3397, +0.3092, -0.1426, +0.1506, +0.1900, +0.0469, +0.0054, +0.3150, -0.0771, -0.6345, -0.3055, +0.4514, +0.1163, -0.2015, +0.2673, +0.6658, -0.0627, -0.4941, -0.0477, +0.1703, +0.0382, -0.1618, +0.6503, -0.4697, -0.3565, -0.6726, +0.1886, -0.3776, -0.1012, -0.3556, +0.1710, +0.1496, -0.3936, -0.0074, +0.4109, +0.1207, +0.6998, +0.3481, +0.2814, +0.1733, -0.0011, +0.1370, +0.2159, -0.1052, +0.3861, +0.1950, -0.7201, -0.7551, -0.4230],
-[ -0.3067, -0.4930, +0.0005, -0.2896, -0.1727, +0.7936, +0.7091, -0.4756, -0.1008, -0.1327, +0.5747, +1.1786, -0.6373, -0.8808, -0.7177, -0.2952, -0.0674, -0.1895, -1.5115, +0.0899, +0.1620, +0.4005, -1.3567, -0.5376, -0.8410, +0.9262, -0.3323, -0.2384, -0.1566, -0.5104, -1.0051, -0.2508, -0.5976, -1.7098, -0.2825, +0.3746, -0.2511, +0.2700, -0.8215, -0.4912, +0.3659, -0.0335, -0.5009, +0.3888, +0.1754, +0.0389, +0.5997, +0.5174, -0.2969, -0.1951, -0.8337, -0.7546, +0.3798, -0.0360, +0.1299, +0.1715, -0.1466, -0.2220, -0.5778, -0.4419, -0.2217, +0.2688, -0.7268, +0.7278, +0.3627, -0.5958, +0.9821, -0.5816, +1.0788, +0.1393, -0.1474, +0.0149, +0.2589, +0.3256, -0.8790, +0.4376, -0.0024, -0.7049, -0.3868, -0.0158, +0.8335, +0.5016, -0.1198, +0.4702, -0.7057, -0.0416, +0.4448, +0.7836, -0.4379, -0.9832, -0.4550, -0.4196, +0.8538, -0.7044, -0.1322, -0.1303, +0.6359, -0.0804, +1.0178, +1.3486, +1.1624, +0.0790, -1.1682, -0.6815, -0.3072, -0.2573, -0.4431, +0.5407, -0.5736, +0.6607, +0.3793, -1.6072, -1.2694, +0.7025, -0.3560, +0.4921, -0.4464, +0.1878, +0.2828, -0.8566, -0.2740, +0.1552, -0.3026, +0.5256, -0.7969, -1.0224, -1.4169, -0.4385],
-[ -0.1259, -0.6170, +0.2135, -0.3418, -0.3997, -0.2842, -0.3138, -0.3543, +0.2284, -0.5683, -0.6383, -0.2562, +0.2448, +0.0349, -0.0070, +0.3173, +0.3845, +0.0760, -0.0011, +0.1687, -0.2101, +0.2975, -0.1408, +0.4728, +0.3411, -0.8453, -0.1121, -0.0397, -0.2378, -0.7145, +0.2055, +0.0822, -0.0557, -0.1722, -0.3179, -0.1208, +0.2442, +0.1715, +0.1880, -0.1211, -0.0342, -0.0293, +0.0311, -0.1830, -0.0408, -0.6688, -0.2091, -0.0040, -0.7909, -0.5701, +0.5024, -0.3416, -0.5435, -0.3508, -0.1217, -0.2373, +0.1755, -0.1108, +0.1743, -0.0851, +0.1787, +0.2393, -0.1975, -0.0802, -0.2206, +0.0480, +0.1984, +0.3452, -0.5239, -0.5806, -0.1068, -0.1596, -0.7319, +0.4167, +0.2523, -0.4128, +0.1135, +0.0306, +0.1043, +0.0031, -0.0962, -0.4736, +0.1725, +0.4047, +0.1519, -0.2261, -0.0665, -0.0859, -0.2420, +0.0381, +0.0051, -0.9161, +0.2209, -0.6169, -0.1194, +0.2994, -0.0627, +0.0196, -0.0753, -0.3026, -0.1814, -0.1946, +0.5229, -0.3275, +0.4493, -2.3710, +0.5644, +0.3316, -0.1655, +0.2269, -0.7205, -0.7091, +0.2792, -0.0576, -0.2398, +0.0926, -0.0381, +0.3547, +0.2970, -0.6312, +0.2424, -0.1980, +0.4490, -0.3666, -0.4262, -1.0815, +0.0510, +0.1120],
-[ -0.1522, +0.7263, -0.2575, +0.6404, +0.6986, +0.2308, +0.6524, -0.6431, +0.4774, +0.3122, -0.3521, +0.3393, +0.2929, -0.3382, +0.2161, +0.1669, +0.4713, +0.3194, -0.1374, +0.1473, +0.0257, +0.3532, -0.3252, +0.5917, -0.0704, -0.1053, -0.2127, +0.2276, -0.0699, -0.2108, +0.4681, -0.3924, -0.0363, +0.4286, -0.1897, -0.3929, -0.5962, -0.0255, -0.4458, -1.0351, -0.1633, +0.0820, -0.9262, -0.3648, -0.1328, -0.8021, -0.2717, +0.1889, -0.0327, +0.1726, +0.4866, -0.2176, -0.0771, +0.2216, -0.7842, -0.0576, +0.0865, +0.0882, -0.1196, -0.1501, -0.3229, +0.1669, -0.4632, -0.5473, -0.0691, +0.4595, +0.1466, -0.0135, +0.0910, -0.6819, +0.0899, -0.2865, -0.2059, -0.1933, +0.4151, -0.7514, -0.1771, -0.1813, +0.4952, -0.1999, +0.5819, +0.7551, +0.2075, +0.3148, +0.2755, -0.0200, -0.1676, -0.3802, -0.4465, -0.2035, +0.4219, +0.7001, -0.4227, -0.3968, -0.0350, +0.0262, -0.5200, -0.8271, +0.6630, -0.1405, +0.3552, +0.1478, +0.4814, -0.6110, +0.4737, -0.1415, +0.3233, +0.1054, -0.9952, -0.4454, +0.3679, +0.5347, -0.4850, -0.1063, -0.0520, -0.6590, -0.0886, +0.2500, +0.3348, +0.4235, -0.0064, -0.5327, +0.4028, +0.1859, +0.3544, -0.0486, -0.0698, -0.1593],
-[ -1.4412, +0.3480, -0.3212, +0.5970, -0.1453, +0.2136, +0.0014, +0.3506, -0.0453, +0.6456, +0.1170, -0.1517, -0.6957, -0.5796, -0.1046, -1.8260, -0.5539, -0.3098, +0.4310, +0.1170, +0.2978, -0.1256, +0.3301, -0.4025, +0.1874, +0.1440, -1.0648, -0.6298, +0.7709, -0.2719, +0.0347, +0.0662, -0.3353, -0.0232, -0.6893, -0.7197, -0.7409, -0.4253, -0.0813, -0.0345, -0.3224, +0.0551, -0.2819, +0.6105, +0.7402, +0.0119, +0.7850, +0.3555, +0.3906, -1.0312, +0.8237, +0.4552, -0.0462, -0.0970, -0.1056, +0.1749, -0.2158, -0.0619, -0.6298, -0.3167, +0.1890, -0.4468, -0.2114, -0.5430, +0.5652, -0.0346, -1.1548, -0.9988, +0.2630, -0.1132, +0.0768, -0.4730, +0.4999, -0.6413, +0.2666, -0.2874, -0.3941, -1.4079, -0.0857, -0.0644, +0.2355, +0.2560, +0.3335, +0.1676, +0.8594, -0.3045, -0.0450, +0.5151, -0.1897, -0.4433, -0.5198, +0.6737, -0.0554, +0.7194, +0.6691, -0.1030, -0.0351, -1.1305, +0.1472, +0.3961, -1.1294, +0.9640, -0.4924, +0.8572, -1.0870, +0.4503, -0.0667, -0.4854, +0.0962, -0.7448, +0.5914, +0.1958, -0.3210, +0.1644, -0.1600, -0.9422, +0.6764, -0.2381, -0.5236, +0.2375, -0.7713, -0.4434, +0.2334, +0.4197, -0.1146, -0.0055, -0.2603, -0.3804],
-[ +0.2623, -0.6742, -0.1993, +0.0275, -0.7052, +1.2116, +0.4374, +0.3504, +0.0669, +0.3822, -1.2969, +0.0477, -0.6903, +0.2683, -0.5223, +0.5357, -0.2184, -0.8535, +0.4472, +0.4117, +0.3604, +0.1036, +0.2050, -0.4264, +0.4200, -0.3343, +0.5134, +1.2498, +0.1218, +0.1369, +0.2551, -0.0446, +0.4509, +0.2681, -0.7028, -0.8939, -0.7081, -0.0569, +0.0521, +0.1812, -0.2422, -0.2498, -0.0139, -0.0250, +0.3727, -0.3403, +0.0781, +0.2812, +0.2414, +0.1040, +0.4258, -0.0754, -0.8383, +0.2211, +0.9545, +0.6634, +0.3905, -0.4359, +0.6621, -0.6212, -0.3982, +0.2255, -0.7956, -0.7635, +0.2918, +1.6278, +0.4458, -1.2421, -0.1383, -0.4592, -0.4291, +0.1865, -0.1378, +0.5386, +0.2323, +0.3259, -0.7551, -0.2441, -0.3889, +0.2272, +0.3650, +0.2131, -0.1952, -0.1559, -0.5230, +1.2104, +0.3986, -0.5949, -0.0793, +0.4432, +0.0015, +0.3842, +0.5633, -0.1258, +0.8018, -1.1682, +0.0577, +0.1036, +0.0183, -0.1660, +0.4307, +0.1333, +0.0457, -0.0437, -0.3825, -0.4111, +0.2496, -0.6148, +0.2306, +0.5412, +0.0872, -0.1177, +0.7272, -0.2590, -0.1273, -0.7244, +0.7958, +1.0682, +0.5466, -0.7884, -0.7472, +0.1050, -0.2250, +0.7092, -1.3658, -0.2327, -0.5164, -0.3347],
-[ +0.0670, -0.4421, -0.5694, -0.4707, -0.9203, -0.4047, -0.0758, -0.6018, -0.6317, -0.0900, -0.0324, +0.4617, -0.2859, -0.0074, +0.7860, +0.2602, -0.3227, +0.3328, -0.0283, -0.6414, -0.1264, -0.4208, -0.0717, -0.2500, -0.0784, -0.5563, -0.1367, +0.1234, +0.3769, +0.6718, -1.4338, +0.1205, -0.6455, -0.2822, +0.6247, +0.0618, +0.1601, -0.7068, +0.1693, -0.0656, +0.3369, +0.2978, +0.1564, -0.1118, -0.3255, -0.4726, -0.0552, +0.2177, +0.0255, +0.2419, -0.3677, +0.0286, -0.1124, -0.5604, -0.2697, +0.5502, +0.5108, +0.0349, +0.1436, +0.2292, +0.3306, -0.0245, -0.2355, +0.2159, +0.3446, +0.0141, -0.4833, -0.6281, -0.5473, -0.1541, -0.1232, -0.0373, +0.4579, -0.1223, -0.1132, -0.3418, -0.0561, -0.1323, -0.0822, +0.1775, -0.0449, +0.5586, +0.4806, +0.1008, -0.4178, -0.5695, +0.2924, +0.0781, -0.0481, +0.0942, +0.2641, -0.1128, +0.1335, +0.3462, -0.2098, -0.6517, +0.2445, +0.1972, +0.3612, -0.0474, -0.6685, -0.3003, +0.1448, +0.3570, +0.1684, -0.0083, -0.6673, +0.2043, +0.0841, -0.5859, -0.4732, +0.1798, +0.0359, -0.8334, +0.2058, -0.2315, -0.5527, -0.5864, +0.1296, +0.2766, +0.3950, -0.2198, -1.2566, +0.0344, -0.0694, +0.1057, +0.0886, -0.0006],
-[ +0.2355, +0.2205, -1.3483, -0.1172, -0.3691, +0.2932, +0.4926, +0.1500, -0.0933, -0.5618, +0.2887, +0.4631, +0.1941, +1.0716, +0.5216, +0.5525, +0.1567, +0.6672, +0.9191, +0.7987, -0.6611, +0.2176, +0.2716, +0.4893, +1.4128, +0.9177, -0.6401, -0.7346, +1.3439, +0.2595, +0.0790, -0.4804, -0.2838, +0.0088, -0.3967, -0.4801, +0.1584, -0.2085, -0.0461, -0.5256, -0.9473, +1.8738, +0.8888, +0.7417, -0.4364, +0.4092, +0.4347, +0.6090, -1.3517, +0.8034, -0.9465, -0.3539, +0.5229, -0.8088, -0.5375, +0.3207, -0.1078, -0.1502, -0.1826, -0.6835, +0.1005, +0.9818, -0.0366, -0.0235, +1.3464, -1.0394, +0.3553, -0.3647, -1.1125, +0.1898, +0.1982, +1.4814, -0.1280, +0.9472, -0.2057, -1.0033, +0.2990, +0.4505, -1.6867, +0.0372, -1.2470, +1.1743, -0.7300, -1.4268, -0.4928, -0.2131, -0.0731, +0.5726, +1.0094, +0.1827, -0.0374, -0.2762, +1.1445, +0.1382, +0.6379, -0.5874, +0.7924, -0.4141, +0.2994, -0.3265, +0.8631, +0.0625, -0.5708, +0.3840, -0.1690, -0.2459, -1.0880, +0.3760, -0.6786, -0.8060, -0.1018, +0.5281, -0.4578, +0.1397, -0.0314, -0.0962, +0.0207, +0.6683, -0.5995, +0.4266, +0.2856, +0.4398, +0.4314, +0.4667, -0.1604, -0.0962, +0.4738, +0.3703],
-[ +0.0467, +0.4707, +0.3331, +0.1481, +0.0379, +0.1480, +0.1593, -0.0646, -0.1355, -0.0840, +0.1212, +0.4008, -0.3111, -0.2571, +0.1511, +0.3338, +0.2279, -0.4840, -1.0219, +0.5547, -0.5126, +0.0801, +0.2081, -0.0607, +0.0969, +0.2595, +0.2859, +0.2738, +0.1785, +0.0969, -0.1021, -0.2732, +0.0357, -0.2654, -0.3296, -0.3804, -0.1135, -0.2353, +0.5887, +0.5972, -0.5222, -0.1587, -0.2610, -0.2225, -0.4598, -0.2176, +0.2049, -0.1485, -0.0299, +0.1484, +0.1950, +0.5583, +0.5110, +0.1370, -0.0910, +0.0798, -0.1201, -0.0193, -0.2943, +0.0764, -0.3307, +0.2936, +0.2535, -0.3703, +0.0249, -0.0005, -0.1424, -0.3010, -0.0445, -0.3506, +0.3826, +0.0547, -0.3623, -0.2543, -0.2261, +0.0637, +0.2958, +0.3432, -0.1460, -0.0548, -0.0379, -0.3288, -0.1262, +0.1693, -0.9188, -0.4361, +0.2599, +0.4048, -0.0817, +0.1643, -0.4248, +0.2501, -0.1260, +0.1860, +0.0839, +0.1641, -0.0727, +0.1643, -0.2693, -0.1530, +0.3114, -0.6813, -0.2417, +0.0138, -0.6074, -0.4009, +0.1408, -0.3276, -0.2314, -0.1093, +0.1874, +0.1717, +0.0237, +0.0482, -0.0837, -0.0706, +0.2035, -0.0895, -0.0915, -0.2132, +0.1071, +0.2370, -0.1392, +0.4087, +0.0054, -0.0605, +0.5010, -0.3720],
-[ -0.6041, +0.3315, +0.4344, -0.0530, -0.0750, -0.6740, +0.5459, +0.0864, -0.4466, -0.3376, -0.3102, -0.0338, +0.2650, +0.5327, +0.0622, -0.7640, +0.0327, +0.1950, -0.1494, -0.6298, -0.0713, +0.0398, +0.0742, -0.9150, -0.0288, +0.1934, -0.6378, +0.0861, +0.1895, +0.2527, -1.2174, +0.2087, -0.0830, -0.1214, +0.1712, -0.0216, +0.2538, +0.1952, +0.3798, -0.3429, +0.1725, +0.3499, +0.3408, +0.4805, +0.4361, +0.0572, +0.0162, -0.2105, -0.0226, +0.1329, -0.4117, -0.4411, +0.0208, -0.3427, +0.1636, -0.4633, +0.2159, +0.0833, -0.2476, -0.0152, -0.0169, +0.2707, +0.4725, +0.4281, +0.1138, -0.2027, -0.1338, +0.0103, -0.1651, -0.1051, -0.0860, +0.1426, -0.1318, -0.1000, -0.3799, -0.1731, +0.0442, -1.0749, +0.2806, -0.0405, -0.6049, +0.4326, +0.3027, +0.2951, +0.2068, -1.1063, +0.1727, +0.0808, +0.3021, +0.2196, +0.2176, -0.0847, -0.6010, +0.1784, -0.0912, -0.6264, +0.1444, +0.0617, +0.2282, -0.2726, +0.1764, +0.1803, +0.3600, -0.3617, -0.1991, -0.3087, +0.3560, -0.5956, -0.0958, +0.1788, +0.2348, -0.1670, -0.2103, -0.1210, +0.2132, -0.1198, +0.0154, +0.2332, +0.2034, -0.5947, -0.0082, -0.1029, +0.4438, -0.6764, +0.1075, +0.0251, -0.5663, -0.4196]
-])
-weights_dense1_b = np.array([ +0.0945, +0.0221, +0.0891, +0.0491, +0.0117, -0.0476, -0.0928, -0.1916, -0.0470, +0.2310, +0.0341, +0.0667, -0.0911, +0.1326, -0.1565, -0.1634, -0.0695, -0.0235, -0.2292, -0.1396, -0.2046, +0.0967, -0.0569, +0.0423, -0.0863, +0.0138, -0.2055, -0.1253, -0.1153, -0.2407, +0.1039, -0.2110, -0.0743, -0.0020, +0.0149, -0.2198, +0.0150, -0.2298, -0.1317, +0.0990, -0.0897, +0.0430, -0.0985, +0.0082, -0.2348, -0.0832, -0.1534, -0.1548, -0.2317, +0.0414, -0.0891, -0.2233, -0.0865, -0.0298, -0.1339, +0.0339, +0.1492, -0.1300, -0.4555, -0.0238, +0.0225, -0.1978, +0.0416, -0.0089, -0.0476, +0.0720, -0.1214, +0.1386, +0.1151, -0.1887, -0.1368, -0.1987, -0.0415, +0.0236, -0.2552, -0.1052, -0.0978, +0.0162, -0.0876, +0.0537, -0.1436, -0.2076, -0.0873, -0.1789, -0.0524, -0.1163, -0.0832, -0.1528, -0.0416, -0.1003, -0.0970, -0.1769, -0.1527, -0.0028, +0.1150, +0.0467, -0.0537, -0.2437, -0.1143, -0.1589, +0.1136, +0.0611, -0.1218, +0.0358, +0.1195, -0.1023, +0.0665, -0.0816, -0.1308, -0.1215, +0.0528, -0.0858, +0.1087, -0.0314, -0.2404, +0.0233, -0.0644, -0.1083, -0.0198, -0.0531, -0.0808, -0.0256, +0.0324, -0.0287, -0.0536, -0.1525, +0.0821, +0.1315])
+# yapf: disable
+weights_dense1_w = np.array(
+ [[
+ -0.5923, +0.0708, -0.2868, -0.5138, -0.1376, +0.3921, +0.3474, +0.2376,
+ +0.6664, +0.1282, +0.1778, +0.2879, -0.3030, +0.1678, +0.1248, +0.1665,
+ -0.1129, -0.5741, +0.1318, +0.4056, +0.2123, +0.1856, +0.3895, +0.0076,
+ +0.4030, +0.1592, +0.2418, +0.0302, -0.2642, -0.0772, -0.5000, -0.0241,
+ +0.3221, +0.1268, -0.1013, +0.1987, +0.2850, -0.3257, -0.1115, -0.3003,
+ +0.0450, -0.2232, -0.1471, +0.5303, +0.6448, +0.0623, +0.4801, +0.1554,
+ -0.0681, -0.4085, +0.6602, +0.1064, +0.1389, +0.6386, +0.5123, -0.3210,
+ -0.0565, +0.2629, +0.5662, -0.2477, -0.1244, +0.0125, +0.1585, +0.0328,
+ +0.0098, +0.0898, +0.4162, -0.0758, -0.4449, +0.4196, +0.0923, +0.4323,
+ -0.2452, -0.1646, +0.8115, +0.3922, +0.2736, -0.2587, +0.6535, +0.1253,
+ +0.0194, +0.3765, +0.2678, +0.4038, -0.1404, -0.2698, +0.1081, +0.0031,
+ +0.4622, -0.1806, -0.2798, -0.2216, +0.2180, -0.0131, -0.3375, +0.2901,
+ +0.2382, -0.0402, +0.4257, -0.2084, -0.1102, +0.6300, +0.0378, +0.5702,
+ +0.0085, -0.4068, +0.5516, +0.1101, +0.4330, +0.0053, +0.0656, +0.6463,
+ +0.2717, -0.5689, -0.2151, +0.1876, +0.6149, +0.1463, +0.2377, +0.4734,
+ -0.5056, +0.5846, +0.1847, +0.4174, -0.0182, -0.0434, +0.4932, +0.1675
+ ],
+ [
+ -0.0323, +0.1990, +0.0035, +0.1374, -0.0162, +0.1237, -0.2231,
+ +0.3492, -0.0100, +0.1316, -0.4408, -0.3253, +0.0478, +0.1452,
+ +0.1131, +0.0822, +0.3286, +0.0443, -0.1344, -0.0785, -0.4665,
+ -0.1749, -0.2719, +0.1309, +0.2622, -0.1787, +0.0132, +0.0169,
+ +0.1424, -0.1192, -0.0486, +0.0994, +0.2762, -0.2210, -0.3417,
+ -0.0453, +0.2207, +0.1077, -0.2448, +0.1683, +0.0924, +0.1232,
+ -0.1016, +0.2795, +0.3878, -0.3440, -0.0133, -0.1766, -0.2442,
+ -0.3664, +0.1455, -0.1039, -0.0158, +0.1746, -0.3620, -0.1886,
+ +0.4197, -0.1972, -0.0783, -0.2513, +0.1576, -0.0283, +0.4125,
+ -0.0183, +0.2840, -0.0190, -0.2548, -0.0755, +0.2639, +0.1207,
+ -0.0633, -0.2397, +0.2823, -0.1291, +0.1105, -0.3745, -0.0536,
+ -0.1834, +0.3941, -0.0746, -0.0950, +0.1063, -0.0520, -0.1393,
+ +0.1153, -0.1724, -0.3873, +0.2700, -0.2059, -0.1402, -0.0576,
+ -0.2060, -0.1197, +0.1246, +0.1575, -0.0923, -0.1524, -0.1861,
+ +0.3553, -0.3640, +0.1487, +0.0001, -0.0485, -0.1573, +0.0710,
+ -0.0659, -0.1262, -0.2399, +0.0415, -0.1848, -0.0352, -0.2980,
+ +0.4015, -0.2548, +0.0777, -0.0573, -0.2989, +0.2988, -0.2647,
+ -0.0445, +0.0962, +0.1144, -0.1381, -0.1443, +0.2538, -0.0203,
+ -0.1139, -0.0137
+ ],
+ [
+ +0.0101, -0.1099, -0.2746, +0.1418, -0.2257, -0.0753, -0.0880,
+ -0.5336, -0.3857, +0.4742, +0.0142, -0.0733, -0.2721, +0.1913,
+ -0.4624, -0.0272, -0.0448, -0.1782, -0.0153, -0.1250, +0.0004,
+ -0.1004, +0.1810, -0.1565, +0.1465, +0.2069, +0.2239, -0.2894,
+ -0.2431, +0.1741, +0.0018, -0.0586, +0.1388, +0.1907, +0.0643,
+ +0.0112, +0.0272, +0.1716, -0.2055, +0.1644, -0.1780, -0.4091,
+ -0.4636, -0.1947, -0.1812, -0.1876, -0.3228, -0.2501, -0.3992,
+ -0.2498, -0.1115, -0.4160, -0.2285, -0.1908, -0.3892, -0.0788,
+ +0.2413, +0.0193, -0.3308, -0.0670, +0.2808, -0.3637, +0.0275,
+ -0.2128, -0.0328, +0.4001, +0.3251, +0.4071, +0.2900, +0.1178,
+ -0.4016, -0.2668, +0.0388, -0.2220, -0.3311, +0.0219, -0.0518,
+ +0.0345, +0.2008, +0.2282, -0.0269, -0.2531, -0.5376, -0.5342,
+ -0.0932, -0.0678, -0.0573, -0.3451, +0.3746, -0.3500, +0.1244,
+ -0.3478, +0.1564, -0.4525, -0.0010, +0.0473, +0.1666, -0.0538,
+ -0.2431, +0.2113, +0.0891, +0.2253, -0.2024, +0.0722, -0.0958,
+ -0.0994, -0.1086, +0.1991, -0.2600, +0.1181, -0.1903, +0.1795,
+ -0.0618, +0.0945, -0.2850, +0.0669, +0.1276, -0.2620, -0.4172,
+ +0.2954, -0.4614, +0.0665, -0.0353, -0.0430, -0.0465, +0.3755,
+ -0.1195, +0.2084
+ ],
+ [
+ +0.0486, -0.0247, +0.1675, +0.3216, -0.2398, +0.2336, -0.1924,
+ -0.7100, +0.4238, -0.2251, -0.1045, -0.0824, -0.1782, +0.0657,
+ -0.3393, -0.0225, -0.0442, -0.1090, +0.2088, +0.0038, -0.0173,
+ -0.1676, +0.5690, -0.0158, -0.4489, -0.0216, +0.2328, +0.2235,
+ +0.0548, +0.5565, -0.0349, -0.2223, +0.3198, +0.0895, -0.2805,
+ -0.3474, -0.3506, -0.1487, -0.1241, +0.1920, +0.2093, +0.0074,
+ -0.3248, -0.0891, -0.3713, -0.0435, -0.1554, +0.4472, +0.7299,
+ -0.0282, -0.0727, +0.2084, -0.6375, +0.1005, -0.1439, +0.4170,
+ +0.2134, -0.0393, -0.1067, -0.0428, +0.0359, -0.5413, -0.1321,
+ -0.4210, +0.5401, +0.1721, -0.0240, -0.2389, -0.0596, -0.2618,
+ +0.0683, +0.0520, +0.2830, -0.0237, +0.7084, +0.0032, +0.6990,
+ +0.0166, -0.1442, +0.5299, -0.1867, -0.2291, -0.1312, +0.0618,
+ -0.2247, -0.2138, +0.5049, +0.1986, -0.0194, +0.1705, +0.0661,
+ +0.3354, -0.5126, +0.1879, +0.1266, +0.1527, -0.1481, +0.0534,
+ +0.4824, +0.2081, +0.2159, +0.1490, -0.0946, -0.3135, +0.0068,
+ +0.2763, -0.3787, +0.5304, +0.2405, -0.2065, -0.3856, -0.3421,
+ -0.0920, -0.2431, +0.1800, -0.1242, -0.2831, -0.4493, -0.5491,
+ +0.0137, +0.3891, -0.1039, -0.2604, -0.5305, -0.4397, +0.2243,
+ +0.3320, -0.5214
+ ],
+ [
+ +0.2827, -0.0681, -0.0571, +0.1937, +0.0216, -0.0113, -0.0919,
+ +0.0923, +0.1170, -0.1119, +0.0732, +0.3078, -0.5637, +0.1494,
+ -0.1741, -0.1985, -0.0968, +0.1848, -0.2082, +0.1764, +0.2342,
+ +0.1448, +0.0192, -0.2817, -0.1275, -0.0167, +0.0631, +0.1762,
+ -0.2762, +0.1179, -0.0295, +0.1779, +0.0460, -0.3562, +0.0457,
+ +0.1098, +0.2099, +0.1457, +0.0766, -0.2229, +0.1076, +0.1364,
+ -0.0568, +0.2080, +0.2249, +0.1715, +0.1573, -0.0279, +0.2404,
+ -0.1265, +0.0210, +0.4009, +0.2633, -0.1419, -0.3217, -0.0988,
+ +0.2678, -0.0627, -0.1092, -0.4646, -0.2602, -0.0886, -0.1043,
+ +0.3363, -0.1775, +0.0361, -0.2431, -0.2028, +0.0805, -0.1340,
+ -0.1488, +0.2928, +0.0214, +0.3602, +0.0467, +0.1229, +0.2465,
+ -0.1079, -0.1829, -0.1387, -0.2267, +0.1946, -0.2169, +0.3601,
+ +0.3059, +0.0612, +0.2089, -0.1133, -0.0262, -0.0988, +0.2344,
+ +0.2919, -0.2250, +0.0829, -0.2239, +0.0054, +0.1842, -0.4559,
+ -0.2440, -0.0654, +0.1422, -0.2005, -0.0992, +0.0436, -0.3750,
+ -0.4290, +0.2150, -0.2206, +0.3941, -0.2326, -0.2311, +0.0832,
+ +0.1774, -0.0006, +0.0894, -0.2395, +0.1252, -0.2813, +0.2075,
+ -0.0058, +0.3007, -0.0255, -0.1857, +0.4371, +0.1055, +0.1396,
+ +0.0276, -0.3052
+ ],
+ [
+ -0.3549, +0.0244, +0.0128, -0.3312, -0.2543, +0.3405, +0.1028,
+ -0.3751, +0.4624, +0.0440, +0.0182, +0.2063, -0.2831, -0.2593,
+ +0.3181, +0.3479, -0.2162, -0.5026, -0.1913, +0.2037, -0.5378,
+ +0.0117, -0.1922, -0.2390, +0.3209, -0.1556, +0.5278, -0.1576,
+ -0.4052, -0.5298, -0.3115, -0.3645, -0.0674, +0.5300, +0.1836,
+ +0.6099, +0.1260, -0.3193, -0.2892, +0.1283, -0.5849, -0.0597,
+ +0.4373, -0.4667, -0.0563, +0.0303, -0.2873, -0.6184, -0.3731,
+ +0.0120, -0.0374, -0.1511, +0.0177, +0.7742, +0.6095, -0.8566,
+ +0.1299, -0.7749, +0.2235, -0.4156, +0.3176, +0.3276, -0.3272,
+ -0.0117, +0.3580, +0.0025, +0.3159, +0.3943, +0.1240, -0.5251,
+ -0.3494, -0.0956, -0.2783, -0.3312, +0.1153, +0.3601, -0.1687,
+ -0.0901, -0.2105, -0.1598, -0.0696, -0.4319, +0.5911, +0.1031,
+ -0.4128, -0.3107, -0.4399, +0.0569, +0.0503, -0.8104, +0.1960,
+ -0.3432, +0.1123, -0.0527, +0.3002, -0.2125, -0.1912, -0.2889,
+ -0.1487, -0.1293, +0.2371, -0.1723, +0.6543, +0.5766, +0.3827,
+ -0.0465, +0.3146, -0.6999, +0.1115, +0.0831, -0.4371, -0.1094,
+ -0.0659, +0.1174, -0.3606, +0.2013, +0.4883, -0.3268, +0.2838,
+ +0.3358, -0.3129, +0.0897, +0.1626, -0.1402, +0.4700, -0.3773,
+ +0.3199, +0.0778
+ ],
+ [
+ -0.0380, -0.0186, -0.0973, -0.0650, -0.0797, -0.0571, -0.2562,
+ +0.3550, +0.0175, -0.2976, +0.1348, -0.1437, -0.2194, -0.0865,
+ -0.1383, +0.1785, +0.2052, +0.1327, +0.3076, -0.0208, -0.5012,
+ -0.3738, -0.0742, +0.0206, -0.0261, -0.0753, -0.0365, +0.2353,
+ +0.2044, +0.1071, -0.1511, +0.1991, +0.1419, +0.2457, +0.2332,
+ +0.2887, +0.0175, -0.0174, -0.3288, +0.0172, -0.2783, +0.1705,
+ +0.0900, -0.1581, +0.0823, +0.1243, +0.0309, +0.1373, -0.1223,
+ +0.0086, +0.3729, +0.0423, +0.2373, +0.4041, -0.2373, +0.3242,
+ -0.3292, +0.2857, -0.1908, -0.1969, +0.4179, +0.0252, -0.0239,
+ -0.3202, -0.2150, +0.0059, +0.1508, +0.3510, -0.2508, +0.2974,
+ -0.3275, +0.1462, -0.3206, -0.3074, -0.1402, +0.3046, -0.1896,
+ -0.1409, -0.1032, -0.2205, +0.0122, +0.0114, +0.0079, +0.0923,
+ -0.0840, +0.1730, -0.1152, +0.3725, -0.1648, +0.0536, -0.1832,
+ +0.0221, -0.0002, +0.1058, +0.0079, +0.0545, -0.4014, -0.0045,
+ -0.0859, +0.1899, -0.1464, +0.0611, +0.1560, +0.2330, -0.0436,
+ -0.0437, -0.0359, -0.1468, +0.4266, -0.4483, +0.1607, -0.0640,
+ +0.3039, +0.1245, +0.0614, -0.0151, +0.1026, +0.4184, -0.3741,
+ -0.1652, -0.1884, +0.0648, +0.0267, -0.0217, +0.1279, -0.1109,
+ +0.2459, -0.1909
+ ],
+ [
+ +0.4641, -0.2639, +0.1744, +0.4878, -0.2263, -0.0335, +0.5683,
+ +0.0308, +0.3132, +0.0384, -0.0191, +0.6840, +0.7869, +0.7729,
+ -0.2036, +0.1718, -0.5897, -0.1966, -0.0254, +0.1200, +0.6171,
+ -0.6490, +0.3407, +0.4501, -0.0544, -0.0178, +0.4335, +0.5922,
+ +0.4188, +0.1670, -0.2214, -0.1771, +0.0564, -0.0337, -0.1317,
+ -0.0320, +0.4909, -0.6020, +0.5674, +0.7039, -0.4565, +0.5487,
+ -0.3368, +0.4934, -0.1279, -0.5785, -0.6351, -0.9523, +0.5945,
+ +0.1008, -0.2629, -0.1561, +0.0582, -0.3995, -0.0903, +0.6003,
+ +0.2845, -0.2892, -0.3994, +0.2377, +0.8273, -0.6761, +0.7568,
+ -0.4131, +0.4980, +0.2917, +0.1099, +0.1988, -0.3377, -0.5839,
+ -0.4254, -0.1366, +0.7022, +0.2762, -0.0126, -0.6649, +0.3256,
+ +0.4342, +0.1040, +0.9052, +0.4308, -0.2127, +0.4446, +0.0384,
+ +0.2398, -0.2750, +0.7937, +0.0828, -0.3238, -0.1872, -0.0145,
+ +0.0556, +0.1063, -0.3786, +0.6058, -0.0708, +0.3147, +0.2582,
+ +0.3061, -0.0249, +0.3195, +0.6195, +0.8043, +0.1070, +0.0869,
+ +0.0387, +0.3916, +0.6197, -0.1543, +0.0553, +0.6231, -0.4391,
+ +0.0212, +0.0637, -0.5223, +0.2129, -0.3591, -0.1149, +0.7172,
+ +0.1986, -0.1989, -0.0314, +0.6212, -0.0091, -0.7394, -0.5792,
+ +0.3289, -0.9215
+ ],
+ [
+ -0.4254, -0.1010, -0.2326, +0.0115, -0.2136, +0.0043, -0.2096,
+ -0.1871, -0.3127, +0.3810, +0.2582, +0.0857, -0.0747, -0.0162,
+ +0.3173, -0.3385, -0.6953, -0.1816, -0.0029, -0.5805, -0.4907,
+ -0.2431, -0.0356, +0.0890, -0.4312, -0.3004, -0.2911, -0.0044,
+ -0.1303, -0.4609, +0.4219, -0.8413, +0.3006, -0.0198, +0.0991,
+ +0.1724, -0.6699, -0.5464, -0.2279, +0.1663, -0.5687, -0.0257,
+ -0.4929, +0.3131, -0.2199, +0.6044, +0.3898, -0.9848, +0.3623,
+ -0.0672, -0.3914, -0.0168, +0.4831, +0.1769, +0.4379, -0.3998,
+ -0.5295, +0.4740, +0.0720, -0.2860, -0.2657, -0.2048, -0.6462,
+ -0.1063, -0.3977, -0.0696, +0.3865, +0.1880, -0.2615, -0.1497,
+ -0.2452, +0.6668, +0.3959, +0.1580, -0.0861, +0.0015, -0.4241,
+ -0.8260, -0.2909, -0.2317, +0.2107, +0.0659, -0.1037, -0.4058,
+ +0.0144, +0.0817, -0.5299, +0.0591, -0.1258, -0.5378, -0.9845,
+ +0.4663, +0.1014, -0.8416, -0.4150, +0.0328, +0.1150, -0.3711,
+ -0.2761, +0.2032, -0.2557, -0.1680, +0.3407, +0.1772, -0.2910,
+ +0.5103, +0.4964, +0.0582, +0.3356, +0.5211, +0.3697, +0.3797,
+ -0.1063, -0.1224, -0.7502, +0.0040, -1.0549, -0.4150, +0.5061,
+ -0.0295, -0.2924, +0.5322, +0.5314, +0.0182, -0.5597, +0.1434,
+ +0.3410, +0.3369
+ ],
+ [
+ +0.3056, +0.0843, +0.0543, -0.4615, -0.4151, -0.0575, -0.8068,
+ -0.2107, +0.8528, +0.1961, +0.2841, -0.2850, -0.0830, -0.2409,
+ +0.0112, +0.0230, +0.0239, +0.5198, +0.4115, +0.0110, -0.0818,
+ +0.4822, +0.3047, -0.1824, +0.3432, +0.0778, +0.0768, +0.0894,
+ +0.2638, -0.3116, -0.1630, -0.5821, -0.0214, -0.0087, +0.3884,
+ +0.1033, -0.2790, -0.1378, -0.2609, -0.2486, +0.1585, -0.4514,
+ -0.2467, -0.4613, -0.1185, +0.5398, -0.0848, +0.1043, -0.1359,
+ -0.0675, -0.3464, +0.2428, -0.2526, +0.2612, +0.4603, +0.0659,
+ -0.3555, +0.3165, +0.0506, -0.0040, -0.4325, -0.0251, -0.1762,
+ +0.6595, -0.2948, -0.3917, +0.1515, +0.0745, -0.2204, -0.0646,
+ +0.4103, +0.3584, +0.4389, +0.2079, +0.0346, +0.1363, -0.7773,
+ +0.2108, -0.2785, -0.4362, -0.7424, +0.3171, +0.3104, +0.0360,
+ -0.0472, -0.0106, -0.0949, +0.3420, +0.4692, +0.3801, -0.6458,
+ +0.0883, +0.1774, -0.4107, -0.5429, -0.0189, -0.4815, +0.0808,
+ -0.4501, +0.0710, +0.0171, -0.2874, -0.1613, -0.0986, +0.4779,
+ -0.0379, -0.0432, -0.1339, +0.2031, -0.1244, -0.4811, +0.0729,
+ +0.2716, +0.2948, -0.4478, -0.1647, +0.3046, +0.0196, -0.3698,
+ -0.2645, +0.0715, +0.1403, +0.0169, -0.1153, -0.2641, -0.0276,
+ +0.1861, +0.3948
+ ],
+ [
+ +0.2767, -0.0743, +0.2740, -0.4792, -0.7306, +0.0418, -0.1570,
+ +0.4153, +0.0627, +0.4058, +0.4510, +0.3410, +0.0399, -1.0956,
+ -0.5747, -0.1151, +0.2627, -0.1982, -0.1019, +0.7238, -0.0384,
+ +0.3866, +0.3792, +0.2662, +0.2362, +0.1112, +0.2728, -0.2878,
+ -0.0650, -0.0905, +0.3320, +0.3422, +0.7680, +0.4203, +0.4889,
+ -0.3364, +0.1576, +0.2025, -1.0459, +0.1940, -0.5367, +0.4368,
+ -0.1559, -0.0261, +0.0649, +0.6833, +0.0792, -0.1099, -0.9185,
+ -0.5792, +0.2715, -0.5116, -0.8132, +0.5739, -0.4300, +0.2802,
+ -0.0944, -0.8149, -0.2920, -0.8222, +0.1704, +0.0467, +0.0717,
+ -0.0861, -1.1820, -0.0288, -1.2486, +0.2247, +0.4574, -0.3306,
+ -0.2873, +0.1044, -0.0061, -0.6058, +0.7101, +1.0664, +0.0885,
+ +0.2544, +0.2762, +0.9233, -0.4762, -0.1358, -0.4847, +0.3625,
+ +0.2238, +0.5404, +0.4796, -0.4765, -0.0754, +0.0130, +0.0350,
+ +0.8824, +0.6476, +0.2358, -0.0104, +0.6710, -1.3786, +0.1219,
+ +0.8695, -0.9081, +0.5234, -0.7513, -0.4966, +1.2130, -0.8264,
+ +0.8768, +0.1144, +0.0391, +0.0208, -0.4296, -0.2219, +0.5561,
+ +0.0160, -0.7934, +0.0037, -0.1454, +0.7168, -0.0297, -0.2560,
+ +0.3648, -0.6412, -0.7076, +0.3461, +0.0958, +0.2879, +0.2225,
+ +0.4269, -0.2274
+ ],
+ [
+ -1.2371, +0.7142, +1.0170, -0.2385, +0.4375, +0.6428, +0.7528,
+ -0.1837, +0.3177, +1.5337, +0.8810, +1.0799, +0.7406, -0.6905,
+ -0.1914, -0.2182, +0.9355, +0.3845, +0.0422, -0.6012, +0.7606,
+ -0.6731, +0.7571, -0.2129, -0.3527, +0.4415, -1.1536, -1.0436,
+ -0.6994, +0.1156, +0.1110, -0.4602, +1.2682, -0.0122, -0.2747,
+ -0.5565, +1.1461, +0.2052, -0.4670, +0.1062, +0.1336, +0.4687,
+ -0.3789, -0.5272, +0.5302, -0.0505, -0.8930, +0.3562, +0.1406,
+ +0.1925, +0.0953, -1.0493, -0.2918, +0.9845, -0.0997, -0.1381,
+ -0.0345, +0.3173, +0.0242, -0.8146, +0.8637, +0.6093, +0.7513,
+ +0.3913, +0.2520, +0.3459, +0.4740, -0.8409, -0.0319, -0.2245,
+ -1.3980, +0.5117, +0.5224, -0.9587, +0.2602, -0.3061, -0.0077,
+ +0.1915, -0.0583, +0.8455, -0.2225, +0.1052, +1.1755, +0.3301,
+ -1.3673, +0.1438, +0.3685, -1.0758, +1.0890, -0.2946, +0.3831,
+ +0.4291, -0.5933, +0.1440, +0.2730, +0.5047, -1.4292, +0.4666,
+ -0.0684, -1.0907, +0.3267, -0.3991, +0.8139, +0.6090, +0.1770,
+ +0.7682, -0.2264, +0.0630, -0.3205, -0.4079, -0.2719, +0.0128,
+ -0.8448, -1.2259, -1.2494, -0.1504, +0.2575, -0.8282, +0.4063,
+ +1.1256, +0.1730, -0.8418, +0.6516, -0.5008, -0.0957, +0.3784,
+ -0.7828, -0.2556
+ ],
+ [
+ +0.4096, -0.4381, +0.0800, +0.4671, +0.2710, +0.3707, +0.1151,
+ +0.0230, -0.1066, -0.6900, -0.1603, -0.3079, -0.0686, -0.6147,
+ -0.3030, -0.1793, -0.7013, +0.1995, +0.2661, +0.2716, -0.0216,
+ -0.7503, -0.5498, -0.1302, -0.3296, +0.3840, +0.0224, -0.1708,
+ -0.1937, -0.2009, -0.5012, -0.4132, -0.1342, +0.2941, -0.3885,
+ +0.0947, +0.0590, +0.1700, -0.4708, -0.1097, -0.0097, +0.3135,
+ +0.2190, -0.6015, +0.0922, -0.0361, -0.3555, +0.0014, +0.2416,
+ +0.7169, +0.0544, +0.0161, -0.4381, -0.0826, -0.2879, -0.2404,
+ -0.3624, -0.3565, -0.0936, +0.1039, +0.0661, -0.2627, +0.1202,
+ -0.3224, -0.5876, -0.3586, +0.1150, -0.3245, +0.3580, +0.0222,
+ +0.3645, -0.1235, -0.1768, +0.1465, -1.0948, +0.0147, +0.3538,
+ +0.2351, -0.3125, +0.3397, +0.3092, -0.1426, +0.1506, +0.1900,
+ +0.0469, +0.0054, +0.3150, -0.0771, -0.6345, -0.3055, +0.4514,
+ +0.1163, -0.2015, +0.2673, +0.6658, -0.0627, -0.4941, -0.0477,
+ +0.1703, +0.0382, -0.1618, +0.6503, -0.4697, -0.3565, -0.6726,
+ +0.1886, -0.3776, -0.1012, -0.3556, +0.1710, +0.1496, -0.3936,
+ -0.0074, +0.4109, +0.1207, +0.6998, +0.3481, +0.2814, +0.1733,
+ -0.0011, +0.1370, +0.2159, -0.1052, +0.3861, +0.1950, -0.7201,
+ -0.7551, -0.4230
+ ],
+ [
+ -0.3067, -0.4930, +0.0005, -0.2896, -0.1727, +0.7936, +0.7091,
+ -0.4756, -0.1008, -0.1327, +0.5747, +1.1786, -0.6373, -0.8808,
+ -0.7177, -0.2952, -0.0674, -0.1895, -1.5115, +0.0899, +0.1620,
+ +0.4005, -1.3567, -0.5376, -0.8410, +0.9262, -0.3323, -0.2384,
+ -0.1566, -0.5104, -1.0051, -0.2508, -0.5976, -1.7098, -0.2825,
+ +0.3746, -0.2511, +0.2700, -0.8215, -0.4912, +0.3659, -0.0335,
+ -0.5009, +0.3888, +0.1754, +0.0389, +0.5997, +0.5174, -0.2969,
+ -0.1951, -0.8337, -0.7546, +0.3798, -0.0360, +0.1299, +0.1715,
+ -0.1466, -0.2220, -0.5778, -0.4419, -0.2217, +0.2688, -0.7268,
+ +0.7278, +0.3627, -0.5958, +0.9821, -0.5816, +1.0788, +0.1393,
+ -0.1474, +0.0149, +0.2589, +0.3256, -0.8790, +0.4376, -0.0024,
+ -0.7049, -0.3868, -0.0158, +0.8335, +0.5016, -0.1198, +0.4702,
+ -0.7057, -0.0416, +0.4448, +0.7836, -0.4379, -0.9832, -0.4550,
+ -0.4196, +0.8538, -0.7044, -0.1322, -0.1303, +0.6359, -0.0804,
+ +1.0178, +1.3486, +1.1624, +0.0790, -1.1682, -0.6815, -0.3072,
+ -0.2573, -0.4431, +0.5407, -0.5736, +0.6607, +0.3793, -1.6072,
+ -1.2694, +0.7025, -0.3560, +0.4921, -0.4464, +0.1878, +0.2828,
+ -0.8566, -0.2740, +0.1552, -0.3026, +0.5256, -0.7969, -1.0224,
+ -1.4169, -0.4385
+ ],
+ [
+ -0.1259, -0.6170, +0.2135, -0.3418, -0.3997, -0.2842, -0.3138,
+ -0.3543, +0.2284, -0.5683, -0.6383, -0.2562, +0.2448, +0.0349,
+ -0.0070, +0.3173, +0.3845, +0.0760, -0.0011, +0.1687, -0.2101,
+ +0.2975, -0.1408, +0.4728, +0.3411, -0.8453, -0.1121, -0.0397,
+ -0.2378, -0.7145, +0.2055, +0.0822, -0.0557, -0.1722, -0.3179,
+ -0.1208, +0.2442, +0.1715, +0.1880, -0.1211, -0.0342, -0.0293,
+ +0.0311, -0.1830, -0.0408, -0.6688, -0.2091, -0.0040, -0.7909,
+ -0.5701, +0.5024, -0.3416, -0.5435, -0.3508, -0.1217, -0.2373,
+ +0.1755, -0.1108, +0.1743, -0.0851, +0.1787, +0.2393, -0.1975,
+ -0.0802, -0.2206, +0.0480, +0.1984, +0.3452, -0.5239, -0.5806,
+ -0.1068, -0.1596, -0.7319, +0.4167, +0.2523, -0.4128, +0.1135,
+ +0.0306, +0.1043, +0.0031, -0.0962, -0.4736, +0.1725, +0.4047,
+ +0.1519, -0.2261, -0.0665, -0.0859, -0.2420, +0.0381, +0.0051,
+ -0.9161, +0.2209, -0.6169, -0.1194, +0.2994, -0.0627, +0.0196,
+ -0.0753, -0.3026, -0.1814, -0.1946, +0.5229, -0.3275, +0.4493,
+ -2.3710, +0.5644, +0.3316, -0.1655, +0.2269, -0.7205, -0.7091,
+ +0.2792, -0.0576, -0.2398, +0.0926, -0.0381, +0.3547, +0.2970,
+ -0.6312, +0.2424, -0.1980, +0.4490, -0.3666, -0.4262, -1.0815,
+ +0.0510, +0.1120
+ ],
+ [
+ -0.1522, +0.7263, -0.2575, +0.6404, +0.6986, +0.2308, +0.6524,
+ -0.6431, +0.4774, +0.3122, -0.3521, +0.3393, +0.2929, -0.3382,
+ +0.2161, +0.1669, +0.4713, +0.3194, -0.1374, +0.1473, +0.0257,
+ +0.3532, -0.3252, +0.5917, -0.0704, -0.1053, -0.2127, +0.2276,
+ -0.0699, -0.2108, +0.4681, -0.3924, -0.0363, +0.4286, -0.1897,
+ -0.3929, -0.5962, -0.0255, -0.4458, -1.0351, -0.1633, +0.0820,
+ -0.9262, -0.3648, -0.1328, -0.8021, -0.2717, +0.1889, -0.0327,
+ +0.1726, +0.4866, -0.2176, -0.0771, +0.2216, -0.7842, -0.0576,
+ +0.0865, +0.0882, -0.1196, -0.1501, -0.3229, +0.1669, -0.4632,
+ -0.5473, -0.0691, +0.4595, +0.1466, -0.0135, +0.0910, -0.6819,
+ +0.0899, -0.2865, -0.2059, -0.1933, +0.4151, -0.7514, -0.1771,
+ -0.1813, +0.4952, -0.1999, +0.5819, +0.7551, +0.2075, +0.3148,
+ +0.2755, -0.0200, -0.1676, -0.3802, -0.4465, -0.2035, +0.4219,
+ +0.7001, -0.4227, -0.3968, -0.0350, +0.0262, -0.5200, -0.8271,
+ +0.6630, -0.1405, +0.3552, +0.1478, +0.4814, -0.6110, +0.4737,
+ -0.1415, +0.3233, +0.1054, -0.9952, -0.4454, +0.3679, +0.5347,
+ -0.4850, -0.1063, -0.0520, -0.6590, -0.0886, +0.2500, +0.3348,
+ +0.4235, -0.0064, -0.5327, +0.4028, +0.1859, +0.3544, -0.0486,
+ -0.0698, -0.1593
+ ],
+ [
+ -1.4412, +0.3480, -0.3212, +0.5970, -0.1453, +0.2136, +0.0014,
+ +0.3506, -0.0453, +0.6456, +0.1170, -0.1517, -0.6957, -0.5796,
+ -0.1046, -1.8260, -0.5539, -0.3098, +0.4310, +0.1170, +0.2978,
+ -0.1256, +0.3301, -0.4025, +0.1874, +0.1440, -1.0648, -0.6298,
+ +0.7709, -0.2719, +0.0347, +0.0662, -0.3353, -0.0232, -0.6893,
+ -0.7197, -0.7409, -0.4253, -0.0813, -0.0345, -0.3224, +0.0551,
+ -0.2819, +0.6105, +0.7402, +0.0119, +0.7850, +0.3555, +0.3906,
+ -1.0312, +0.8237, +0.4552, -0.0462, -0.0970, -0.1056, +0.1749,
+ -0.2158, -0.0619, -0.6298, -0.3167, +0.1890, -0.4468, -0.2114,
+ -0.5430, +0.5652, -0.0346, -1.1548, -0.9988, +0.2630, -0.1132,
+ +0.0768, -0.4730, +0.4999, -0.6413, +0.2666, -0.2874, -0.3941,
+ -1.4079, -0.0857, -0.0644, +0.2355, +0.2560, +0.3335, +0.1676,
+ +0.8594, -0.3045, -0.0450, +0.5151, -0.1897, -0.4433, -0.5198,
+ +0.6737, -0.0554, +0.7194, +0.6691, -0.1030, -0.0351, -1.1305,
+ +0.1472, +0.3961, -1.1294, +0.9640, -0.4924, +0.8572, -1.0870,
+ +0.4503, -0.0667, -0.4854, +0.0962, -0.7448, +0.5914, +0.1958,
+ -0.3210, +0.1644, -0.1600, -0.9422, +0.6764, -0.2381, -0.5236,
+ +0.2375, -0.7713, -0.4434, +0.2334, +0.4197, -0.1146, -0.0055,
+ -0.2603, -0.3804
+ ],
+ [
+ +0.2623, -0.6742, -0.1993, +0.0275, -0.7052, +1.2116, +0.4374,
+ +0.3504, +0.0669, +0.3822, -1.2969, +0.0477, -0.6903, +0.2683,
+ -0.5223, +0.5357, -0.2184, -0.8535, +0.4472, +0.4117, +0.3604,
+ +0.1036, +0.2050, -0.4264, +0.4200, -0.3343, +0.5134, +1.2498,
+ +0.1218, +0.1369, +0.2551, -0.0446, +0.4509, +0.2681, -0.7028,
+ -0.8939, -0.7081, -0.0569, +0.0521, +0.1812, -0.2422, -0.2498,
+ -0.0139, -0.0250, +0.3727, -0.3403, +0.0781, +0.2812, +0.2414,
+ +0.1040, +0.4258, -0.0754, -0.8383, +0.2211, +0.9545, +0.6634,
+ +0.3905, -0.4359, +0.6621, -0.6212, -0.3982, +0.2255, -0.7956,
+ -0.7635, +0.2918, +1.6278, +0.4458, -1.2421, -0.1383, -0.4592,
+ -0.4291, +0.1865, -0.1378, +0.5386, +0.2323, +0.3259, -0.7551,
+ -0.2441, -0.3889, +0.2272, +0.3650, +0.2131, -0.1952, -0.1559,
+ -0.5230, +1.2104, +0.3986, -0.5949, -0.0793, +0.4432, +0.0015,
+ +0.3842, +0.5633, -0.1258, +0.8018, -1.1682, +0.0577, +0.1036,
+ +0.0183, -0.1660, +0.4307, +0.1333, +0.0457, -0.0437, -0.3825,
+ -0.4111, +0.2496, -0.6148, +0.2306, +0.5412, +0.0872, -0.1177,
+ +0.7272, -0.2590, -0.1273, -0.7244, +0.7958, +1.0682, +0.5466,
+ -0.7884, -0.7472, +0.1050, -0.2250, +0.7092, -1.3658, -0.2327,
+ -0.5164, -0.3347
+ ],
+ [
+ +0.0670, -0.4421, -0.5694, -0.4707, -0.9203, -0.4047, -0.0758,
+ -0.6018, -0.6317, -0.0900, -0.0324, +0.4617, -0.2859, -0.0074,
+ +0.7860, +0.2602, -0.3227, +0.3328, -0.0283, -0.6414, -0.1264,
+ -0.4208, -0.0717, -0.2500, -0.0784, -0.5563, -0.1367, +0.1234,
+ +0.3769, +0.6718, -1.4338, +0.1205, -0.6455, -0.2822, +0.6247,
+ +0.0618, +0.1601, -0.7068, +0.1693, -0.0656, +0.3369, +0.2978,
+ +0.1564, -0.1118, -0.3255, -0.4726, -0.0552, +0.2177, +0.0255,
+ +0.2419, -0.3677, +0.0286, -0.1124, -0.5604, -0.2697, +0.5502,
+ +0.5108, +0.0349, +0.1436, +0.2292, +0.3306, -0.0245, -0.2355,
+ +0.2159, +0.3446, +0.0141, -0.4833, -0.6281, -0.5473, -0.1541,
+ -0.1232, -0.0373, +0.4579, -0.1223, -0.1132, -0.3418, -0.0561,
+ -0.1323, -0.0822, +0.1775, -0.0449, +0.5586, +0.4806, +0.1008,
+ -0.4178, -0.5695, +0.2924, +0.0781, -0.0481, +0.0942, +0.2641,
+ -0.1128, +0.1335, +0.3462, -0.2098, -0.6517, +0.2445, +0.1972,
+ +0.3612, -0.0474, -0.6685, -0.3003, +0.1448, +0.3570, +0.1684,
+ -0.0083, -0.6673, +0.2043, +0.0841, -0.5859, -0.4732, +0.1798,
+ +0.0359, -0.8334, +0.2058, -0.2315, -0.5527, -0.5864, +0.1296,
+ +0.2766, +0.3950, -0.2198, -1.2566, +0.0344, -0.0694, +0.1057,
+ +0.0886, -0.0006
+ ],
+ [
+ +0.2355, +0.2205, -1.3483, -0.1172, -0.3691, +0.2932, +0.4926,
+ +0.1500, -0.0933, -0.5618, +0.2887, +0.4631, +0.1941, +1.0716,
+ +0.5216, +0.5525, +0.1567, +0.6672, +0.9191, +0.7987, -0.6611,
+ +0.2176, +0.2716, +0.4893, +1.4128, +0.9177, -0.6401, -0.7346,
+ +1.3439, +0.2595, +0.0790, -0.4804, -0.2838, +0.0088, -0.3967,
+ -0.4801, +0.1584, -0.2085, -0.0461, -0.5256, -0.9473, +1.8738,
+ +0.8888, +0.7417, -0.4364, +0.4092, +0.4347, +0.6090, -1.3517,
+ +0.8034, -0.9465, -0.3539, +0.5229, -0.8088, -0.5375, +0.3207,
+ -0.1078, -0.1502, -0.1826, -0.6835, +0.1005, +0.9818, -0.0366,
+ -0.0235, +1.3464, -1.0394, +0.3553, -0.3647, -1.1125, +0.1898,
+ +0.1982, +1.4814, -0.1280, +0.9472, -0.2057, -1.0033, +0.2990,
+ +0.4505, -1.6867, +0.0372, -1.2470, +1.1743, -0.7300, -1.4268,
+ -0.4928, -0.2131, -0.0731, +0.5726, +1.0094, +0.1827, -0.0374,
+ -0.2762, +1.1445, +0.1382, +0.6379, -0.5874, +0.7924, -0.4141,
+ +0.2994, -0.3265, +0.8631, +0.0625, -0.5708, +0.3840, -0.1690,
+ -0.2459, -1.0880, +0.3760, -0.6786, -0.8060, -0.1018, +0.5281,
+ -0.4578, +0.1397, -0.0314, -0.0962, +0.0207, +0.6683, -0.5995,
+ +0.4266, +0.2856, +0.4398, +0.4314, +0.4667, -0.1604, -0.0962,
+ +0.4738, +0.3703
+ ],
+ [
+ +0.0467, +0.4707, +0.3331, +0.1481, +0.0379, +0.1480, +0.1593,
+ -0.0646, -0.1355, -0.0840, +0.1212, +0.4008, -0.3111, -0.2571,
+ +0.1511, +0.3338, +0.2279, -0.4840, -1.0219, +0.5547, -0.5126,
+ +0.0801, +0.2081, -0.0607, +0.0969, +0.2595, +0.2859, +0.2738,
+ +0.1785, +0.0969, -0.1021, -0.2732, +0.0357, -0.2654, -0.3296,
+ -0.3804, -0.1135, -0.2353, +0.5887, +0.5972, -0.5222, -0.1587,
+ -0.2610, -0.2225, -0.4598, -0.2176, +0.2049, -0.1485, -0.0299,
+ +0.1484, +0.1950, +0.5583, +0.5110, +0.1370, -0.0910, +0.0798,
+ -0.1201, -0.0193, -0.2943, +0.0764, -0.3307, +0.2936, +0.2535,
+ -0.3703, +0.0249, -0.0005, -0.1424, -0.3010, -0.0445, -0.3506,
+ +0.3826, +0.0547, -0.3623, -0.2543, -0.2261, +0.0637, +0.2958,
+ +0.3432, -0.1460, -0.0548, -0.0379, -0.3288, -0.1262, +0.1693,
+ -0.9188, -0.4361, +0.2599, +0.4048, -0.0817, +0.1643, -0.4248,
+ +0.2501, -0.1260, +0.1860, +0.0839, +0.1641, -0.0727, +0.1643,
+ -0.2693, -0.1530, +0.3114, -0.6813, -0.2417, +0.0138, -0.6074,
+ -0.4009, +0.1408, -0.3276, -0.2314, -0.1093, +0.1874, +0.1717,
+ +0.0237, +0.0482, -0.0837, -0.0706, +0.2035, -0.0895, -0.0915,
+ -0.2132, +0.1071, +0.2370, -0.1392, +0.4087, +0.0054, -0.0605,
+ +0.5010, -0.3720
+ ],
+ [
+ -0.6041, +0.3315, +0.4344, -0.0530, -0.0750, -0.6740, +0.5459,
+ +0.0864, -0.4466, -0.3376, -0.3102, -0.0338, +0.2650, +0.5327,
+ +0.0622, -0.7640, +0.0327, +0.1950, -0.1494, -0.6298, -0.0713,
+ +0.0398, +0.0742, -0.9150, -0.0288, +0.1934, -0.6378, +0.0861,
+ +0.1895, +0.2527, -1.2174, +0.2087, -0.0830, -0.1214, +0.1712,
+ -0.0216, +0.2538, +0.1952, +0.3798, -0.3429, +0.1725, +0.3499,
+ +0.3408, +0.4805, +0.4361, +0.0572, +0.0162, -0.2105, -0.0226,
+ +0.1329, -0.4117, -0.4411, +0.0208, -0.3427, +0.1636, -0.4633,
+ +0.2159, +0.0833, -0.2476, -0.0152, -0.0169, +0.2707, +0.4725,
+ +0.4281, +0.1138, -0.2027, -0.1338, +0.0103, -0.1651, -0.1051,
+ -0.0860, +0.1426, -0.1318, -0.1000, -0.3799, -0.1731, +0.0442,
+ -1.0749, +0.2806, -0.0405, -0.6049, +0.4326, +0.3027, +0.2951,
+ +0.2068, -1.1063, +0.1727, +0.0808, +0.3021, +0.2196, +0.2176,
+ -0.0847, -0.6010, +0.1784, -0.0912, -0.6264, +0.1444, +0.0617,
+ +0.2282, -0.2726, +0.1764, +0.1803, +0.3600, -0.3617, -0.1991,
+ -0.3087, +0.3560, -0.5956, -0.0958, +0.1788, +0.2348, -0.1670,
+ -0.2103, -0.1210, +0.2132, -0.1198, +0.0154, +0.2332, +0.2034,
+ -0.5947, -0.0082, -0.1029, +0.4438, -0.6764, +0.1075, +0.0251,
+ -0.5663, -0.4196
+ ]])
-weights_dense2_w = np.array([
-[ -0.1271, +0.3914, +0.0018, -0.6558, -0.4675, +0.0085, -0.1844, +0.6802, -0.0125, +0.4014, -0.5915, -0.9738, +0.1934, -1.1626, -0.1495, +0.5737, +0.0789, -0.0532, -0.0646, -0.6168, +0.0404, -0.2622, -0.2860, -1.0234, -1.0591, -0.0915, -0.6457, -0.4371, +0.2578, -0.1847, -0.0168, -0.3883, +0.3122, -0.2463, +0.0569, -0.6280, +0.2718, -0.3457, +0.0460, -0.0186, -0.5913, -0.1637, +0.1242, +0.1545, -0.4075, +0.1479, +0.4976, -0.6677, +0.1678, +0.0601, -0.6402, +0.2643, +0.5309, -0.5865, +0.4594, -0.4839, +0.0092, -1.0042, -0.4222, -0.1008, +0.3164, +0.4503, -0.4733, -0.3181],
-[ -0.7950, -0.2874, -0.9796, -0.0894, -0.2489, +0.1023, -0.7191, -0.1062, -0.0686, +0.0219, -0.5166, -0.1731, +0.6046, +0.1325, -0.1113, -0.1895, -0.5124, +0.2307, +0.1318, -0.1584, -0.0253, -0.0489, -0.1236, +0.1723, -0.1987, -0.1482, +0.2360, -0.6252, +0.1100, -0.0496, -0.2046, -0.0098, +0.1554, -0.0330, +0.1830, +0.5273, -0.2040, -0.3389, -0.0136, +0.3009, -0.8369, -0.5315, +0.3389, +0.0406, -0.1619, +0.1336, -0.0931, +0.3350, -0.5562, -0.2256, -0.1484, -0.1714, +0.3276, +0.3614, -0.5478, +0.0381, -0.6016, -0.4736, -0.1763, +0.6435, -0.4753, -1.0543, +0.8731, -0.0291],
-[ +0.0954, -0.2826, +0.4515, +0.2719, -1.5872, -0.6669, +0.5393, +0.0683, +0.0223, -0.4139, -0.0436, -0.2927, -0.1016, +0.0872, -0.0511, +0.2276, -0.3104, -0.1281, -0.3726, -0.4281, -0.2043, -0.0067, -0.0833, +0.1530, +0.1471, +0.0299, -0.7778, -0.4584, -0.2937, -0.5823, +0.1004, -0.0315, -0.2546, -0.2999, +0.1273, -0.4236, +0.0839, -0.2711, -0.4104, -0.9313, +0.1809, +0.1160, +0.1217, +0.0610, -0.1349, +0.1962, +0.2288, +0.0999, -0.2857, +0.1488, -1.1450, +0.0397, +0.0243, -0.4398, -0.1675, +0.1116, -0.4391, +0.3284, +0.2221, -0.2577, -0.4555, -0.0088, -0.0855, -1.3852],
-[ -0.9066, -0.0779, +0.2506, +0.5973, -0.2074, -0.0816, +0.1313, -0.0467, +0.3583, -0.2508, +0.3739, +0.3117, -0.4828, +0.3411, -0.4750, -0.2348, -0.0597, -0.1498, -0.6612, -0.1696, -0.4938, +0.1585, +0.2521, -0.4542, +0.0009, -0.1163, +0.2059, -0.2132, +0.2928, +0.2853, +0.1130, +0.1913, -0.0430, +0.0943, -0.0217, -0.4564, +0.2648, -0.3642, -0.0154, -0.1325, -0.1173, +0.0562, +0.4583, +0.2892, -0.5079, +0.6878, -0.1487, +0.0205, +0.0981, -0.0039, -0.3292, +0.0082, +0.1342, -0.0187, +0.3907, -0.2287, -0.5168, -1.0717, -0.1443, -0.1601, +0.1502, +0.2766, -0.0043, +0.1320],
-[ -0.2278, +0.1479, -0.7906, +0.1998, +0.5790, -0.7421, +0.0865, -0.4855, +0.0669, +0.5062, -0.5994, +0.1859, -0.3231, -0.4490, -0.6158, -0.0905, +0.1926, -0.0107, -0.1922, +0.3182, +0.7090, +0.1008, -0.5894, -0.1029, +0.2866, -0.9230, +0.3036, -1.6312, -0.4129, +0.0185, +0.2326, -1.2005, -0.2662, -0.1140, -0.3067, -0.9747, -0.4549, +0.0886, +1.1618, +0.0391, +0.5329, +0.3774, +0.0105, +0.0694, +0.0137, -0.4737, -0.1588, +0.3237, -0.3649, +0.0849, -0.2834, -0.4216, +0.2610, -0.7456, -0.3009, +0.2728, +0.2492, +0.4658, -0.4006, +0.0284, +0.3466, -0.2762, -0.0260, -0.3199],
-[ +0.0064, -0.2720, -1.1888, +0.1102, -0.6399, -0.5524, +0.1461, -0.6517, +0.0382, +0.5065, -0.1815, -0.7615, +0.1473, -0.0197, +0.1725, +0.0512, +0.2036, +0.4414, -0.1795, -0.0886, -0.1142, +0.4498, +0.1177, +0.0057, -0.0964, -0.0811, +0.1596, -0.4883, +0.1965, -0.1698, +0.2760, -0.0165, -0.1367, +0.3872, -0.1555, +0.4407, -0.1900, -0.7512, -0.5738, +0.0527, -0.1601, +0.1037, -0.1187, -0.2776, -0.3760, +0.5335, -0.5347, -0.1479, +0.0165, -0.0124, +0.7250, +0.1477, +0.0149, +0.1117, +0.2934, +0.2190, -0.1941, -0.5849, +0.1879, -0.4424, -0.9252, +0.1739, -0.5742, +0.3218],
-[ -0.5851, +0.2061, -0.1146, +0.3440, -0.8697, +0.5240, +0.0196, -0.0692, -0.4171, +0.1702, -0.2292, -0.2366, -0.0427, -0.3395, -0.0157, -0.1608, -0.0301, -0.0541, +0.1548, -1.1881, -0.1515, -0.0891, +0.0046, -0.2020, +0.1449, -1.1849, -0.2219, -0.3805, +0.0840, -0.2359, +0.2454, -0.4630, -0.0234, -0.1242, +0.0518, +0.6156, +0.1568, +0.3287, -0.0841, -0.7317, -0.6159, +0.3588, +0.1828, -0.9023, -1.1006, -0.0212, +0.2007, +0.5831, +0.0995, -0.6283, -0.0894, +0.1098, -0.2749, -0.0411, -0.0119, +0.0558, +0.1683, -0.0131, +0.1848, +0.0679, +0.0456, -0.2571, -0.9563, -0.2443],
-[ -0.0073, -0.3201, -0.3817, -0.0192, -0.4109, -0.4282, -0.1132, -0.4349, +0.2255, -0.0437, -0.6572, +0.2767, -0.4989, -0.4036, -0.1763, +0.2089, -0.5215, +0.1290, -0.1541, -0.3489, +0.2339, -0.0198, -0.0317, -0.9100, -0.0544, -0.6314, -0.1819, +0.2346, -0.0081, +0.0007, -0.0257, -0.1465, -0.6833, -0.9600, -0.1040, -0.1067, -1.1308, -0.2348, +0.1580, -0.9859, -0.9199, -0.0363, -0.0562, +0.0475, -0.5149, +0.2848, -0.3803, -0.1797, -0.0309, -0.1081, -1.3299, -0.1604, -0.1880, +0.0615, +0.1823, +0.0057, +0.1575, +0.0888, -0.1895, +0.2093, -0.1036, -0.6154, +0.5185, +0.1521],
-[ +0.2531, -0.6279, -1.4513, -0.1934, +0.0015, -0.4900, -0.2063, -0.4151, +0.1763, -0.0243, -0.6314, -1.2217, -0.9091, -0.0730, -0.4270, +0.0620, -0.6859, +0.0461, -0.0924, +0.3800, +0.1811, +0.1697, -0.2316, -0.5443, +0.0866, +0.0782, +0.1150, -0.6990, -1.1189, -0.3874, -0.4161, +0.0440, -0.7594, -0.2724, -0.5725, +0.3213, +0.2200, +0.1760, -0.2150, +0.1958, -1.6232, -0.2854, -0.0612, -0.2916, -0.0928, +0.0537, -1.0109, +0.4645, +0.0471, +0.0559, +0.2336, +0.0665, +0.1497, -0.3873, -0.1014, +0.1958, -0.6501, -0.1341, +0.1965, -0.4280, +0.2265, +0.0304, +0.6069, -0.3555],
-[ -0.7091, -0.1624, +0.1640, -0.0758, -1.2377, -0.0772, +0.1476, +0.2682, -0.1253, +0.2720, -0.1572, -0.0119, +0.3484, +0.4451, +0.2922, +0.5946, -0.5605, +0.1464, +0.6736, -0.1512, -0.2042, +0.3320, -1.2094, +0.0608, +0.7341, -0.0744, -0.5122, -0.3548, -1.1743, +0.3937, -0.4435, -0.5681, -0.1948, +0.2073, -0.4939, +0.2860, -0.0874, -0.1584, -0.5339, -0.6618, +0.4565, -0.0450, -0.0703, +0.1782, +0.2719, -0.7235, +0.0849, -0.5152, -0.4409, -0.1473, +0.1932, -0.5657, -1.0101, +0.2300, +0.1768, -0.2755, -0.4970, +0.2075, +0.6405, -0.4757, -0.3832, -0.5012, -0.6960, -0.4705],
-[ -0.2843, -0.5661, +0.1295, -0.6372, +0.6743, +0.3116, -0.1094, +0.2181, +0.4413, +0.0471, +0.3553, +0.3585, +0.4372, -0.0685, -0.0842, -0.4250, +0.4091, -0.3233, -0.2269, -0.0794, +0.8587, +0.1432, -0.3835, -0.1686, +0.1641, -0.7328, -0.8287, -0.4402, -1.3005, +0.5130, +0.0564, +0.1681, -0.3760, +0.0408, -0.1430, -0.8277, +0.0467, -0.7583, -0.1697, -0.2131, +0.2831, +0.1558, +0.2284, -0.2450, +0.0555, -0.1912, +0.0449, -0.2269, -0.3708, +0.2114, -0.4205, -0.7571, -0.0382, -0.2707, -0.0797, -0.1280, +0.0478, -0.0070, -0.1342, -0.9769, +0.2671, -1.0572, -0.0770, -0.9964],
-[ +0.6900, +0.4678, -0.0557, -0.2668, +0.7300, -0.5408, -0.0688, +0.0454, -0.5562, +0.0199, +0.3122, -0.6756, +0.5708, +0.1600, +0.6282, +0.2039, -0.3018, +0.1667, -0.0453, -0.7653, -0.2430, -0.4678, +0.1237, +0.2742, +0.2941, +0.0830, -1.0421, +0.3499, -0.5175, +0.2747, +0.1062, -0.2901, -0.2809, +0.1417, +0.1436, +0.3868, +0.5309, -0.0153, +0.0805, -0.2631, -0.0940, -0.1412, +0.2611, -0.7766, -0.2855, -0.0439, -0.6175, +0.0947, +0.2999, -0.0547, +0.5183, +0.2994, -0.8269, +0.0034, +0.0987, +0.5503, -0.0088, +0.4137, +0.3632, -0.2834, -0.6923, -0.2821, -1.1406, -0.0749],
-[ +0.1632, -0.4623, -0.1741, +0.0680, -0.9023, -0.0249, +0.4469, -0.4021, -0.1585, +0.1242, +0.3737, -0.0057, +0.6399, -0.3139, -0.2913, +0.1754, +0.0486, -0.4752, -0.1895, -0.3187, -0.2623, +0.0258, -0.1153, +0.2278, +0.0386, -0.8582, +0.8477, -0.0064, +0.4177, -0.0644, +0.5750, +0.4484, -0.1827, +0.3148, +0.1698, -0.3985, +0.0600, -0.0887, -0.8542, -0.7936, -0.4169, +0.3954, +0.1737, -0.3940, +0.0167, +0.1208, +0.0302, +0.0156, +0.0017, +0.0780, -0.6662, +0.1520, +0.2476, -0.7796, -0.0420, +0.7442, -0.1745, +0.1173, +0.5134, +0.3903, -0.0390, -0.2774, -0.0728, -0.5430],
-[ +0.4816, -0.3489, +0.5506, -0.6623, -0.9104, -0.8120, -0.8344, -0.2220, +0.3552, -0.0790, -0.8096, +0.2325, -0.3253, +0.1020, +0.1459, -0.0834, -0.7332, -0.3141, -0.8383, +0.0168, +0.1568, +0.5853, -0.1375, +0.1475, +0.6293, +0.2314, -1.1498, -0.3753, -0.8417, -0.8575, -1.3400, -0.2256, -1.4539, -0.3584, -0.4006, +0.1593, -0.9150, +0.6774, -0.2619, +0.1728, -0.2879, -0.1338, -0.5645, +0.3988, +0.3520, +0.4010, -0.2041, +0.0341, -0.3362, +0.2805, -2.0402, -0.6181, -0.7972, +0.1749, -0.6493, -1.4597, -0.5267, +0.5981, +0.2521, -0.5638, -0.2909, -0.4402, -0.0561, +0.4762],
-[ -0.4250, +0.1095, -0.0655, -0.1546, -0.2041, -0.1293, +0.2493, -0.0696, +0.0848, +0.1911, -0.1816, -0.6701, -0.0172, +0.0131, +0.0102, -0.3538, +0.3072, -0.4811, +0.1599, +0.0691, +0.1479, +0.0118, +0.3573, +0.2026, -0.7681, -0.1526, -0.4309, +0.8109, -1.1647, +0.2582, -0.5493, +0.2395, +0.5988, +0.0868, -0.3176, -0.3688, +0.1128, -0.0358, -0.5428, +0.1570, -0.3296, -0.4567, -0.4286, -0.1437, +0.1628, +0.0506, -0.1043, +0.3776, +0.3047, +0.0809, +0.1967, -0.1743, -0.2635, -0.3714, -0.0760, -0.0980, +0.3933, +0.1918, -0.0237, -0.3041, +0.2151, -0.2341, -0.1485, -0.0661],
-[ +0.2394, +0.4236, +0.4937, +0.4839, +0.2579, -0.4842, +0.7196, +0.3410, +0.2490, +0.5013, -0.5042, -0.5623, +0.2319, +0.1771, +0.3028, +0.1137, +0.4389, -0.3229, -0.5965, -0.6932, +0.6443, +0.7066, -0.0893, -0.6891, -0.2387, -0.2105, -0.6846, +0.0999, -0.1248, -0.1359, +0.2185, +0.0941, +0.3376, -0.2558, -0.3110, -0.0893, -0.1423, -0.4745, +0.0687, -0.2922, -0.0603, -0.0707, -0.0455, +0.5964, -0.0152, -0.1886, +0.0025, +0.1093, +0.3974, +0.3669, -0.3385, -0.4696, -0.0199, -0.6017, +0.4395, +0.6234, -0.0496, -0.2090, -0.2171, +0.3449, -0.0730, -0.1001, -0.3171, +0.5123],
-[ +0.0847, +0.1436, -0.3228, -0.3510, -0.7931, -0.0264, -0.3533, +0.6762, -0.0224, -0.1094, -0.3798, +0.1935, -0.2485, -0.1415, -0.5330, +0.2227, +0.1866, -0.3358, -1.9247, +0.1269, -0.0177, +0.1557, -0.3095, +0.2560, +0.0238, +0.2123, +0.4908, -0.3848, -0.0091, -0.2054, -0.1635, +0.0463, +0.0052, +0.2153, -0.0972, +0.3529, -0.5443, +0.5997, -0.6787, -0.7814, -0.2001, +0.1732, -0.1145, +0.2478, -0.2095, -1.0370, +0.0598, +0.1606, +0.3335, +0.3511, +0.3206, -0.5018, +0.5416, -1.2949, -1.5172, +0.0665, -0.3943, -0.6214, -0.0136, +0.2626, -0.2100, -0.0828, -0.3910, -0.3130],
-[ +0.0901, +0.0253, +0.2478, +0.3539, -0.6675, +0.2158, +0.2303, +0.4287, +0.1316, +0.1663, -0.0972, -0.6236, -0.1827, +0.0954, +0.1095, -0.2775, +0.0321, +0.1237, -0.9309, +0.1208, +0.0141, -0.5857, +0.2646, -0.0349, -0.5315, -0.0656, -0.1674, -0.4231, +0.0615, -0.2795, +0.5309, +0.0471, +0.3718, +0.4552, -0.2424, -0.0762, +0.2703, +0.0431, -0.2285, +0.1411, -0.3293, -0.1031, -0.1698, -0.4149, -0.4501, +0.3116, +0.0163, -0.4347, +0.4256, -0.1770, +0.1217, -0.4240, +0.2111, -1.9418, -0.5665, +0.1624, +0.0666, -0.0973, +0.9793, -1.0486, +0.6492, +0.0490, -0.3199, -0.3808],
-[ +0.2482, +0.3556, -0.1717, -0.9919, +0.7054, -1.2118, -0.5110, -0.3328, -0.1633, +0.3957, +0.3085, +0.0137, +0.3065, +0.0052, -0.0270, +0.0560, +0.2907, -0.6105, -0.4772, +0.1645, +0.0208, -0.9893, +0.3875, +0.2657, +0.3233, -0.3869, +0.1572, +0.1036, -0.1463, +0.0472, -0.3489, -0.3521, +0.0799, -0.6925, +0.0984, +0.3195, +0.3130, +0.6108, +0.2780, +0.0603, -0.2143, -0.1337, -0.2644, -0.5923, +0.2042, -0.4949, -0.0480, +0.3116, -0.1095, +0.2364, -1.1135, -0.0363, -1.0648, +0.2119, -0.0442, +0.0743, -0.0370, +0.2927, +0.2213, +0.2895, -0.1277, +0.4592, -0.5358, +0.1096],
-[ -0.0645, -0.1623, -0.2801, +0.1601, +0.4115, +0.1034, +0.5808, -0.3871, +0.0811, +0.1312, -1.2262, -0.3058, -0.4259, -1.4654, -0.8499, -0.4536, -0.0568, +0.3527, -0.4492, +0.2055, +0.2393, +0.3164, -0.1928, -0.1498, -0.4880, +0.1955, +0.2008, -1.0742, +0.0050, -0.0898, +0.3253, -0.0754, +0.0392, -0.0040, +0.1946, +0.0193, +0.0192, +0.4451, -0.7988, +0.0087, -0.2325, +0.2076, +0.0636, -0.1281, +0.5703, +0.1476, +0.0923, -0.2612, -0.2150, +0.3855, -0.2078, -0.1543, -0.2050, +0.3544, +0.0617, +0.0985, -0.2980, -1.1922, -1.3932, +0.1081, +0.1347, -0.7791, +0.0098, +0.3203],
-[ -0.2477, -0.0342, +0.0651, +0.4190, -0.1286, -0.1516, +0.3836, -0.5551, -0.0254, +0.0229, +0.3122, -0.0037, -0.3752, +0.0208, -0.2014, -1.0760, +0.0428, +0.9403, +0.0155, -0.2281, -0.5390, -0.3031, -0.2937, -0.0763, +0.4585, +0.3504, -0.6128, +0.0253, +0.1955, -1.3097, -0.4295, -0.7464, -0.3443, +0.0480, -0.2732, -0.3435, -0.4001, +0.5535, -0.0008, -0.6926, +0.4328, +0.0657, +0.1847, +0.0448, -0.5529, +0.3648, +0.4270, -0.0240, -0.0652, +0.2067, +0.3803, -0.1376, -0.1249, +0.1560, -0.2670, -0.0751, -0.1908, +0.4397, +0.1006, -0.0798, -0.5067, -0.0203, -0.7287, -0.5677],
-[ -0.4990, -0.2926, -0.3664, +0.0513, +0.0405, +0.1084, +0.3047, -0.5012, +0.0434, +0.1440, -0.6061, -0.0411, -0.6098, -0.8454, +0.0514, -0.0952, +0.1158, -0.0216, +0.3436, -0.1477, +0.3443, +0.1691, +0.1902, -0.5084, -0.3644, +0.1407, +0.2799, -1.1430, -0.1313, -0.4736, +0.2768, -0.1113, +0.2119, +0.3614, +0.0707, -0.4669, -0.0945, -0.0747, +0.2336, +0.0373, +0.3955, -0.0911, -0.2888, -0.0373, -0.0459, -0.1130, +0.1475, +0.1832, -0.0709, +0.1757, +0.0890, -0.2821, -0.2146, +0.2685, +0.2819, +0.2381, +0.3611, +0.2664, -0.4607, +0.4548, -0.5928, -0.7542, +0.3888, -0.1321],
-[ +0.2451, -0.0352, -0.0067, +0.5649, -1.3223, -0.0114, -0.2494, +0.2709, -0.1561, +0.6785, -0.4168, -0.0214, +0.1366, -0.1545, -0.0716, +0.2056, -0.5251, +0.2082, +0.0296, +0.1914, -0.5742, +0.0196, -0.2925, +0.2337, +0.4122, -0.5012, +0.1940, +0.3099, -0.9448, +0.4322, -0.5790, -0.3489, +0.0104, -1.0007, +0.2016, +0.2950, +0.2477, -0.1989, -0.3270, -0.3255, -0.0711, +0.1675, +0.1886, -0.3077, +0.6931, +0.0106, +0.0890, +0.2538, +0.3688, -0.3061, -0.5655, +0.0562, +0.3011, +0.0977, -0.1398, -0.2165, -0.7578, +0.0214, -0.4609, -0.2431, +0.0330, +0.2445, -0.0303, +0.0900],
-[ -0.0365, -0.0273, +0.4411, -0.4758, -0.0957, +0.1289, -0.0185, -0.6137, -0.6106, +0.2414, +0.4711, +0.0494, +0.0588, -0.1135, -0.2285, +0.2474, -0.1030, -0.0374, -0.3801, +0.3589, -0.1773, +0.0079, +0.0782, -0.0122, -0.0823, +0.7424, +0.0962, +0.4727, -0.8676, +0.3077, +0.0557, +0.3209, -0.1592, -0.4861, +0.0395, -0.9804, +0.1699, +0.4900, -0.0592, +0.2355, +0.1924, -0.5904, +0.2611, +0.3920, +0.2856, -0.3913, +0.2407, -0.2500, -0.1903, -0.5961, +0.1522, -0.0197, +0.0872, -0.1873, -0.3491, -0.1286, +0.3000, -0.7042, +0.2894, -0.1837, +0.0561, +0.1254, -0.3829, +0.2918],
-[ -0.3763, -0.4747, +0.4768, -0.0502, +0.1480, -0.1086, -1.4858, -0.1386, -0.0867, +0.0294, -0.9916, -1.3011, -0.3439, -0.0785, -0.0095, -0.0793, +0.1420, -0.4394, -0.4325, +0.0846, +0.1926, +0.1353, +0.0876, -0.3864, -0.4143, -0.3908, +0.1920, -0.0516, -0.3529, +0.1273, -0.8187, -0.3242, +0.3229, +0.3314, -0.0751, +0.0271, -0.5786, -0.4159, -0.5292, -0.1346, -0.5713, +0.0241, -0.3994, +0.6553, +0.1069, -0.3205, -0.1558, -0.0292, -0.1864, +0.0467, -0.1643, -0.0032, -0.1768, -0.1139, +0.1924, +0.0858, +0.1814, -1.0873, +0.2349, +0.8407, +0.3165, -0.3767, -0.2488, +0.5314],
-[ +0.0194, -0.5392, -0.1518, -0.3236, -0.4986, +0.3160, -0.1412, +0.0953, +0.7768, +0.3661, -0.5067, +0.0749, +0.3022, -0.0791, +0.0717, -0.4890, -0.5433, +0.1542, -0.1284, -0.5432, +0.1367, +0.4199, +0.0517, -0.2629, -0.2446, -0.5404, -0.0661, -0.8388, +0.2460, -0.0568, +0.1513, -0.1651, -0.5316, -0.3067, +0.2167, +0.3853, +0.1916, -0.3641, +0.1010, -0.6142, -0.3014, +0.0601, -0.1717, -0.0344, -0.1642, +0.2797, -0.2147, +0.3422, +0.1077, -0.3756, -0.3877, -0.0933, -0.2401, -0.9595, -0.2368, -0.1898, -1.2555, +0.0958, +0.0762, -0.0292, +0.3576, -0.1580, -0.0738, -0.0079],
-[ +0.0141, +0.0895, -1.2167, -0.2237, -0.3790, +0.1855, -0.3394, -0.0038, -0.9612, -0.8003, -0.4690, -0.7451, -0.0575, -0.4595, -0.1010, +0.0564, -0.2061, +0.0016, +0.2122, -0.5486, +0.2575, +0.6701, -0.2359, -0.6095, +0.2275, +0.4353, -0.0755, +0.1635, -1.1059, +0.0813, +0.5430, +0.2135, -0.7705, -0.3789, -0.4640, +0.1618, -0.0749, -0.1601, -0.2568, +0.2982, -0.5505, -0.2380, +0.2200, -0.7600, -0.3742, +0.0263, +0.0205, +0.2430, -0.1207, -0.1844, -0.4536, +0.2157, -0.0314, +0.0561, +0.7357, +0.0529, -0.7068, -0.0974, -0.7203, +0.2107, -0.4502, +0.0662, -0.4206, -0.3138],
-[ +0.1017, -0.0354, -0.0509, -0.1870, +0.0343, +0.3647, +0.1347, +0.2237, +0.3690, -0.9343, +0.1449, -0.5858, -0.2125, +0.5630, -0.1528, -0.1546, -0.7001, -0.1598, +0.2196, -0.0277, -0.5136, -0.8544, +0.0426, -0.5008, +0.1092, -0.0860, -0.0112, +0.0401, -0.6656, -0.1314, +0.1416, +0.3360, +0.5900, -0.2389, +0.0217, +0.1804, +0.2413, -0.5896, -0.4484, -0.0288, -0.3412, +0.5241, -0.0806, +0.1861, -0.6325, -0.4081, -0.0944, +0.4332, -0.5102, +0.1041, -0.1426, -0.2980, +0.1690, +0.1186, +0.2074, -1.0632, +0.7055, -0.2705, -1.0567, -0.2129, -1.1142, +0.2914, +0.2099, +0.1106],
-[ +0.3102, +0.1703, +0.3606, -0.0527, +0.1473, -0.2773, -0.0154, +0.1442, -0.1247, +0.0323, -0.3110, -0.1122, +0.1576, +0.2158, +0.1385, -0.2753, -0.1098, -0.7658, +0.2754, -0.0433, -0.0520, +0.5368, +0.1772, -0.0695, -0.0489, -0.0608, +0.1372, +0.2162, -0.2351, +0.2987, -0.1364, -0.2891, +0.3583, +0.1633, -0.3839, +0.4315, -0.0990, +0.0823, +0.1158, +0.0991, -0.1278, -0.3236, -1.2764, -0.6431, +0.1492, -0.3952, +0.1064, -0.1531, +0.2157, +0.4975, -0.2037, -0.4894, -1.5186, +0.2924, -0.6009, -0.1678, -0.1449, +0.1978, -0.3505, -0.0908, +0.0612, +0.2921, -0.0509, -0.1469],
-[ +0.1539, -0.1646, +0.0906, -0.8074, -0.3751, -0.2480, -0.1706, +0.0897, +0.1467, -0.2731, +0.0630, +0.1252, -0.3487, +0.1124, +0.3977, -0.5022, -0.2230, -1.1773, +0.0916, -0.3775, -0.3700, -1.3137, +0.2118, -0.0780, +0.2561, +0.3471, +0.2589, +0.5410, -0.6811, -0.0975, +0.2142, +0.1334, -0.1160, +0.2675, -0.6791, +0.0902, -0.0351, +0.1841, -0.1571, +0.0284, -0.1294, -0.2189, -0.4384, -0.6264, +0.1533, -0.5177, +0.1915, -0.0130, +0.4706, +0.0774, -0.1659, +0.1409, -0.1534, -0.0867, -0.3677, -0.2035, -0.6024, +0.2904, -0.5581, -1.1772, +0.2702, -0.0471, +0.0550, -0.4774],
-[ -0.0836, -0.4589, +0.3629, +0.2122, -0.8646, -0.0445, +0.0280, +0.1863, +0.2066, -0.1308, -0.1080, -0.3527, -0.2431, +0.2671, +0.2674, +0.0165, -0.0020, +0.3624, -0.5614, +0.5891, -0.3631, -0.0238, -0.1281, -1.3143, -0.3550, +0.3269, +0.1919, -1.0129, +0.4851, +0.0349, -0.0614, -1.2018, -0.6409, +0.7077, +0.1713, +0.1755, -0.5143, +0.4006, -0.7570, -1.0930, -0.1735, +0.6484, +0.2872, +0.2859, -0.4082, +0.2657, -0.3075, -0.1418, -0.1542, -0.1517, -0.0277, -0.5681, -0.4103, +0.2963, -0.2609, -0.2730, -0.4601, -0.1779, +0.1927, -0.8079, -0.2650, +0.0229, +0.1281, -0.5343],
-[ -0.4350, +0.0553, -0.5729, -0.2978, -0.9495, -0.7255, -0.7779, -1.1735, +0.1343, -0.3928, +0.2136, -0.2948, +0.1546, -0.9938, -0.1214, -0.0147, +0.0305, -0.1277, +0.7548, +0.2856, +0.0463, +0.0179, +0.0937, +0.8215, +0.2234, +0.1009, -0.3107, +0.0118, -0.4554, -0.0069, +0.1453, +0.0118, -0.1247, -0.6418, -0.0716, +0.4212, -0.5202, -0.0074, -1.1218, +0.1333, -0.0457, +0.3628, +0.3515, -0.1092, -0.4001, -0.5215, +0.1932, +0.0911, +0.0685, +0.0898, +0.0290, -0.5139, +0.0949, -0.1830, -0.5459, +0.1143, -0.8995, -0.2821, +0.4568, +0.0758, -0.9298, -0.4243, +0.3363, -0.2241],
-[ +0.3514, -0.1343, -0.1294, +0.2483, -1.1607, +0.2577, +0.1505, +0.0614, -0.0038, +0.1206, -0.3880, +0.1227, +0.1437, +0.0353, -0.2475, +0.1809, -0.0030, +0.5491, +0.3195, -0.1809, -0.3715, +0.0359, -0.5749, +0.3637, +0.2684, +0.2354, +0.2458, +0.2446, +0.1564, +0.3003, -0.0686, +0.2666, -0.4387, -0.7032, +0.2667, +0.4540, -0.3143, -0.0387, -0.7421, -0.1658, +0.0813, +0.1450, +0.0384, -0.0218, +0.0556, -0.0205, -0.1314, -0.0056, +0.1476, +0.0417, +0.1668, +0.0552, +0.0224, +0.4450, -0.0994, +0.5961, -0.6376, -0.5452, +0.0621, -0.0608, -0.2084, -0.1293, -0.0258, +0.2475],
-[ -0.1171, -0.2599, -0.1720, -0.0803, +0.0339, +0.2908, -0.2794, -0.3024, -0.3362, +0.1535, -0.6788, +0.0768, -0.4502, -0.3021, -0.5293, +0.3125, -0.2088, -0.9037, -0.3597, +0.4170, +0.2103, -0.3589, +0.0696, -0.1204, +0.0044, +0.0838, +0.0282, -0.5995, -0.2631, -0.4564, +0.3498, -0.2223, -0.8802, -0.4124, +0.0308, -0.0660, +0.0638, +0.1032, -0.1193, +0.0706, -0.6944, -0.4653, -0.0051, -0.2518, +0.1609, -0.0292, +0.4536, -0.0411, +0.1867, +0.1496, -0.2681, +0.5124, +0.1813, +0.2306, -0.0282, +0.1134, -0.6127, +0.1256, -0.2708, -0.2768, -0.8077, +0.2824, -0.5783, +0.3528],
-[ +0.2195, +0.0042, -0.2501, -0.5760, +0.2663, +0.2616, -1.4127, -0.0305, +0.0709, +0.1793, -0.0951, +0.0447, -0.3207, -0.6272, -0.0155, +0.1012, -0.0007, +0.1282, +0.4843, -0.0964, +0.2349, +0.3481, -0.0057, +0.1658, -0.3583, +0.0888, +0.0394, +0.2364, -0.3175, +0.2203, -0.1178, +0.1645, +0.0964, +0.3774, +0.4404, -0.5199, +0.6773, +0.1753, +0.4348, +0.1499, -0.0905, -0.2781, -0.0887, -0.4866, +0.0237, -0.4941, -0.0295, -0.3038, +0.3751, -0.1036, -0.0868, +0.2667, -0.3343, -0.6834, -0.1344, -0.0162, +0.2101, +0.2938, -0.2194, +0.1351, +0.0117, -0.0811, -0.2689, -0.2086],
-[ +0.2790, -0.2113, -0.0294, -0.2711, -0.2345, +0.1162, -0.0328, +0.2538, +0.5912, +0.1002, +0.2225, -0.5451, +0.4108, +0.0101, +0.0081, -0.0407, +0.9695, -0.0133, -0.0273, +0.4477, +0.0020, -0.8086, +0.3932, +0.1379, -0.9660, -0.2829, -0.2764, -0.4216, -0.1525, +0.0447, +0.4320, +0.5953, -0.4424, +0.4349, +0.1270, -1.0019, +0.8496, +0.1190, -0.0241, +0.3886, -0.2159, +0.1899, +0.2716, +0.2144, +0.1521, +0.6238, -0.0974, -0.1747, -0.4646, +0.1670, +0.0986, +0.2091, -0.4881, -0.5386, +0.7234, -0.2337, +0.0926, -0.2680, -0.1878, +0.3848, +0.1225, -0.1042, -0.8029, +0.0488],
-[ -0.0194, -0.1207, -0.7887, -0.1932, -0.7671, -0.6160, +0.5836, -0.5835, -0.6046, +0.4231, -0.0390, +0.1148, -0.6782, -0.3514, -0.2648, -0.0168, +0.0781, -0.2630, +0.0882, -0.6942, +0.3235, -0.0105, +0.1153, +0.4368, -0.1751, -0.7266, +0.2544, -1.3023, +0.2659, +0.1671, -0.2608, -0.8921, -0.3162, +0.3498, +0.3295, +0.3511, +0.2690, +0.1425, -0.3212, -0.3263, +0.3445, +0.2796, +0.2022, -0.6122, -0.1682, -0.2297, -0.8197, +0.2056, +0.1508, +0.1413, -0.7759, -0.2761, +0.3577, -0.3738, -0.4012, +0.3824, -0.3468, -0.0403, -0.0345, -1.2605, -0.2159, -0.1952, -0.2995, -1.1620],
-[ +0.0024, -0.0664, +0.2425, -0.2706, -0.4890, -0.0621, +0.0284, +0.1899, +0.3082, +0.0377, -0.0764, +0.0176, +0.1866, -0.4896, -0.3989, +0.0462, -0.0192, -0.1653, -0.3642, +0.1768, -0.6478, -0.0532, +0.0198, -0.7094, +0.0706, -0.0496, +0.4831, +0.1259, +0.3517, -0.8037, +0.2697, -0.6875, +0.0155, +0.2172, -0.2454, -0.0460, +0.0325, +0.3533, -0.7351, +0.0536, +0.3590, +0.0721, +0.0898, +0.3589, -0.6221, -0.0299, +0.1699, +0.0649, +0.0230, +0.0554, +0.0944, -0.3458, -0.0950, -0.7440, -0.3821, +0.1427, +0.1813, -0.2649, +0.5347, +0.6652, -0.1711, +0.7013, +0.1752, -0.1868],
-[ -0.1828, -0.6123, +0.6553, +0.1558, +0.3014, -0.4433, -0.7209, +0.2053, +0.3311, -0.1320, -0.4184, -0.1434, +0.0526, +0.3701, -0.0308, -0.3408, -0.2352, -0.3524, -0.1875, +0.2216, -0.2856, +0.0646, +0.1154, +0.2610, +0.2901, +0.2325, -0.2882, +0.0842, -1.1907, -0.2716, -0.7922, +0.7111, -1.2862, +0.0379, -0.4006, +0.0314, -0.4250, +0.1251, -0.0795, +0.1266, -0.8298, -0.1187, +0.3498, -0.9881, +0.0415, -0.7624, -0.0081, +0.6712, -0.3528, -0.0880, -0.9316, -0.5180, +0.5190, +0.0895, -0.6918, -0.7873, -0.9653, +0.2742, +0.1894, +0.0651, +0.0850, +0.3659, -0.0652, +0.4338],
-[ +0.3964, +0.2627, +0.1103, +0.3970, +0.0069, +0.0609, -0.5005, +0.1489, -0.1099, -0.0272, -0.2021, -0.2302, +0.5451, +0.2993, +0.5454, -0.3649, -0.2674, +0.2017, -0.1702, +0.0644, -0.2060, +0.1508, -0.3876, +0.1846, +0.2237, -0.0312, -0.0015, +0.2604, +0.0666, +0.1684, -0.5425, +0.0538, -0.1207, -0.2343, +0.3771, +0.0393, +0.0222, -0.7628, -0.0214, +0.0529, +0.3262, -0.1331, +0.4950, +0.0991, +0.4385, +0.2752, +0.0735, -0.0804, +0.2287, +0.1171, -0.0309, -0.0385, -0.1264, +0.1230, +0.7229, +0.1880, -0.2943, -0.2166, -0.4507, +0.0930, -0.0285, +0.0990, +0.0044, +0.3985],
-[ -0.0031, +0.5645, -0.1319, -0.5523, -0.4907, +0.4110, +0.3013, -0.8591, +0.1433, -0.1375, -0.3205, +0.0561, -0.2520, -0.0548, -0.2757, -0.3679, +0.3600, -0.3787, -0.5952, +0.0254, -0.9357, -0.1175, -0.7752, +0.1179, -0.2159, +0.0500, -0.1339, +0.5283, -0.9314, -0.6431, +0.1058, +0.3230, -0.1007, -0.1266, -0.5315, -0.8632, -0.9976, +0.1715, -0.2625, +0.0601, +0.1164, +0.1491, -0.0567, -0.2342, +0.0974, -0.1337, +0.1588, -0.1241, -0.5045, +0.0436, -0.5320, +0.3478, +0.1662, +0.0267, -0.2026, -0.1873, -0.3899, +0.3353, +0.0762, -0.8446, +0.4566, -0.1213, -0.1316, -0.1156],
-[ +0.0788, -0.5533, -0.0632, +0.4225, -0.1865, +0.1681, +0.0134, +0.7480, -0.3772, +0.5010, +0.2476, -0.1259, +0.3469, +0.4376, +0.2804, -0.0866, -0.1412, -0.3347, -0.3281, -0.5378, +0.2721, -0.0447, +0.0935, -0.0756, -0.1555, -0.8725, -0.0454, -0.0183, -0.1579, +0.0542, -0.1080, -0.3307, +0.2024, +0.3322, +0.0422, +0.1186, +0.3260, -0.2936, -0.3349, -0.4838, +0.0834, +0.0592, -0.6705, -0.3260, +0.0743, +0.2571, +0.2412, +0.0242, +0.2629, +0.0535, +0.5536, -0.2178, -0.6783, -0.1315, +0.1264, +0.3777, +0.0022, +0.5147, +0.0381, -0.7052, -0.4232, +0.3291, +0.0325, -0.8253],
-[ -0.4288, +0.1143, +0.0962, +0.7745, -0.6219, -0.6415, -0.5820, -0.7458, +0.1792, -0.0657, -0.0073, -0.2255, -0.6996, +0.5389, +0.0176, -0.5660, +0.1982, +0.0434, -0.5836, -0.0448, -0.2092, -0.0071, +0.3852, -0.2947, -0.6535, +0.4864, -0.7791, -0.1412, -0.1299, +0.3475, +0.1343, +0.3463, +0.1048, +0.0316, -0.5184, -0.0222, -0.3967, -0.0674, +0.1681, +0.0684, +0.2178, -0.3731, -0.1102, +0.2250, +0.0125, -0.2276, +0.3460, +0.5391, +0.2497, +0.1035, -0.6424, -0.0980, -0.5851, -0.0769, -0.1334, -0.2680, +0.2863, -0.2820, +0.3512, +0.4946, -0.5509, -0.3891, -0.5598, +0.1242],
-[ +0.2275, -1.2861, +0.1299, -0.0979, -0.4085, -0.1043, +0.0712, +0.5451, +0.3515, +0.3715, -0.5478, +0.2548, -0.2834, -0.0661, +0.1657, -0.1720, +0.0069, +0.1588, -0.1688, -0.4428, -0.2631, -0.1873, -0.8449, -0.1050, +0.1493, -0.2306, +0.2786, +0.1779, -1.2995, +0.0726, -0.0404, -0.1492, -0.3769, -0.0255, -1.3681, -0.4152, -0.2884, -0.0752, -0.4874, +0.0279, -0.1301, +0.2796, -0.9356, +0.3804, +0.2122, +0.5285, +0.1615, -0.0558, -0.2161, -0.0181, -0.8286, -0.1466, -0.5898, +0.2223, +0.3719, -1.2969, -0.9986, +0.4289, -0.0471, -0.6719, +0.1405, +0.1363, +0.0252, -0.3354],
-[ -0.3759, -0.6515, +0.0460, +0.0283, -0.8381, +0.3087, +0.3022, -0.2319, +0.1286, -0.1438, +0.1850, -0.1800, -0.1794, +0.0986, -0.1768, -0.0451, -0.2033, -0.1855, +0.6338, -0.4709, -0.5497, +0.7151, -0.4716, -0.5314, +0.1111, +0.2166, -0.0352, -0.0598, +0.3829, -0.0287, -0.0314, +0.0628, +0.1576, +0.2672, -1.1742, -0.4661, -0.9687, +0.1184, -0.5358, -0.7947, +0.2941, +0.3904, +0.5036, -0.0896, +0.1207, +0.1425, +0.2391, -0.0947, +0.0254, -0.0128, -0.7186, -0.0005, -0.2771, +0.0802, -0.2057, -0.1500, -0.0696, +0.1850, +0.3296, -0.1802, -0.8522, +0.1613, -0.3446, -0.9611],
-[ -0.0172, +0.2102, +0.1269, -0.9535, -0.3040, +0.3378, +0.3050, -0.2810, -0.2334, +0.2156, -0.0862, -0.1692, -0.2226, -0.2373, -0.0424, -0.2194, +0.5642, +0.3826, -0.5695, +0.2485, -1.7143, -0.1864, +0.3349, -0.0294, +0.2349, +0.1219, +0.3391, +0.2065, +0.1599, -0.0162, +0.2464, +0.2802, +0.1396, +0.1066, +0.2178, -0.2903, +0.2673, +0.4015, -0.0220, +0.3709, +0.6791, +0.1762, -1.1385, -0.2852, +0.4311, -1.1372, +0.3373, +0.0017, +0.3223, -0.5834, -1.0435, +0.1683, -1.1370, +0.0143, -0.0677, -0.0824, +0.0469, -0.2916, +0.2428, +0.6020, +0.1504, +0.2878, +0.2507, -0.0694],
-[ -0.2793, -1.2367, +0.1159, -0.2581, +0.3229, +0.0633, +0.0636, +0.2241, +0.3225, -0.0054, -0.3638, -0.0872, -0.8421, -0.0888, +0.0428, -0.2117, -0.1279, -0.3660, +0.3204, -0.1785, -0.0268, +0.2952, +0.1293, -0.1686, +0.0307, +0.3396, +0.2283, +0.1379, -0.0364, +0.1079, +0.2544, +0.0268, +0.2063, -0.2763, -0.3733, +0.1734, -0.0365, +0.2843, +0.1328, +0.0068, +0.0526, -0.0669, -0.7334, -0.0753, +0.0473, -0.2722, +0.2632, +0.2818, +0.3078, -0.4365, -0.4914, -0.8685, -1.4296, +0.1319, +0.2325, -0.4812, -0.1695, +0.1455, -0.4673, +0.2661, +0.2466, +0.1248, +0.5303, +0.2625],
-[ -0.2681, +0.0662, -0.5923, -0.3222, -0.6338, -0.5358, +0.6831, -0.0542, +0.4915, -0.0380, +0.0579, +0.3449, -0.6349, +0.4578, +0.0056, -0.2389, -0.0125, -0.6983, +0.0123, +0.5005, -0.3100, -0.1522, +0.1345, +0.5235, +0.6363, +0.1654, +0.1748, +0.2844, +0.2939, -0.2889, +0.2093, -0.3874, -0.0596, +0.1637, -0.5551, -0.2298, -2.1090, -0.6629, +0.3637, +0.1401, -0.3406, -0.2474, -0.2669, -0.6201, -0.4406, +0.1284, +0.8146, +0.2618, -0.2990, +0.5372, +0.4015, -0.4386, -0.3580, +0.3213, -0.1395, -0.1086, -0.3120, +0.3592, -0.1714, -0.9797, -0.2330, -0.2895, +0.5740, -0.0750],
-[ -0.9698, -0.8484, +0.0831, +0.3071, +0.3030, -0.3330, +0.2211, +0.1237, +0.1860, -1.4592, +0.0474, -0.2930, -0.5213, -0.2863, -0.4018, -0.5164, -0.7680, -1.2742, +0.1244, -0.6117, +0.3339, -0.6391, +0.0054, -0.6506, +0.2615, -0.1341, +0.3390, -0.9834, -0.5222, +0.5488, +0.1504, +0.1792, -0.0281, -0.2283, -0.7494, -0.2537, -0.2610, -0.1271, -0.1880, +0.0840, +0.1234, +0.2401, -0.1056, +0.1950, -0.4009, +0.0054, -0.2824, +0.5646, +0.2155, -0.2039, -0.4253, +0.0929, +0.3874, +0.0945, -0.3247, -0.4850, -0.3040, -1.0356, +0.1536, -0.0128, -0.2592, -0.8912, +0.0705, +0.3209],
-[ -0.3948, -0.9965, +0.0050, +0.2379, +0.0539, +0.3259, +0.0382, -0.1108, -0.2276, -0.4007, +0.0166, -0.5534, -0.2853, +0.4997, +0.2019, +0.0453, +0.2201, -0.2351, -0.9356, -0.2385, -0.0424, -0.5058, +0.4940, -0.6912, -0.4253, +0.0810, -0.3655, +0.1859, -0.0412, -0.0912, +0.0632, -0.2972, +0.0772, +0.0487, -0.0515, +0.1638, +0.3188, -0.1115, -0.2563, +0.4259, +0.2540, -0.0207, -0.0622, +0.0273, -0.6594, +0.2525, +0.5872, +0.0366, -0.1142, -0.2282, -0.1075, +0.8922, +0.1124, -1.6357, +0.2399, -0.0886, +0.1945, -0.2365, -1.6711, -0.5883, +0.4049, -0.0049, -0.5896, -0.0418],
-[ -0.4143, +0.1528, +0.4760, +0.1183, +0.0014, +0.2190, -0.0362, -0.8062, +0.3214, +0.1326, +0.2072, +0.1400, +0.4244, -0.3917, -0.8188, +0.4239, +0.1449, +0.2362, -0.5594, +0.6168, -0.3246, +0.3341, -0.5919, +0.0815, +0.4067, +0.1814, +0.4408, -0.4474, -0.2818, -0.0265, -0.1569, -0.4575, +0.4622, +0.2102, +0.1408, +0.1323, -0.2570, +0.1578, +0.1281, +0.2395, +0.0889, +0.0440, +0.3288, +0.3748, +0.0734, -0.1664, -0.5203, +0.0544, -0.0571, +0.2111, +0.2552, -0.6038, +0.4826, +0.0443, -0.2141, +0.4272, +0.2828, -0.6792, -0.6578, +0.3101, -0.0040, +0.2418, +0.1197, +0.0414],
-[ +0.5036, -0.0710, -0.5354, -0.0832, +0.5295, -0.3346, -0.6920, +0.2490, -0.0346, -0.6139, +0.5644, +0.5261, +0.0128, -0.5987, +0.3123, -0.3102, -0.2144, +0.1843, -0.5506, -0.1807, +0.1333, -0.2694, +0.2776, -0.3190, -0.1241, +0.2397, +0.0467, +0.1639, -0.0202, +0.2547, +0.2727, +0.2766, +0.1032, +0.2433, -0.2080, -0.1870, -0.1091, -1.2571, -0.5648, +0.3736, -0.6316, +0.2332, +0.3590, -0.0994, -0.1051, +0.2673, +0.0045, -0.0055, +0.2778, +0.3100, +0.5339, -0.3611, +0.0369, +0.0216, +0.3185, -0.8140, +0.3609, -0.6879, -0.6326, +0.0915, +0.1364, -0.1097, -0.2144, +0.2251],
-[ +0.5415, -0.3312, -0.7819, -0.5402, +0.0574, +0.2336, +0.0098, +0.3032, +0.2109, -0.1144, -0.3755, +0.1675, +0.6641, -0.6918, +0.2823, +0.3307, +0.0195, -0.2317, +0.0834, -0.3695, +0.7589, -0.1579, +0.1433, -0.4708, -0.5547, +0.0167, -0.5846, -0.4162, -0.0054, +0.4191, +0.0935, -0.3095, -0.0772, -0.5562, +0.0620, -0.8387, -0.4571, -0.2059, +0.4216, -0.4745, -0.3587, -0.0113, -0.4873, -0.3253, -0.2477, +0.2562, -0.1393, -0.2321, -0.3196, -0.0813, -0.1766, -0.5138, +0.1283, +0.0956, -0.0365, +0.1988, +0.1467, -0.0275, -0.0379, -0.0494, +0.0763, -0.0612, -0.4318, +0.2575],
-[ -0.2761, -0.9689, -0.3303, -0.7023, -0.4928, -0.3009, +0.0291, -0.4230, +0.5759, +0.0989, -0.8509, -0.1306, -0.0595, +0.1574, -0.0485, +0.5048, +0.3384, -0.1445, -0.2781, -0.4470, +0.0887, +0.2998, -0.0981, +0.6717, +0.0993, +0.1626, +0.2985, -0.0080, -0.0010, +0.0653, +0.2250, +0.6091, +0.1562, +0.1161, +0.5716, -0.2470, -0.4208, -0.5375, -1.1928, +0.1185, +0.8855, +0.3924, +0.0061, -0.1286, +0.2825, -0.3767, -0.3815, +0.1588, -0.6792, -1.0360, -0.1299, +0.4925, -0.0620, -0.7220, -0.7866, +0.1224, -0.1552, -1.0134, +0.5721, -0.7248, -1.0616, -0.5778, +0.3760, -0.2161],
-[ -0.5326, +0.7165, +0.0792, +0.2508, -0.2711, -0.2975, -0.0981, -0.0309, -0.0226, -0.1754, -0.0990, -0.1178, -0.5456, +0.1010, -0.3404, +0.0810, +0.4984, +0.2788, -0.3860, -0.1752, -0.6125, -1.2417, +0.4557, -0.4470, +0.4315, -0.0454, -0.2439, -0.9114, +0.6899, +0.5681, -0.3259, +0.4912, -1.0011, -0.4782, +0.8627, +0.3346, -0.4200, +0.6671, -0.4101, +0.2222, -0.2604, -1.1758, +0.5707, -0.5659, -0.1541, +0.0028, -0.6961, +0.1943, -1.2026, -0.3061, -0.2279, +0.1856, -0.3946, +0.2157, +0.4633, +0.1402, +0.2419, -0.6997, +0.2056, +0.6528, -0.4918, -0.0056, -0.3281, -0.0303],
-[ -0.2521, -0.4440, +0.2354, -0.8008, -0.7654, -0.9568, -0.3908, -0.1637, +0.1596, -0.2531, -0.0419, -0.0372, -0.3797, +0.1746, +0.3741, +0.0963, -0.5509, -0.7025, -0.3153, +0.2185, -0.5326, -0.9472, +0.2125, -0.0905, +0.1235, +0.0780, +0.2451, +0.1500, -0.6441, -0.8495, -0.1646, -0.7545, -0.2271, -0.2027, +0.0191, +0.1703, -0.4407, -0.9649, -0.0960, +0.1947, -0.7579, +0.0200, +0.1715, -0.8105, -0.3087, -0.0016, +0.1807, +0.2233, -0.3559, +0.1208, +0.6184, -0.3895, -0.0184, -0.0622, -0.2338, -0.2363, -0.9124, +0.1358, -0.5606, -1.4253, -0.1812, -0.2845, +0.1957, -0.0284],
-[ +0.2106, +0.1527, +0.0672, -0.4241, -0.5017, -0.5233, -0.2833, +0.0599, -0.2671, +0.2882, -0.0645, -0.3441, -0.0450, +0.3017, +0.5250, +0.0886, +0.1231, -0.3728, +0.3071, +0.0619, +0.3998, +0.4689, -0.4973, +0.0398, -0.0601, +0.0153, -0.6525, +0.3215, -0.3874, +0.0084, -0.9022, -0.6516, +0.0830, +0.1692, -0.2292, +0.1235, -1.1122, -0.0030, +0.4186, -0.2612, -0.8774, -0.6022, -0.1726, -0.3275, +0.1364, -1.1799, -0.0944, -0.1624, -0.3801, -0.0173, +0.1695, -0.3159, -0.1089, +0.2296, -0.4541, +0.0854, +0.3056, +0.2502, -0.1071, -0.1358, -0.6425, -0.2226, -0.5790, +0.0545],
-[ +0.1139, -0.3351, +0.4969, -0.1394, -0.1872, +0.1136, -0.5034, +0.4215, +0.0047, +0.3804, -0.2160, -0.2978, +0.0770, -0.1280, +0.0935, -0.1517, +0.2508, +0.0238, +0.2649, +0.1492, -0.2315, -0.1531, +0.3535, -0.3587, -0.0937, -0.0271, -0.1757, +0.0513, -0.3445, -0.1265, +0.0707, +0.3534, +0.3746, +0.1297, -0.4518, +0.1721, -0.1487, +0.1188, -0.0693, -0.3754, -0.0135, +0.3600, -0.5287, +0.0960, +0.3786, -0.4262, -0.2394, -0.2733, +0.5393, -0.0416, -0.6425, -0.1794, +0.2697, +0.0738, -0.0440, -0.4378, +0.2735, +0.0333, +0.0073, +0.4403, +0.1354, +0.2958, +0.1619, -0.1507],
-[ -0.5420, +0.0362, -0.4296, +0.0190, +0.2051, +0.3369, -0.3391, -0.1887, -0.0326, +0.3692, +0.0149, -0.3465, +0.6006, -0.4643, +0.0753, +0.4372, +0.2077, +0.1342, -0.8206, -0.0578, -0.2016, +0.2382, +0.6409, -0.0740, -0.2623, -0.1396, -0.0616, +0.2323, +0.0943, -0.1674, -0.4978, +0.8055, +0.3402, +0.2021, +0.1088, -0.1912, -0.0790, +0.3857, +0.3156, +0.3516, -0.0174, -0.2086, +0.1347, -0.0845, -0.3709, -0.3238, -0.8348, +0.1269, -0.0504, +0.3153, +0.2908, +0.2420, -0.0790, -0.2399, +0.1506, +0.1858, -0.1051, +0.0915, -0.1252, +0.1255, -0.0974, +0.5441, +0.0452, +0.3842],
-[ +0.0955, +0.0485, +0.3281, +0.0474, +0.3446, -0.6093, -0.4275, +0.3763, +0.3858, -0.1701, -0.1463, +0.2718, +0.2689, -0.3098, +0.0246, -0.4480, +0.0518, -0.1522, -0.8059, +0.2289, +0.1221, -0.3030, +0.1093, -0.1955, -0.0475, +0.0153, -0.3349, +0.1145, -0.8206, -0.0766, -0.1023, +0.2766, -0.0855, +0.0702, -1.0922, -0.3249, -0.5735, +0.0820, +0.3922, +0.2788, -0.0104, +0.0196, +0.0290, -0.1168, -0.3654, -0.3279, -0.0258, -0.2164, +0.0979, +0.1401, -0.9651, -0.2296, +0.0746, -0.2225, -0.2155, -0.7558, +0.2613, -0.0114, -0.8169, -0.1495, +0.2781, +0.3386, -0.9345, +0.2608],
-[ +0.5088, +0.2218, +0.1765, -0.0331, -0.3075, -0.2475, +0.5497, +0.1426, -0.1553, +0.3819, +0.2006, -0.0863, +0.1830, +0.1197, -0.0123, -0.3290, -0.1844, +0.4336, -0.0328, +0.1667, -0.1849, +0.0575, -0.6713, +0.0672, -0.3829, -0.6262, -0.1215, -0.1144, -0.2839, +0.1405, -0.3369, -0.2201, -0.4221, +0.3506, +0.1168, -0.0560, +0.5997, -0.4228, +0.1629, -0.4290, +0.1672, -0.0236, +0.1454, -0.6296, -0.3503, +0.3121, -0.6164, +0.0040, -0.4038, -0.0525, -0.3641, -0.0239, -0.0257, -0.0226, +0.0809, +0.6442, -0.4453, +0.2383, +0.2805, +0.0694, +0.0128, +0.3397, -0.3719, -0.2788],
-[ -0.4670, -0.4915, -0.0640, -0.1080, +0.2980, -0.3258, +0.1757, +0.2146, -0.1510, -0.0491, +0.0563, -0.3987, -0.4028, -0.3628, +0.2874, +0.0314, +0.1795, -0.2589, -0.0268, +0.2839, +0.1206, +0.2479, +0.4548, -0.3583, -0.0697, +0.2491, -0.0507, -0.4918, +0.8737, +0.1426, +0.0454, -0.1107, +0.2844, +0.1997, -0.3644, +0.0446, -0.0212, +0.1599, -0.3419, -0.6802, +0.0552, +0.2812, -0.3779, +0.1032, -0.3777, -0.3186, -0.3213, +0.4516, +0.0486, -0.0300, +0.5251, +0.2281, -0.6970, -0.8787, -0.2758, +0.0643, -0.0935, -0.0450, +0.3067, +0.1487, -0.2221, -0.7158, +0.0694, +0.3405],
-[ -0.0807, +0.1956, -0.7065, -0.1968, -0.4069, -0.5939, +0.1061, -0.5533, -0.0029, +0.1155, +0.5999, +0.2973, -0.1382, -1.8868, -0.0625, +0.1852, -0.3384, -0.3145, -0.7115, -1.2999, +0.2507, +0.0126, -0.6911, -0.0353, -0.2144, -0.5896, +0.2757, +0.1991, +0.4955, +0.1525, +0.0883, -0.3836, -0.5029, -0.9232, -0.0399, -1.1315, -0.3385, -0.4110, +0.6206, -0.0164, +0.0728, -0.1295, +0.3592, +0.1283, +0.1660, -0.8184, +0.2055, +0.0100, +0.0749, -0.1921, -0.7224, -0.3581, +0.3517, -0.5052, -0.1384, +0.2164, -1.1142, -0.2332, +0.1493, -1.4533, +0.0383, -0.1263, +0.3252, -0.5295],
-[ +0.4723, +0.0690, +0.0814, -0.3747, -0.8142, +0.2669, -0.1641, +0.3448, +0.2360, -0.1284, +0.2488, +0.1250, +0.1398, -0.3875, +0.1035, -1.5125, +0.2221, +0.4065, -0.2947, -0.0980, +0.3115, +0.0269, -0.1230, +0.3413, -0.1347, +0.1201, -0.6609, -0.1416, +0.3478, +0.0002, -0.0886, +0.5476, +0.3687, +0.6390, -0.7058, -1.8022, -0.5987, +0.1807, -0.4258, +0.6345, +0.3594, -0.1921, -0.3109, -0.3026, +0.1414, -0.2782, +0.1817, -0.4103, +0.1402, +0.4675, -0.5731, +0.0838, -0.2392, -0.6368, +0.0406, -0.2823, -0.0034, +0.2043, +0.1200, +0.0025, +0.1826, +0.0479, -0.0833, -2.2805],
-[ +0.2949, -0.1150, +0.1010, -0.3074, -0.9746, -0.6663, +0.0088, -0.2697, -0.3506, +0.0307, +0.1338, -0.5369, +0.0397, +0.3680, +0.1448, +0.2810, -0.6666, -0.0522, +0.2465, -0.0007, +0.1407, -0.3858, -0.1713, +0.2521, +0.3547, +0.0813, +0.1617, -0.2469, +0.1505, +0.0883, +0.1682, -0.1433, -0.5352, -0.4478, -0.2829, +0.1012, -0.1545, +0.2683, +0.0461, +0.2103, -0.7766, -0.9584, -0.3077, -1.1369, +0.2401, +0.3353, -0.6189, +0.1956, -0.1073, -0.4741, +0.0010, -0.6126, +0.0567, +0.4589, -0.3578, +0.2795, -0.2678, -0.2943, -0.5274, -0.0226, +0.0119, +0.2351, -0.2179, +0.2254],
-[ -0.2141, +0.1382, +0.4498, +0.6240, -0.3318, -0.7858, -0.0516, -0.4167, +0.1866, +0.2468, -0.3664, -0.8685, -0.0878, +0.1317, +0.1082, +0.4507, -0.2831, +0.1331, -0.0394, +0.0402, -0.2291, +0.3571, -0.3876, +0.0876, +0.4871, -0.8254, +0.2762, +0.0464, -0.3720, -1.0204, -0.2339, -0.3136, -0.3625, -0.3413, +0.1632, +0.5506, -0.3524, +0.3550, -0.4057, -0.4933, +0.3779, +0.0777, +0.0433, -0.1397, -0.3430, -0.0584, -0.1373, -0.0246, -0.6115, +0.3367, -0.2185, -0.0417, +0.4116, +0.2236, -0.0797, -0.0377, -0.7056, +0.2603, +0.0040, -0.0374, -0.2992, +0.1517, -0.6489, +0.0531],
-[ -0.1267, -0.5069, +0.2074, -0.2553, -0.4368, -0.4911, +0.3021, -0.2026, -0.3328, -0.5599, -0.4192, -0.1039, +0.2192, -0.3493, +0.4454, -0.0429, +0.2264, +0.2224, +0.4339, -0.4501, -0.0765, -1.2330, +0.3052, -0.5080, -0.0426, -0.0030, -0.6783, +0.0537, -0.1739, +0.2823, +0.4150, -0.3388, -0.1453, +0.3024, -0.1280, +0.1714, -0.3645, -0.0861, -0.4287, +0.2726, -0.8224, +0.2332, +0.0662, -0.2844, -0.1834, +0.2771, +0.0497, -0.3258, -0.6752, +0.2520, +0.3726, +0.7169, +0.1558, -0.5803, -0.2885, -0.3842, -0.3185, +0.3158, +0.1080, +0.1682, +0.0620, +0.3014, -0.1028, +0.1426],
-[ -0.0723, -0.5000, +0.1487, -0.0095, -0.4658, -0.3077, -0.7908, -0.4927, -0.5117, -0.3589, -0.9917, +0.5179, +0.2535, -0.7080, -0.2462, +0.0268, -0.3043, +0.4264, +0.0668, -0.1914, +0.2648, -0.3950, +0.3762, -0.4192, +0.2441, +0.1355, -0.7419, -0.6720, +0.1731, +0.1542, -0.3981, +0.3598, +0.0109, -0.2058, +0.0691, -1.2895, -0.1651, +0.1311, +0.4099, +0.2998, +0.3317, +0.2282, +0.5977, +0.0649, -0.0173, -0.4743, +0.1518, -0.3689, -0.6426, -0.4369, -0.7365, -0.6539, -0.0260, +0.0977, -0.0872, -0.7097, +0.2004, -0.3222, -0.3049, -0.1635, +0.1556, +0.1445, -0.2192, -0.1735],
-[ -0.8152, -0.2915, -0.2327, -0.2137, -0.1635, +0.2767, -0.0897, +0.0506, +0.3301, -0.6531, -0.1230, +0.2334, -1.0137, +0.4155, -0.2141, -0.3039, +0.1495, +0.2163, +0.2163, -0.0377, +0.0263, +0.2615, -0.2307, +0.6041, -0.0230, +0.2658, -0.3772, -0.7199, +0.1255, -0.3156, +0.5027, +0.0295, -0.0046, +0.0743, +0.1850, +0.2075, -0.5971, -0.3057, +0.0794, -0.3854, +0.0672, +0.2752, +0.5847, +0.5027, -0.6998, +0.3995, -0.0344, -0.5871, -0.4606, -0.6819, +0.4443, -0.6050, +0.0125, -0.0160, +0.0141, -0.2969, +0.0984, -0.2110, +0.1360, -0.0030, -0.2199, -0.2806, -0.4028, -0.2105],
-[ +0.0086, +0.2366, -0.2388, -0.7499, +0.3473, -0.3351, +0.4687, -0.6588, +0.3916, -0.8119, -0.5929, +0.2525, -0.7352, -0.2726, +0.2062, +0.0520, +0.3612, -1.1951, +0.2574, -0.5112, -0.1439, +0.1617, +0.1917, -1.9899, -0.1703, +0.3676, +0.2320, -0.0203, -0.4018, +0.3225, +0.0675, -0.5493, -0.1561, +0.2205, +0.1122, -0.8326, -0.9873, -0.2357, +0.6072, +0.3998, +0.0549, -0.2751, +0.0890, -0.3323, +0.0969, -0.1550, +0.3064, +0.4299, +0.1660, -0.1824, +0.2009, -0.3313, -0.0823, -0.2167, -0.1848, +0.2666, +0.2336, -0.1165, -0.3577, -0.6992, +0.3805, -0.4676, +0.1645, +0.1216],
-[ -0.5994, +0.2128, -0.4627, +0.0702, +0.3855, +0.1554, -0.0293, +0.3617, +0.3152, -0.1431, +0.4439, +0.2291, -0.1586, -0.0755, -0.4190, -0.3665, -0.0843, +0.0891, -0.2107, +0.1810, +0.1604, +0.1431, +0.3822, -0.2960, +0.0394, +0.2106, -0.3115, +0.0588, -0.0221, +0.2901, +0.2319, +0.0913, +0.0881, +0.1558, +0.2094, -0.5158, -0.0340, +0.0142, +0.1323, +0.2055, -0.3577, +0.3536, +0.0224, +0.0234, +0.0999, +0.3119, +0.0797, -0.4424, -0.2596, +0.1601, -0.2896, -0.6153, +0.1903, -0.0908, +0.1287, +0.0787, +0.1265, -0.8994, -0.5396, -0.0339, +0.2975, -0.2216, +0.1704, -0.1286],
-[ -0.0142, +0.2379, -0.1136, -0.0227, +0.0428, +0.2032, -0.2604, -0.5311, +0.0952, +0.2859, +0.2672, -0.3840, +0.2569, -0.5696, +0.0714, -0.2037, +0.3220, +0.2425, -0.1276, -0.7212, +0.2417, -0.0748, +0.2104, -0.1355, -0.2372, +0.0144, +0.4330, -0.0108, -0.7008, +0.1504, -0.4478, -0.3534, -0.0906, +0.0781, +0.0750, +0.3150, +0.0884, +0.5228, +0.0073, +0.1359, +0.2701, -0.2142, -0.2422, -0.4849, +0.2584, -0.1368, -0.1542, +0.3142, +0.1448, +0.0291, +0.1900, -0.3429, -1.3660, -0.1068, -0.0261, +0.0589, +0.3062, +0.1114, -0.3424, -0.0476, -0.0689, -0.0977, +0.6588, +0.1288],
-[ +0.1364, -0.1144, +0.1574, -0.3419, +0.1935, -0.0943, +0.2272, -0.1504, +0.3254, +0.3180, -0.3487, +0.5566, -0.9484, -0.0958, +0.1641, -0.5995, -0.2025, -0.2777, +0.0415, -0.1855, -0.1811, -0.1807, +0.1249, -0.1251, -0.1046, -0.2293, +0.3936, -0.1513, +0.0573, +0.0934, -0.0753, -0.0327, +0.0111, -0.0191, -0.4537, +0.2813, +0.2061, -0.0505, +0.0374, -0.0946, +0.3502, +0.0734, -1.0019, -1.0110, +0.3520, -0.3134, -0.0215, -0.2545, +0.1434, -0.5697, -0.7286, -0.4365, -1.6550, +0.0742, -0.7167, -0.1912, -1.1841, +0.0912, -0.6878, -0.3645, +0.2087, +0.5016, -0.1441, +0.1419],
-[ -0.1610, -0.7360, +0.1001, -0.5159, -0.1114, -1.3956, -0.4303, -0.1506, +0.0529, +0.1836, +0.2128, -0.3067, +0.0156, +0.1256, -0.0579, -0.0213, -0.0353, -0.3984, -0.5750, -0.3961, +0.4362, -0.0910, +0.2649, +0.1807, -1.0079, -0.6953, -0.4110, -0.0544, -0.1440, -0.0898, +0.3983, +0.0142, +0.3467, +0.0764, +0.5826, -1.0772, +0.1329, +0.1583, +0.4074, -0.4069, -0.2080, +0.0637, -0.2797, +0.1188, -0.0272, +0.0528, -0.1775, +0.1708, -0.1801, +0.3543, +0.1264, -0.8590, -0.4402, -0.3558, +0.3612, -0.3962, +0.1641, +0.2552, -0.6210, -0.3405, -1.3635, -0.3804, -0.0130, -0.2085],
-[ -0.3926, -0.4244, -0.8905, -0.1961, -0.1443, -0.9498, -0.3382, -0.8519, -0.6429, -0.2444, -0.1375, -0.5616, +0.4198, -0.5713, -0.2244, -0.1486, -0.1400, -0.2307, -0.0475, -0.2259, +0.1446, +0.2832, -1.2677, -0.6729, +0.6527, +0.4285, -0.5992, +0.0715, -0.6911, -0.4754, -0.9201, -0.4254, -0.7185, +0.0664, -0.4074, -0.4005, -0.1831, +0.2600, -0.4282, -0.1873, -1.4707, +0.5088, -0.4531, -0.0573, +0.4479, -0.3896, -1.3122, -0.2406, -0.7760, -0.0552, -0.1311, +0.2692, -0.2829, -0.2300, -0.9993, +0.2252, +0.6695, +0.0364, -0.1045, +0.0466, -0.8347, -0.3719, +0.2533, +0.1563],
-[ -0.2412, +0.3157, -0.0911, -0.9888, +0.6987, +0.2569, -0.2099, -0.1531, -0.3486, -0.3566, -0.1593, -0.0828, -1.2565, -0.1513, -0.1533, -0.0785, -0.5587, +0.3774, +0.5322, +0.0573, -0.3218, -0.0546, -0.1710, +0.2196, -0.1172, +0.2556, +0.2856, -0.2720, +0.0261, +0.2103, +0.0640, -0.0452, -0.2239, -0.0712, +1.1437, -0.7186, -0.2894, +0.5009, +0.1654, +0.1889, +0.5348, -0.2929, +0.3507, +0.1541, -0.2035, -0.4617, +0.2521, +0.2938, +0.0196, +0.1961, -0.5070, +0.5579, -0.1937, +0.0963, +0.1044, -0.1526, +0.7057, -0.7649, -0.1567, -0.0077, -0.2938, +0.1193, -0.1897, -0.1215],
-[ +0.3582, +0.0938, -0.0087, +0.2090, -0.9981, +0.3406, +0.2442, +0.2977, +0.0398, -0.1321, +0.1777, -1.1774, +0.5394, -0.2764, -0.0729, +0.1203, -0.0837, +0.1776, -0.1322, +0.3963, +0.0025, +0.0991, -0.0755, -0.3995, +0.1701, +0.1077, -0.0413, -0.4130, +0.0422, +0.2433, +0.0258, -0.1082, -0.1366, +0.0227, +0.0329, -0.1431, +0.0231, -0.2993, -0.0951, -0.0591, -0.0835, +0.0814, +0.0316, -0.3648, +0.4959, +0.4102, +0.2490, -0.3487, +0.2844, +0.3580, -0.2262, -0.2718, +0.0704, +0.0435, +0.1235, +0.8514, -0.3005, -0.6121, -0.0672, -1.0684, +0.2366, +0.1307, +0.2148, -0.4796],
-[ +0.8412, +0.5887, -0.4191, +0.0875, -0.4845, +0.6013, +0.5707, +0.3917, -0.0227, +0.4339, -1.0224, -0.7570, +0.3608, -0.2532, +0.1064, +0.6448, -0.2207, -1.2217, +0.1895, -0.0188, +0.3665, -0.4125, -0.2246, -0.3406, -0.3777, +0.1114, +0.0960, -1.4468, +0.2017, -0.1103, -0.5602, -0.0740, -0.1705, -0.0307, +0.6227, +0.5056, +0.0644, -0.3713, +0.2553, -0.0499, -0.1112, -0.3409, +0.2212, +0.5274, +0.1242, -0.0929, +0.5207, -0.3954, +0.2206, +0.6032, -0.1240, -0.3202, +0.5229, -0.3248, -0.2238, +0.0788, +0.1125, -1.5450, -0.2782, -0.3103, +0.4263, +0.5339, -0.4021, -0.0213],
-[ -0.1685, +0.2132, +0.2234, +0.1307, -0.4110, -0.3189, -0.4531, +0.1865, -0.0200, -0.0282, +0.5585, -0.4741, -0.0928, -0.1840, -0.4882, +0.0903, +0.2165, -0.3946, +0.1760, +0.4589, -0.1230, +0.2934, +0.0979, +0.1098, +0.2834, +0.4592, -0.6382, +0.1312, -0.7111, -0.3250, +0.0696, -0.2336, -0.1130, -0.1304, +0.4843, +0.3157, -0.8460, -0.0586, +0.4201, -0.3655, +0.0920, +0.6134, +0.3466, +0.2227, -0.4758, -0.0722, +0.0661, -0.9082, -0.1224, +0.4001, -0.6238, +0.0766, +0.4568, +0.8708, +0.3388, -0.4030, -0.1210, +0.0577, -0.0684, +0.1317, +0.0379, -0.7594, -0.8605, +0.1362],
-[ +0.3891, -0.0004, +0.0555, -0.1140, -0.3759, +0.1374, +0.3610, +0.0419, -0.3176, +0.3248, +0.2752, +0.0961, +0.4376, +0.2473, +0.0575, +0.2554, -0.7989, +0.5068, -0.1314, -0.2717, -0.3923, +0.1135, -0.3779, +0.1417, -0.0900, -0.5626, +0.0551, -0.1210, -0.0790, -0.1690, -0.5073, -0.6554, -0.4579, -0.0294, +0.2184, +0.3044, +0.3497, -0.7188, -0.2664, -0.7073, +0.2607, -0.2781, +0.4217, -0.8461, -0.1371, +0.2458, +0.1470, -0.0571, +0.3661, +0.1540, +0.0704, -0.1645, -0.1654, +0.2660, -0.1874, +0.7393, -0.3254, +0.3798, +0.0534, -0.3681, -0.4176, +0.4060, -0.2834, -0.0005],
-[ -0.0320, +0.0778, -0.0580, +0.5162, -0.3992, -0.2747, +0.3408, +0.2020, -0.1224, -0.8774, +0.2791, -0.7213, -0.6805, +0.3189, -0.0929, +0.0764, +0.4005, -0.1066, -0.1712, -0.7954, +0.0733, +0.2352, -0.1182, +0.1373, +0.3099, +0.0808, -0.5416, +1.1081, -0.5261, -0.2217, -0.0330, -0.1539, +0.2503, +0.5595, -0.2014, +0.1417, +0.2703, -0.1015, +0.8298, -0.3646, +0.1370, +0.2641, +0.2149, +0.1676, -0.4836, -0.0130, -1.0195, +0.0247, -0.0851, -0.9918, -0.0406, +0.0383, -0.0550, +0.4607, +0.2914, +0.1750, +0.2401, +0.3667, -1.1202, -0.3222, -0.0731, -0.0615, -0.3787, +0.4553],
-[ -0.4131, -0.5941, -0.6169, -0.6164, -0.4406, -0.3381, -0.1022, -0.0502, -0.0368, +0.4848, -0.4012, -0.1352, -0.2898, -0.0027, +0.1197, +0.2204, +0.1906, -0.7479, -0.4403, +0.1008, -0.3108, -0.3402, +0.4565, -1.1084, +0.1237, -0.2884, +0.0959, -0.1072, -0.5372, +0.1698, +0.1137, -0.1729, +0.5687, -0.0171, -0.5504, +0.5379, -0.0916, +0.3523, +0.1967, -0.8104, -0.2025, +0.3720, -0.5468, -0.4242, -0.1023, -0.2784, +0.1138, +0.1413, +0.7391, -0.3176, +0.4443, -0.2557, +0.1129, -0.3916, -0.7132, +0.2897, -0.1364, +0.4325, -0.6139, -0.3159, +0.0334, +0.3121, -0.0236, -0.6013],
-[ +0.3438, -0.2672, -0.2729, -0.8516, -0.7865, +0.2380, -0.2967, -0.1444, -0.1531, +0.4419, +0.0100, -0.5118, +0.0695, -0.6206, +0.0933, +0.3544, +0.5651, -0.2669, -0.5611, -0.1266, -0.1960, +0.2097, +0.5543, +0.2757, -0.2284, -1.5897, +0.0603, +0.2600, -0.0583, +0.0183, -0.1176, +0.2799, -0.0466, +0.1799, -0.1208, +0.1377, +0.1683, -0.3353, -0.5734, -0.5524, -0.5980, +0.1921, +0.2213, -0.5839, +0.0293, -0.6613, -0.6761, +0.0707, -0.3450, -0.1691, -0.2508, -0.2959, +0.2573, -0.0742, -0.3314, +0.0760, +0.5143, -0.5326, +0.1858, +0.0744, +0.3574, +0.2932, -0.6550, -0.1763],
-[ -0.1878, +0.3530, +0.2846, -0.4720, -0.6593, +0.2894, +0.1681, +0.1220, +0.3990, -0.5962, +0.3605, -0.2635, +0.0589, -0.0482, -0.3337, +0.0602, +0.1452, -0.1377, +0.1189, +0.7641, +0.2783, +0.3026, -0.2819, +0.1425, +0.4815, -0.0261, -0.6602, +0.2245, +0.1700, -1.0549, +0.3293, -0.0214, -0.2830, +0.2202, +0.1940, +0.3953, -0.5394, -0.2268, -0.0700, -0.5736, +0.0992, +0.3600, +0.1267, +0.3211, -0.5622, -0.1395, -0.2889, -0.1606, +0.0129, +0.4565, -0.0817, -0.3216, +0.0586, -0.3770, +0.1933, +0.5314, -0.2282, +0.5116, -0.3646, -0.0844, -0.1667, +0.2177, -0.4722, +0.1682],
-[ -0.6046, -0.0019, +0.7055, +0.0671, -0.5065, -0.8512, -0.0155, -0.0531, +0.1195, -0.4814, -1.2434, -0.3227, +0.3413, -0.8682, -0.8491, +0.6140, +0.2121, +0.0350, -0.3647, +0.6926, +0.0886, -0.5127, +0.5188, -1.3790, -0.6758, -1.0013, +0.3871, +0.3379, -0.2159, +0.0706, +0.5615, +0.7641, -0.0087, +0.0456, +0.4031, -0.1160, +0.5081, -0.1776, -0.3154, +0.2156, +0.5289, -0.0052, -0.2746, +0.2361, -0.7520, -0.1301, +0.3298, -0.1321, +0.4440, -0.6782, -0.2450, -0.2377, -0.1662, -0.1527, +0.1268, -0.2387, +0.8365, -0.9122, -0.1251, -0.1620, -0.0842, +0.3611, -0.2000, +0.5543],
-[ -0.3054, -0.1114, -0.2290, +0.4891, -0.7619, -0.0520, -0.3236, -0.6297, +0.3625, -0.1399, -0.2639, -0.1181, +0.0798, -0.3294, -0.2301, +0.1280, +0.3002, +1.0975, -0.2288, -0.0913, -0.9323, -0.1649, +0.3137, -0.1293, +0.2304, +0.2064, -0.4795, -0.1544, -0.0805, -0.1257, -0.1547, +0.1534, -0.4968, -0.5140, -0.0610, +0.5317, -0.6079, +0.2771, +0.2970, -0.1766, -0.4933, -0.0424, +0.7516, -0.4173, -1.1842, +0.3461, -0.0435, +0.1062, -0.8075, -0.5636, +0.7547, +0.0459, -0.3499, +0.1656, -0.4118, -0.5384, -0.4461, -0.0754, -0.0632, -0.2161, -0.3203, +0.0456, +0.0656, -0.2893],
-[ +0.0842, +0.2350, -0.2874, -0.7300, -0.3664, +0.3465, +0.1789, +0.2259, +0.0675, -0.2017, +0.2220, +0.0256, +0.3503, +0.5651, +0.0252, +0.0729, -0.0869, -0.1370, -0.2466, +0.0226, -0.2938, -0.2426, -0.4704, +0.0995, +0.1053, +0.4180, +0.2697, +0.1746, +0.2504, -0.3138, -0.4582, -0.6039, -0.1333, +0.0827, -0.1264, +0.3337, -0.4454, -0.5489, -0.3235, -0.3897, -0.2475, -0.1961, +0.1282, -0.4765, -0.3531, +0.3029, +0.5360, +0.0134, -0.0629, +0.3819, +0.1028, -0.2920, -0.3325, +0.0562, -0.1956, +0.1254, -0.6301, +0.3737, -0.1224, -0.8364, -0.5796, +0.2944, -0.1286, -0.4786],
-[ +0.2911, -0.2918, -0.2983, -0.1799, +0.5004, +0.1641, -1.8806, +0.2665, +0.2884, -1.0550, +0.6388, +0.1462, +0.1680, -0.0982, -0.0077, -0.0693, -0.3434, +0.2433, +0.3355, -0.1851, +0.0465, +0.1885, +0.2110, -0.2517, -0.3897, -0.4081, +0.1757, -0.3554, +0.5196, +0.3916, -0.0051, +0.2256, -0.0817, +0.3246, +0.0079, -1.0587, +0.0605, -0.2847, +0.1970, +0.4176, +0.2595, -0.6440, -0.2987, -0.0802, -0.0082, +0.0894, +0.2301, +0.1005, +0.0890, +0.0689, +0.3122, -0.3237, -0.6040, +0.0348, -0.5192, -0.2683, +0.4273, -0.0652, -0.1506, -0.2352, +0.0493, +0.0534, +0.2133, +0.0982],
-[ +0.3272, +0.1324, +0.0023, -0.2772, -1.0236, +0.0239, -0.2064, +0.0468, -0.2204, +0.2162, -0.1171, -0.3942, +0.2313, -0.0039, +0.0945, -0.2131, +0.2256, +0.7016, -0.0260, +0.1757, -0.0407, +0.3079, -0.3533, +0.2725, +0.5806, +0.5924, -0.3883, -0.1294, -0.1834, +0.1339, -0.1177, -0.2016, +0.1945, -0.3999, -0.2208, +0.2980, -0.0075, +0.0909, +0.0309, -0.7034, +0.3555, -0.0051, -0.2755, +0.0161, +0.5550, -0.4416, +0.1154, +0.2074, -0.2569, -0.4099, -1.0087, -0.3479, +0.4183, -0.0786, -0.1718, +0.1801, -0.0383, -0.1651, -0.2073, +0.4251, +0.1538, -0.1537, +0.3422, -0.5363],
-[ -0.0005, -0.0823, -0.4054, -0.4387, -0.9801, -0.7941, -0.6260, -0.2934, +0.2604, -0.4400, +0.4142, +0.2642, +0.2926, -0.0690, +0.2422, -0.0340, +0.1123, -0.5302, -0.3629, +0.0005, -0.2184, -0.9489, +0.2292, +0.4085, +0.1849, +0.4804, -0.1979, +0.4252, -0.0989, -0.5815, -0.1266, -0.0716, +0.2599, +0.2402, -0.1451, -0.1020, -0.4833, -0.0605, +0.2253, -0.3367, -1.1238, -0.3284, -0.0642, -0.2709, +0.0412, -0.0656, +0.2200, +0.3204, +0.0376, +0.2544, -0.0845, -0.7557, -0.1007, -0.0697, -0.3928, -0.0440, -0.3349, -0.1664, +0.1248, -0.1058, -0.1661, -0.5682, -0.1187, -0.4495],
-[ +0.3877, +0.1701, +0.2470, +0.3815, -0.7099, +0.4480, -0.3912, +0.0509, +0.3866, +0.0605, -0.1034, -1.1513, -0.0388, +0.1839, -0.0730, +0.2069, +0.1406, -0.2765, +0.0556, +0.3360, +0.3587, +0.2648, -0.1238, -0.1401, -0.1359, -0.1055, +0.1128, +0.1099, +0.0895, -0.2581, -0.3244, -0.2875, -0.0157, +0.3111, -0.3051, +0.1191, -0.2008, +0.0276, +0.4500, -0.3447, -1.8635, -0.0225, -0.0287, -0.1122, -0.3062, +0.0934, +0.0968, -0.0839, +0.1880, +0.3712, -0.1919, +0.3895, -0.4872, -0.2177, -0.0260, +0.5779, +0.1781, +0.4362, +0.3131, -0.8176, +0.2263, -0.5366, -0.3734, -0.2069],
-[ -1.1235, -0.9674, -0.0259, +0.2390, -0.2322, -0.4858, -0.0673, -0.0436, +0.4784, -0.5001, -0.1335, -0.0299, -0.1177, +0.5094, -0.0886, -0.6063, -0.8532, +0.0729, +0.2496, -0.1499, -0.6113, +0.1188, +0.1059, +0.1600, +0.0897, -0.1650, +0.7303, -0.6695, +0.0782, +0.4738, -0.0097, +0.4754, +0.1041, -0.5552, -0.1545, +0.1880, -0.0279, -0.6501, -0.4160, -0.1361, -0.0866, -0.3986, +0.0944, +0.2977, -0.1807, +0.2639, +0.4842, +0.6219, +0.3545, -0.1240, +0.1304, +0.2634, -0.0749, -0.1111, -0.1349, -0.0482, -0.3663, -0.2051, +0.1262, +0.0840, +0.2020, -1.6679, +0.1338, -0.0481],
-[ -0.0692, -1.0423, -0.6125, -0.4597, +0.0297, -0.4761, -0.4631, -0.3290, -0.2766, +0.0555, +0.3061, -0.1475, -0.8444, -0.3880, +0.2820, -0.4371, -0.0310, -0.8606, -0.9039, +0.0020, -0.0050, +0.0948, +0.2473, -0.7799, -0.3398, -0.6164, -0.5401, -0.4733, -0.4821, +0.4097, -0.5277, -0.2846, +0.0884, -0.2126, -0.0294, +0.0071, +0.0244, +0.2756, -1.3022, +0.1808, -0.1945, -1.1679, -0.4115, -0.1681, +0.4425, -0.0881, -0.1101, +0.2275, +0.1305, -0.2721, -0.1444, -1.7055, -0.4794, +0.2592, +0.0446, -0.0600, +0.2102, -0.1754, +0.0657, -0.2513, -0.1904, +0.1755, +0.3229, -0.0288],
-[ +0.5168, -0.4403, +0.1617, -0.0585, -0.1969, -0.4617, -0.4481, -0.5496, +0.5089, -0.7188, -0.1878, -0.1813, -0.2418, -0.0046, +0.3130, -1.7845, +0.0638, -1.0377, -0.0172, -0.2044, -0.3992, -0.5402, -0.5061, +0.3127, +0.3964, +0.1543, +0.1298, +0.1039, +0.0507, +0.1353, -0.5773, -0.3090, +0.3562, +0.6026, -0.3442, +0.3625, -0.6769, -0.1507, +0.1097, -0.3716, +0.0978, +0.0150, -0.0408, -0.0370, +0.4052, -0.0185, +0.2788, -0.1076, -0.2841, +0.0922, +0.1425, -0.2230, -0.8524, +0.0620, -0.5464, -0.1797, +0.1239, +0.0314, +0.2159, -0.6538, -0.0031, -0.7640, -0.0217, -0.4866],
-[ +0.2358, -0.2772, +0.2595, +0.6524, +0.3488, +0.0607, +0.1904, +0.1577, +0.0482, +0.1901, -0.1420, -0.2318, +0.0705, +0.7032, +0.1648, -0.1761, -0.3265, -0.1246, -0.2734, +0.1199, -0.5026, +0.2313, -0.3349, +0.0078, -0.0800, -0.2408, +0.1623, -0.3919, +0.3836, -0.0706, -0.6569, -0.6874, -0.2303, -0.1488, -0.2527, +0.1399, -0.0429, -0.8683, +0.0116, -0.2729, +0.1803, -0.3104, -0.0248, -0.2009, -0.3645, +0.8482, +0.2003, +0.1095, -0.2804, +0.1855, +0.0342, -0.5573, -0.9607, +0.4382, +0.2139, +0.0982, +0.0443, +0.1411, +0.0551, -0.1386, -1.3499, +0.2195, -0.0387, -0.1416],
-[ -0.0189, -0.4482, -0.0687, -0.4171, -1.1698, +0.0934, -0.2861, -0.1069, +0.2478, -0.2631, -0.6573, +0.4906, +0.3018, -0.2749, -0.8819, -0.4961, -0.1743, +0.3760, -1.2279, +0.2292, +0.2814, -0.0434, -0.4484, -0.1545, +0.3929, +0.0769, -0.0394, -0.0692, -0.3811, -0.1864, +0.0444, -0.2080, -0.1870, -0.1867, +0.2350, -0.7152, -0.1055, +0.0963, -1.0288, +0.0322, +0.2215, -0.4954, +0.3377, -0.1467, +0.0027, -0.0491, -0.3208, -0.8264, -0.2718, -0.2542, +0.0741, -0.2323, -0.1001, -1.0198, -0.2890, -0.1343, -0.2319, -0.4908, +0.3050, -0.0255, +0.0115, -0.0030, -0.2358, -0.4015],
-[ -0.1719, -0.4269, +0.5157, -0.3660, +0.0783, -0.2254, -0.7160, +0.3215, +0.4847, -0.6721, -0.1024, +0.0750, -0.4257, +0.0658, +0.1847, +0.2579, +0.1711, +0.1768, +0.0540, +0.0076, -0.0497, +0.0019, -0.3865, +0.1233, +0.1422, +0.4548, +0.1440, -0.4759, -1.1967, +0.2683, +0.1576, -0.0557, -0.8877, +0.3377, -1.0919, -0.1791, -1.1117, +0.2514, -0.5695, +0.2673, -0.7146, +0.1625, -1.1816, -0.2575, +0.2272, -0.9284, -0.4375, -0.2500, -0.5735, +0.1477, -0.2161, -0.1063, -1.0993, +0.2553, -0.0129, +0.3550, -0.4742, +0.1937, -0.5110, -0.4952, +0.3438, +0.0144, -0.0949, -0.1458],
-[ +0.0636, +0.2933, -0.1864, -0.4025, -1.0270, -0.2597, -0.0660, -0.2247, -0.0048, -0.6861, +0.1695, +0.1418, +0.1761, +0.2443, -0.1339, -0.1673, +0.0148, +0.0555, -0.2577, -0.2610, -0.4787, -0.4025, +0.3526, +0.0557, -0.3496, +0.5078, -0.8030, +0.4197, +0.2154, -0.6415, -0.3827, -0.1026, -0.0396, +0.0502, +0.0724, -0.2952, +0.4268, -0.0801, +0.2876, -0.1107, +0.4451, -0.2080, +0.3860, -0.4921, -0.1323, -0.8016, -0.3088, +0.2469, -0.0782, -0.1180, +0.0223, +0.0847, -0.0293, -0.6148, -0.1082, -0.2367, -0.6443, +0.0539, +0.0207, -0.1587, -0.1582, +0.1998, -0.4013, +0.2739],
-[ +0.0038, +0.1245, -0.3433, -0.4856, -0.4741, +0.4551, +0.5898, -0.1498, +0.2642, +0.3023, +0.1732, -1.0681, -0.1445, +0.1467, +0.0002, -0.1426, -0.9189, +0.1320, +0.0581, +0.0967, -0.0914, +0.0801, +0.0305, +0.0327, +0.0905, -1.0551, +0.1300, -0.7099, +0.2902, +0.1220, -0.1958, +0.0704, -1.2429, -0.1132, -0.2477, +0.2343, -0.2246, -0.5217, -0.1491, -0.4591, +0.3662, -0.3556, -0.6157, -0.8142, -0.1378, +0.1513, +0.2413, -0.0337, +0.6665, -0.2057, +0.1610, -0.1389, -0.5894, +0.0005, +0.0621, +0.6012, -0.1235, +0.5874, -0.5528, -0.2310, -0.1762, +0.1297, -0.1719, +0.0325],
-[ +0.0008, +0.2486, +0.3471, -0.6321, +0.3799, -0.0780, -0.0376, +0.0776, +0.2057, -0.6391, +0.1711, -0.0638, +0.0299, +0.1975, -0.0466, -0.0290, -0.0443, +0.0426, -0.3097, +0.0908, +0.1078, -0.3136, -0.0517, -0.0219, -0.3360, +0.3552, +0.2264, -0.8491, +0.1069, +0.0375, +0.1422, -0.0855, -0.4314, +0.1987, -0.7457, -0.4619, -0.2737, +0.4460, +0.0367, -0.0661, +0.1025, +0.4836, +0.1807, +0.0178, -0.7587, -0.1794, -0.1558, -0.3419, -0.4544, -0.3955, +0.2712, -0.4674, -1.1360, +0.0936, -0.1987, -0.1250, -0.3655, -0.0430, -0.1751, +0.2196, +0.0193, +0.1743, -0.4942, +0.3843],
-[ +0.1284, -0.8808, +0.3882, -0.1527, -0.0198, +0.0071, -0.1231, -0.0403, -0.3053, +0.7561, -0.8750, -0.7770, +0.2674, -0.1818, +0.0836, +0.1696, +0.1877, -0.2631, -0.7180, -0.1721, -0.3764, +0.5574, +0.3879, -1.7586, +0.1584, +0.0229, -0.2597, -0.2745, -0.0041, -0.7704, +0.2686, -0.6262, +0.2735, +0.2018, -0.1796, +0.2239, +0.4402, +0.2529, -0.5100, -0.0231, -0.2497, -0.2817, -0.1345, -0.3458, -0.2159, +0.2782, -0.1067, -0.4089, -0.1312, +0.1312, +0.2225, +0.5538, -0.0014, -0.2335, -0.2113, +0.3140, -0.2814, -1.0457, +0.2956, -0.0813, -0.0878, -0.2742, -0.2099, -0.1060],
-[ +0.0774, -0.7316, +0.2640, +0.2897, +0.0154, -0.2817, -0.2962, -0.2956, -0.2675, -0.0654, +0.2018, -0.3843, +0.1061, +0.3959, -0.1483, -0.3143, -0.0607, -0.0341, -0.9169, +0.0874, -0.4429, -0.4101, -0.2229, -0.0070, -0.2998, -0.5374, -0.1129, -0.5779, -0.0182, -0.0070, +0.0043, -0.6822, -0.7798, +0.1554, -0.0940, +0.1911, +0.5163, -0.1492, +0.3483, -0.5709, +0.0793, +0.2243, +0.4628, +0.3321, -0.4983, -0.0078, +0.0161, -0.0902, +0.1897, -0.1736, +0.2867, -0.3187, -0.8528, +0.5943, -0.6071, -0.3823, -0.2354, +0.0569, +0.0469, -0.0745, +0.0970, +0.3657, -0.8127, +0.1084],
-[ -0.0145, -0.5299, +0.2584, -0.1679, -0.5984, -0.9276, +0.2116, +0.3666, -0.3246, -0.1920, -0.4188, -0.4159, +0.5277, -0.6807, +0.1607, +0.1703, -0.5065, -0.0285, -0.0377, +0.3741, -0.5164, +0.1889, -0.1941, -0.1753, -0.2329, -1.3540, -0.3580, +0.7976, +0.3418, -0.3402, -0.5864, -0.2918, -0.3103, -0.8543, -0.4453, -0.5695, -0.3897, -0.2154, -0.7735, +0.3474, -0.4120, +0.5434, +0.5985, -0.4188, -0.6688, +0.0221, -0.3335, +0.0823, -0.9285, +0.5000, -0.5239, -0.1289, +0.1898, -0.0251, -0.4911, -0.1460, +0.3242, +0.5531, -0.2855, -0.0153, +0.3504, -0.7660, -0.5513, +0.5004],
-[ +0.0273, -1.1660, -0.4373, -0.0665, +0.1115, +0.1340, -0.1542, -1.0896, -0.0308, -0.6965, -0.4566, +0.4433, -0.4034, -0.5017, +0.2259, -0.9126, -0.8050, +0.1053, -0.1586, -0.5198, +0.0862, -0.6760, -1.0836, +0.1359, -0.2969, -0.5577, +0.0696, -0.4491, -0.2396, +0.1705, -0.4238, -0.4414, +0.2904, -1.1770, -0.2532, +0.2228, +0.2173, -0.0848, -0.0284, +0.1148, +0.2002, -0.8461, -0.4833, -0.2364, +0.4290, -0.0140, -0.2397, +0.0003, -0.2664, -0.8921, +0.4706, +0.2010, -0.4245, +0.2278, -0.1853, +0.3507, -0.4354, -0.1236, +0.2643, +0.0153, -0.1940, -0.4305, +0.0677, -0.0475],
-[ +0.0903, -1.0140, -0.3648, -0.2671, -0.9869, -1.1105, -0.1728, -0.4584, +0.1077, -1.2754, -0.3594, -0.9522, +0.0033, -0.0398, -0.0673, +0.5141, -0.3745, -0.4329, -0.3398, -0.1699, +0.0370, -0.5619, -0.3187, -0.2753, +0.2649, -0.6796, -0.2249, +0.3044, -0.8603, -0.2977, +0.1388, +0.0352, +0.3563, +0.4092, -0.8553, -1.0842, +0.0022, -0.5831, -0.2512, +0.3504, -0.7838, +0.0974, +0.3445, -0.5496, +0.2463, -0.3484, -1.0328, -0.1989, -0.2634, -0.1709, +0.3680, -0.0917, -0.2035, -0.7795, -0.5149, +0.2160, -0.9999, -0.3293, -1.0852, -0.1559, +0.3706, +0.0294, +0.1326, -0.4432],
-[ -0.3382, -0.6195, +0.1247, -0.9739, -0.2695, +0.4227, +0.5390, -0.6254, +0.7109, -0.4693, +0.4139, -0.1816, -0.3087, +0.4984, -0.2314, -2.1260, +0.1874, -1.2938, -0.2536, +0.3450, -0.4624, +0.2507, -0.2771, +0.1359, -0.1039, -0.2051, +0.9813, -0.1579, +0.4289, +0.5024, +0.8469, +0.6266, -0.3238, +0.1631, -0.3280, -0.0628, -1.0241, -0.2662, -0.4386, -0.1759, -0.0683, -0.2852, -0.6328, -0.4171, -0.6023, -0.1489, +0.6873, +0.2652, +0.1424, -1.4934, -0.4190, +0.1496, -0.1254, -0.1988, -0.9254, +0.0787, -0.6244, +0.0852, -0.6942, +0.3636, +0.6130, -1.1516, -0.0166, +0.1482],
-[ -0.6169, +0.1188, +0.3406, +0.1486, -0.6095, -0.1965, +0.3326, +0.4358, +0.0495, -1.1649, -0.5144, +0.4749, -0.2066, -0.0452, -0.8100, +0.3289, -0.4713, +0.3136, -0.4597, +0.3147, -0.3159, -0.2916, +0.3687, +0.1243, +0.5095, +0.1617, -0.7095, +0.4710, +0.0587, -0.6793, -0.2090, -0.1338, -0.1012, -0.4273, +0.2017, +0.1794, -0.6143, +0.0151, -0.2607, -0.3144, +0.2775, +0.2231, +0.3938, +0.0757, -0.6821, -0.0948, -0.0276, +0.4643, -0.4261, +0.1980, -0.3515, -0.4316, -0.2730, +0.1513, +0.3709, -0.5053, -0.3931, -0.0077, +0.4617, +0.2240, -0.5421, +0.0172, +0.3574, +0.3165],
-[ -0.1494, +0.1755, -0.1157, -0.3965, -0.3154, -0.5596, -0.0307, +0.1837, +0.0388, -0.0440, +0.5869, +0.1878, +0.2522, -0.4798, -0.3823, +0.1313, -0.0318, +0.0430, +0.1159, +0.3460, -0.2264, -0.2695, -0.1647, +0.9139, -0.2705, -1.4509, +0.8597, +0.1964, -0.4520, +0.1905, -0.1044, +0.1410, +0.0431, +0.0959, +0.0074, -0.7522, +0.2711, -0.0279, -0.5335, +0.3875, +0.1375, +0.1347, +0.1622, -0.6972, +0.2821, +0.1858, +0.1513, +0.1948, +0.9353, +0.1265, -0.4261, -0.7619, +0.0747, -0.3146, -0.0773, +0.2217, +0.1078, +0.1632, -0.8363, -0.0736, -0.7793, +0.3148, +0.1152, -0.0871],
-[ -0.1752, +0.5067, +0.2685, -0.3138, -0.1825, -1.1993, -0.5480, -0.0802, +0.0464, +0.1444, -0.0249, -0.6009, -0.2998, -0.1202, -0.1522, +0.2545, -0.3147, +0.0469, +0.2033, -0.1856, -0.1173, -0.3927, +0.1988, -0.0460, +0.1827, +0.1227, +0.1774, -0.0260, +0.3352, +0.2306, +0.1482, +0.0897, -0.5807, -0.4350, +0.4242, -0.5245, +0.5988, +0.3664, +0.2803, +0.2254, +0.0257, -1.0348, -0.0827, -0.3720, +0.0641, -0.0757, +0.3361, +0.1720, -0.0170, -0.1818, -0.7976, +0.6775, +0.1444, -0.0576, +0.1275, -0.0842, -0.2819, -0.3301, -0.1414, +0.0448, -0.2871, +0.2704, -0.0597, +0.3678],
-[ -0.4166, -0.1664, +0.4311, +0.2548, +0.0251, +0.0090, -0.1093, -0.0026, +0.0234, -0.4495, +0.2458, -0.4985, +0.0709, -0.0913, -0.3304, -0.7517, +0.2261, +0.0720, +0.0285, +0.0063, -0.1014, -0.0074, +0.0738, +0.2781, -0.0023, +0.0906, -0.3204, +0.2005, +0.2953, +0.1304, -0.1219, +0.2426, -0.3057, +0.1381, +0.2148, -0.2981, -0.0340, -0.0236, +0.1463, +0.1595, +0.2486, +0.3110, +0.2315, -0.1590, -0.3630, -0.1236, -0.5037, +0.3045, +0.3508, +0.4195, -0.4814, +0.4588, -1.0159, -0.1006, +0.3944, -0.5326, -0.2366, +0.1164, -0.1002, +0.3154, -1.3383, -0.0688, -0.5051, +0.3699],
-[ -0.7197, +0.1504, -0.1446, -0.1339, -0.1417, -0.8162, +0.1944, +0.7188, +0.2220, -0.0700, -0.3646, +0.2094, -0.5074, -0.4900, +0.0540, -0.1434, +0.0774, -0.0898, -0.6445, -1.3980, +0.1683, -0.0078, +0.1635, -1.7522, -0.1579, +0.0890, -0.1984, -0.1460, -0.2629, -0.1298, +0.0776, -0.2910, -0.6156, -0.1294, -0.1896, +0.0145, -0.0966, -0.4646, +0.2838, -1.2625, -0.3026, +0.3173, +0.0627, -0.2735, -0.5908, +0.4986, -0.2053, -0.1533, -0.1913, -0.3208, -0.9794, -0.1901, -0.2732, +0.2572, +0.1799, -0.2724, -0.0612, +0.3570, -0.1317, -0.2146, -0.1356, +0.1379, -0.1355, -0.0752],
-[ -0.6539, -0.0727, -0.3427, +0.2905, -0.8430, -0.1184, -1.0977, +0.1251, -0.3407, -0.7221, -1.2782, +0.3135, -0.5871, -0.6889, +0.2488, -0.0093, -0.3846, +0.0363, -0.3364, -0.1874, -0.4212, -0.3552, -0.0608, +0.2429, +0.1007, +0.1632, -0.0480, -0.6035, -1.1736, +0.3253, -0.3441, +0.1198, +0.4950, -0.5443, +0.0941, +0.1484, -0.2168, +0.0281, -0.1605, +0.3858, -0.5413, -1.0550, -0.3714, +0.5328, -0.0108, -0.3914, +0.3519, -0.0481, +0.1556, -0.5657, -0.0249, -0.0100, +0.0097, -0.2173, -0.0652, +0.1465, -0.0911, -0.3613, -0.7631, +0.0362, +0.5869, -0.9699, +0.3223, -0.0013],
-[ -0.1603, +0.3650, +0.5134, +0.5864, +0.0150, -0.1627, -1.0264, -0.3798, +0.2746, -0.4213, -0.6696, -0.1510, +0.2925, -0.1033, +0.1605, +0.2035, +0.2847, -0.2705, -0.7426, +0.1778, -0.2366, -0.5919, -0.5160, -0.2858, +0.0174, +0.2660, -0.5899, +0.2780, -0.1739, -0.3548, -0.2082, +0.2561, +0.2203, -0.4143, -0.1662, +0.3997, -0.1140, +0.3797, +0.1374, -0.4189, -0.0794, +0.2233, +0.0798, -0.2465, +0.1627, -0.7068, +0.0921, +0.1746, -0.1801, +0.0973, -0.3874, +0.1683, -0.1716, -0.2131, -0.1740, -0.2968, +0.0111, -0.1467, +0.3081, +0.1584, -0.2410, -0.1039, -0.0486, +0.1736],
-[ -0.2541, -0.2942, +0.7954, -0.3406, +0.0833, -0.7064, +0.4935, -0.8418, -0.4647, +0.0957, -0.0341, +0.1078, +0.1308, -0.1374, -0.3026, -0.5658, +0.7016, +0.4218, -0.8008, +0.1745, +0.1244, -0.3131, -0.0462, -0.2624, -0.9678, +0.0175, -1.4123, -0.5639, -0.4396, -0.3965, +0.3948, -0.5819, +0.0683, +0.4224, -0.2057, +0.3409, +0.0405, +0.3297, +0.4343, +0.1012, +0.0315, -0.1699, +0.1734, -0.3161, -0.9861, +0.0318, -0.9950, -0.2561, -0.6608, +0.0695, -0.2817, -0.3608, +0.0228, -0.1920, +0.6605, -1.0173, -0.1881, -0.0018, -1.4576, -0.1873, +0.0563, -0.1610, -1.3073, -0.4878],
-[ -0.4730, +0.3181, -0.9216, +0.0616, -0.0595, -0.3835, -1.0827, -0.2049, +0.3268, -0.0025, +0.4207, +0.0695, +0.2867, -0.6964, -0.2021, -0.3313, +0.2401, -0.5865, +0.1225, +0.0662, -0.0395, -0.3217, +0.0283, -0.6146, +0.3855, +0.4659, -0.1366, +0.1905, -0.4189, -0.0221, +0.0485, -0.0824, -0.0852, +0.3699, -1.1362, -0.3399, -0.3045, +0.4129, -0.0479, -0.2226, -0.1424, +0.1984, +0.1308, -0.0697, -0.1180, -0.0040, +0.0799, -0.5004, -0.2016, +0.3574, -0.0379, -0.1902, -0.2152, -0.1548, -0.2587, -0.0184, +0.1557, -0.8546, +0.0033, -0.5034, -0.0296, -0.7283, -0.2543, -0.5056],
-[ -0.3047, -0.4435, -0.0328, +0.1094, +0.2118, +0.0936, +0.1051, -0.3049, -0.2984, -0.2139, +0.4623, +0.0697, +0.0438, -0.0070, +0.0173, -0.0140, +0.3330, +0.1464, -0.8054, -0.5374, +0.2089, +0.0343, -0.0500, +0.2463, -0.5428, +0.3249, -0.2111, +0.1987, +0.3385, +0.0350, +0.2139, +0.2606, +0.0579, +0.1967, +0.2805, -0.6701, +0.1659, +0.1625, -0.0811, +0.1512, +0.2602, +0.0735, +0.3579, +0.1876, -0.1828, +0.2517, -0.2081, -0.0434, -0.0671, -0.2775, -0.0324, +0.0956, +0.1478, -0.5488, +0.4217, +0.3050, +0.1241, -0.1265, -0.0378, -0.4110, +0.0372, +0.1242, -0.5133, -0.4433],
-[ -0.0908, -0.4056, +1.0407, +0.2022, +0.3277, +0.0473, -0.2004, -0.0019, +0.6105, -0.2085, -0.3269, -0.5087, -0.9063, +0.4416, -0.5120, -0.6012, -0.0893, +0.7692, -0.8258, +0.2614, +0.3312, +0.2587, -0.2327, +0.2353, +0.2126, -0.9841, -0.9045, -1.6272, -0.0327, -0.2158, +0.1556, -1.2507, +0.1904, +0.2771, -0.1323, +0.0612, -0.2321, -0.0461, -0.0934, -0.6754, +0.1108, +0.4772, -0.0157, +0.1737, +0.2587, +0.3093, -0.4642, -0.2549, -0.6423, +0.7156, -0.0731, +0.2901, -0.8073, +0.5818, -0.0272, +0.4151, +0.6385, -0.4803, +0.5069, +0.1455, -0.6939, -0.5308, -0.1173, +0.3071],
-[ +0.0517, -0.4560, -0.5719, -0.6117, -0.1617, -1.0319, -1.3503, +0.2440, +0.2115, +0.0598, -0.1558, -0.5093, -0.4359, -1.0329, -0.2702, +0.6932, +0.7264, -0.6596, -0.8755, -0.0335, -0.1665, +0.2618, +0.3496, -0.3067, -0.2615, -0.5898, -0.0792, -0.0211, -0.1784, -0.1019, +0.3617, +0.1576, +0.2354, -0.3653, -0.2507, -0.6275, -0.0337, +0.4102, -0.9432, -0.2444, -0.6182, -0.1471, -0.0926, +0.1671, -0.8133, +0.3371, -0.0011, +0.4394, -0.5574, +0.0047, -0.1289, -1.0679, +0.0061, +0.1657, +0.0043, +0.0216, -0.3186, -0.1413, +0.1294, +0.4513, -0.4948, +0.3693, -0.1198, +0.0882],
-[ +0.0040, -0.4130, -0.1497, +0.1240, -0.0150, -0.8052, +0.0120, -0.5317, -0.1766, -0.5743, +0.1538, -0.1543, +0.3415, +0.3493, +0.2536, -0.7229, -0.0653, -0.1433, -2.7258, -0.3427, -0.1859, +0.0050, -0.3057, -0.1605, +0.2688, -0.5278, -0.3073, +0.1964, +0.6694, +0.0137, -0.2008, -0.2361, -0.1387, -0.0223, -0.0853, +0.1436, -0.1557, +0.2564, -1.0089, -0.6109, +0.2781, +0.1629, +0.1666, -0.1351, -0.3322, +0.1780, -0.8044, +0.4328, -0.6413, +0.2032, -0.2698, -0.0661, -0.2372, +0.1637, -0.1807, +0.4428, +0.0628, +0.4494, +0.1031, -0.1792, -0.7799, -0.0583, -0.2036, +0.3183],
-[ -0.0603, -0.9099, +0.3309, +0.0880, -1.0803, -0.1118, -0.1298, -0.1775, +0.2533, +0.3987, -0.5975, -0.1113, +0.2020, -0.0156, -0.0979, -0.1306, +0.1531, -0.1246, +0.3544, +0.3535, -0.1467, -0.5855, -0.4307, +0.1979, -0.3168, -0.3793, +0.0741, -0.1397, -0.6970, +0.1966, -0.1540, +0.2032, +0.3120, -0.4629, +0.0909, -0.7293, +0.2610, -0.7788, +0.0532, +0.2694, -0.2469, -1.1975, -0.2844, +0.0471, +0.1458, +0.1922, -0.3000, -0.2814, -0.4190, -0.2708, -0.2938, +0.0716, -0.5238, -0.1817, +0.3848, -0.2661, -0.0399, -0.1237, -0.0065, -1.0783, +0.0090, -0.2122, -0.2348, +0.1777],
-[ +0.3301, +0.3029, +0.2309, -0.2222, -0.3760, +0.2900, +0.4730, +0.3653, +0.1257, -0.2469, +0.0678, -0.3140, -0.1101, -0.3410, +0.2531, -0.1499, +0.1895, +0.3933, -0.0175, +0.1947, +0.3018, +0.1375, +0.1816, -0.0375, -0.0476, -0.3521, -0.1531, +0.1851, -0.0556, +0.0737, +0.0242, -0.0522, +0.2391, +0.3069, -0.8566, -0.2267, -0.4648, +0.0512, +0.1738, -0.1233, +0.3117, -0.1392, -0.2971, -1.6641, +0.0319, -0.2886, +0.2520, -0.4421, -0.0578, +0.1778, +0.0562, -0.0425, -0.2082, -0.4188, -0.4602, +0.3081, -0.0443, +0.1036, -0.6564, -0.0622, +0.4363, -0.2111, +0.3930, -0.4231],
-[ -0.2303, -0.3073, +0.0881, -0.0259, +0.1158, -0.1876, -0.4537, -0.1588, -0.0792, -0.2001, +0.0530, -0.2474, +0.1344, +0.2636, +0.1983, -0.9749, +0.1990, -0.0957, -0.5147, -0.2180, +0.1174, +0.1786, +0.1739, -0.3798, -0.0471, +0.1633, -0.1721, -0.0853, +0.2622, +0.2510, -0.0152, -0.1403, -0.4670, -0.0056, +0.1107, -0.6130, +0.0380, +0.2772, +0.2147, +0.4764, +0.2957, -0.1803, +0.0094, -0.0602, +0.0961, +0.1071, -0.1469, +0.3588, +0.1152, +0.2732, -0.0841, +0.1434, -0.8871, +0.1359, +0.4381, -0.3618, -0.1783, +0.0244, -0.3266, +0.2683, +0.0475, +0.2396, +0.2882, +0.2097],
-[ -0.3898, +0.1630, +0.1282, -0.3963, -0.4884, -0.4047, +0.2388, -0.1641, -0.2076, -0.5232, -0.0945, +0.0596, +0.4917, -0.9385, -0.6932, +0.0820, -0.1105, +0.1518, -1.0556, +0.2921, -0.1624, -1.1541, -0.3967, -0.0768, +0.2946, -0.1138, -0.6109, +0.4627, -0.0852, -0.4616, -0.3002, +0.3148, +0.4467, -1.3130, +0.0544, -0.6324, -0.2650, +0.4150, -0.0212, -0.6526, +0.0006, +0.1399, +0.3180, +0.2171, -0.2745, +0.1383, +0.3992, -0.1085, -0.8361, +0.4735, +0.3327, -0.2108, -0.1326, +0.1012, -0.1039, -0.7952, -1.0795, -0.8962, +0.2586, -0.1086, -0.1492, +0.1341, +0.4539, +0.0087],
-[ -0.7632, -0.3424, -0.8353, +0.2849, +0.4074, +0.3540, -0.0225, -1.0280, -0.0935, -0.1287, -0.9041, -0.2897, -1.2458, -0.9333, -0.3642, +0.1682, -0.0609, -0.3427, -0.8061, +0.0809, -0.0527, +0.2854, +0.0572, -0.9497, -0.1074, -0.4606, -0.3741, -0.1462, -0.0244, +0.1021, -0.1344, -1.4004, +0.2785, +0.0365, +0.0607, -0.0216, +0.2336, +0.2448, +0.3313, +0.0876, -0.0096, -0.0115, +0.2235, +0.1732, +0.0449, +0.2710, -0.4689, +0.3985, +0.3226, -0.4791, +0.1363, -0.2898, -0.2764, +0.2951, +0.1026, +0.2428, +0.4613, -0.6892, -0.6060, +0.0831, +0.0033, +0.0969, +0.1732, +0.1978],
-[ -0.4818, -0.4774, -1.1071, +0.3249, +0.2093, +0.0438, -0.9925, -0.4215, +0.0589, -1.1715, +0.0919, +0.0382, -0.8698, -0.4791, -0.7492, -0.8701, +0.0800, +0.0196, -0.7821, +0.1573, +0.5803, -0.1820, -0.0484, +0.3254, +0.1583, +0.2182, -0.2223, -0.5444, -0.6228, -0.7236, -0.1355, +0.2437, -0.0066, +0.2737, +0.2386, -0.4084, -0.8557, +0.2213, -0.6375, +0.2682, -0.1000, -0.3804, -0.0290, -0.0049, -0.3404, -0.4885, -0.1223, -0.2278, -0.4468, +0.0452, -0.4968, -0.1218, +0.3995, -1.0746, -0.7465, -0.3371, +0.4305, -1.6123, -0.1957, -0.1523, +0.1393, -0.8650, -0.1711, -0.3793],
-[ -0.1557, -1.0601, -0.4499, -0.1604, -0.5255, -0.4208, -0.6083, +0.3356, -0.0805, +0.2551, +0.0412, -0.1619, +0.2200, -0.8917, -0.4723, -1.0188, +0.4529, -0.0400, -0.0839, +0.0217, -0.3820, +0.3089, +0.2091, +0.1926, +0.0795, +0.1515, +0.1128, -0.3851, -0.1858, +0.3644, +0.2686, -0.1214, +0.5001, -0.9542, +0.0416, -0.0110, -0.8521, +0.2699, -0.7884, -0.0235, -0.6484, +0.3534, -0.7125, +0.2728, +0.0038, -0.3497, +0.2039, +0.2628, +0.4429, +0.2073, -1.0902, -0.1620, +0.3977, +0.5173, -0.4190, -0.5424, +0.1696, +0.4501, -0.1723, +0.3870, +0.3782, -0.4795, -0.0925, +0.1928],
-[ -0.1994, +0.0819, -0.9161, -0.0627, -0.3875, -0.1237, -0.3848, +0.1303, -0.5012, -0.0149, -0.0410, +0.9109, -0.0172, +0.2573, -0.0970, +0.1189, -0.2560, +0.2362, -0.0120, -0.0293, +0.0847, -0.2890, +0.1035, -1.1365, -0.6136, +0.0283, -0.6735, -0.3893, -0.2377, +0.1533, -0.1454, +0.4457, +0.0874, -0.6123, +0.0648, -0.0958, +0.3596, -0.9314, -0.0837, +0.4202, -0.2286, -0.3712, +0.0654, -0.1894, +0.7228, -0.0053, +0.2753, +0.1067, +0.2597, -0.0419, -0.5189, -0.0970, +0.3215, +0.0511, +0.1690, -0.5153, -0.7584, -1.0287, +0.6774, +0.2733, -0.0217, -0.5480, -0.0327, +0.0814],
-[ -0.0850, -0.2497, -0.2107, -0.2141, +0.3072, +0.3229, -0.1949, +0.1294, -0.2154, -0.5436, -0.2756, +0.1585, -0.3081, -0.2884, +0.0584, +0.3902, +0.5601, -0.0324, -0.8309, +0.0884, +0.4890, +0.2771, +0.1323, +0.2234, -0.5563, +0.2813, -1.1535, +0.3736, -0.8677, +0.2691, +0.1412, +0.4179, +0.3897, -0.2039, +0.0885, -0.2746, -0.3438, +0.6083, +0.1196, +0.6909, +0.3943, -0.4563, -0.2028, +0.3160, +0.4372, -0.3929, -0.6564, -0.2445, -0.3547, -0.0069, +0.3304, +0.2863, +0.0022, -0.6024, +0.0905, -0.0902, +0.3029, -0.2148, +0.3599, +0.3216, +0.5142, -0.8270, +0.3086, +0.2275]
+weights_dense1_b = np.array([
+ +0.0945, +0.0221, +0.0891, +0.0491, +0.0117, -0.0476, -0.0928, -0.1916,
+ -0.0470, +0.2310, +0.0341, +0.0667, -0.0911, +0.1326, -0.1565, -0.1634,
+ -0.0695, -0.0235, -0.2292, -0.1396, -0.2046, +0.0967, -0.0569, +0.0423,
+ -0.0863, +0.0138, -0.2055, -0.1253, -0.1153, -0.2407, +0.1039, -0.2110,
+ -0.0743, -0.0020, +0.0149, -0.2198, +0.0150, -0.2298, -0.1317, +0.0990,
+ -0.0897, +0.0430, -0.0985, +0.0082, -0.2348, -0.0832, -0.1534, -0.1548,
+ -0.2317, +0.0414, -0.0891, -0.2233, -0.0865, -0.0298, -0.1339, +0.0339,
+ +0.1492, -0.1300, -0.4555, -0.0238, +0.0225, -0.1978, +0.0416, -0.0089,
+ -0.0476, +0.0720, -0.1214, +0.1386, +0.1151, -0.1887, -0.1368, -0.1987,
+ -0.0415, +0.0236, -0.2552, -0.1052, -0.0978, +0.0162, -0.0876, +0.0537,
+ -0.1436, -0.2076, -0.0873, -0.1789, -0.0524, -0.1163, -0.0832, -0.1528,
+ -0.0416, -0.1003, -0.0970, -0.1769, -0.1527, -0.0028, +0.1150, +0.0467,
+ -0.0537, -0.2437, -0.1143, -0.1589, +0.1136, +0.0611, -0.1218, +0.0358,
+ +0.1195, -0.1023, +0.0665, -0.0816, -0.1308, -0.1215, +0.0528, -0.0858,
+ +0.1087, -0.0314, -0.2404, +0.0233, -0.0644, -0.1083, -0.0198, -0.0531,
+ -0.0808, -0.0256, +0.0324, -0.0287, -0.0536, -0.1525, +0.0821, +0.1315
])
-weights_dense2_b = np.array([ +0.3157, -0.0138, +0.1347, +0.2792, -0.0769, +0.0847, -0.0819, +0.2974, +0.1350, -0.0025, +0.0698, -0.2427, +0.2004, +0.2309, +0.1715, +0.0219, +0.1258, +0.1784, +0.3261, +0.1711, -0.0779, +0.1550, +0.1433, +0.0774, -0.1676, -0.0443, -0.1684, +0.1624, +0.0597, +0.0358, +0.1652, +0.1075, +0.0770, +0.1979, +0.1490, -0.0719, +0.1036, +0.0766, +0.2915, -0.1048, +0.1366, +0.0610, +0.2238, +0.1660, +0.0433, +0.3754, -0.0812, -0.0851, +0.2820, +0.2110, +0.0232, -0.0167, -0.2433, -0.0042, +0.2591, -0.0215, +0.0927, +0.1470, -0.0324, +0.2150, -0.1883, +0.0956, +0.1331, +0.2330])
+weights_dense2_w = np.array(
+ [[
+ -0.1271, +0.3914, +0.0018, -0.6558, -0.4675, +0.0085, -0.1844, +0.6802,
+ -0.0125, +0.4014, -0.5915, -0.9738, +0.1934, -1.1626, -0.1495, +0.5737,
+ +0.0789, -0.0532, -0.0646, -0.6168, +0.0404, -0.2622, -0.2860, -1.0234,
+ -1.0591, -0.0915, -0.6457, -0.4371, +0.2578, -0.1847, -0.0168, -0.3883,
+ +0.3122, -0.2463, +0.0569, -0.6280, +0.2718, -0.3457, +0.0460, -0.0186,
+ -0.5913, -0.1637, +0.1242, +0.1545, -0.4075, +0.1479, +0.4976, -0.6677,
+ +0.1678, +0.0601, -0.6402, +0.2643, +0.5309, -0.5865, +0.4594, -0.4839,
+ +0.0092, -1.0042, -0.4222, -0.1008, +0.3164, +0.4503, -0.4733, -0.3181
+ ],
+ [
+ -0.7950, -0.2874, -0.9796, -0.0894, -0.2489, +0.1023, -0.7191,
+ -0.1062, -0.0686, +0.0219, -0.5166, -0.1731, +0.6046, +0.1325,
+ -0.1113, -0.1895, -0.5124, +0.2307, +0.1318, -0.1584, -0.0253,
+ -0.0489, -0.1236, +0.1723, -0.1987, -0.1482, +0.2360, -0.6252,
+ +0.1100, -0.0496, -0.2046, -0.0098, +0.1554, -0.0330, +0.1830,
+ +0.5273, -0.2040, -0.3389, -0.0136, +0.3009, -0.8369, -0.5315,
+ +0.3389, +0.0406, -0.1619, +0.1336, -0.0931, +0.3350, -0.5562,
+ -0.2256, -0.1484, -0.1714, +0.3276, +0.3614, -0.5478, +0.0381,
+ -0.6016, -0.4736, -0.1763, +0.6435, -0.4753, -1.0543, +0.8731, -0.0291
+ ],
+ [
+ +0.0954, -0.2826, +0.4515, +0.2719, -1.5872, -0.6669, +0.5393,
+ +0.0683, +0.0223, -0.4139, -0.0436, -0.2927, -0.1016, +0.0872,
+ -0.0511, +0.2276, -0.3104, -0.1281, -0.3726, -0.4281, -0.2043,
+ -0.0067, -0.0833, +0.1530, +0.1471, +0.0299, -0.7778, -0.4584,
+ -0.2937, -0.5823, +0.1004, -0.0315, -0.2546, -0.2999, +0.1273,
+ -0.4236, +0.0839, -0.2711, -0.4104, -0.9313, +0.1809, +0.1160,
+ +0.1217, +0.0610, -0.1349, +0.1962, +0.2288, +0.0999, -0.2857,
+ +0.1488, -1.1450, +0.0397, +0.0243, -0.4398, -0.1675, +0.1116,
+ -0.4391, +0.3284, +0.2221, -0.2577, -0.4555, -0.0088, -0.0855, -1.3852
+ ],
+ [
+ -0.9066, -0.0779, +0.2506, +0.5973, -0.2074, -0.0816, +0.1313,
+ -0.0467, +0.3583, -0.2508, +0.3739, +0.3117, -0.4828, +0.3411,
+ -0.4750, -0.2348, -0.0597, -0.1498, -0.6612, -0.1696, -0.4938,
+ +0.1585, +0.2521, -0.4542, +0.0009, -0.1163, +0.2059, -0.2132,
+ +0.2928, +0.2853, +0.1130, +0.1913, -0.0430, +0.0943, -0.0217,
+ -0.4564, +0.2648, -0.3642, -0.0154, -0.1325, -0.1173, +0.0562,
+ +0.4583, +0.2892, -0.5079, +0.6878, -0.1487, +0.0205, +0.0981,
+ -0.0039, -0.3292, +0.0082, +0.1342, -0.0187, +0.3907, -0.2287,
+ -0.5168, -1.0717, -0.1443, -0.1601, +0.1502, +0.2766, -0.0043, +0.1320
+ ],
+ [
+ -0.2278, +0.1479, -0.7906, +0.1998, +0.5790, -0.7421, +0.0865,
+ -0.4855, +0.0669, +0.5062, -0.5994, +0.1859, -0.3231, -0.4490,
+ -0.6158, -0.0905, +0.1926, -0.0107, -0.1922, +0.3182, +0.7090,
+ +0.1008, -0.5894, -0.1029, +0.2866, -0.9230, +0.3036, -1.6312,
+ -0.4129, +0.0185, +0.2326, -1.2005, -0.2662, -0.1140, -0.3067,
+ -0.9747, -0.4549, +0.0886, +1.1618, +0.0391, +0.5329, +0.3774,
+ +0.0105, +0.0694, +0.0137, -0.4737, -0.1588, +0.3237, -0.3649,
+ +0.0849, -0.2834, -0.4216, +0.2610, -0.7456, -0.3009, +0.2728,
+ +0.2492, +0.4658, -0.4006, +0.0284, +0.3466, -0.2762, -0.0260, -0.3199
+ ],
+ [
+ +0.0064, -0.2720, -1.1888, +0.1102, -0.6399, -0.5524, +0.1461,
+ -0.6517, +0.0382, +0.5065, -0.1815, -0.7615, +0.1473, -0.0197,
+ +0.1725, +0.0512, +0.2036, +0.4414, -0.1795, -0.0886, -0.1142,
+ +0.4498, +0.1177, +0.0057, -0.0964, -0.0811, +0.1596, -0.4883,
+ +0.1965, -0.1698, +0.2760, -0.0165, -0.1367, +0.3872, -0.1555,
+ +0.4407, -0.1900, -0.7512, -0.5738, +0.0527, -0.1601, +0.1037,
+ -0.1187, -0.2776, -0.3760, +0.5335, -0.5347, -0.1479, +0.0165,
+ -0.0124, +0.7250, +0.1477, +0.0149, +0.1117, +0.2934, +0.2190,
+ -0.1941, -0.5849, +0.1879, -0.4424, -0.9252, +0.1739, -0.5742, +0.3218
+ ],
+ [
+ -0.5851, +0.2061, -0.1146, +0.3440, -0.8697, +0.5240, +0.0196,
+ -0.0692, -0.4171, +0.1702, -0.2292, -0.2366, -0.0427, -0.3395,
+ -0.0157, -0.1608, -0.0301, -0.0541, +0.1548, -1.1881, -0.1515,
+ -0.0891, +0.0046, -0.2020, +0.1449, -1.1849, -0.2219, -0.3805,
+ +0.0840, -0.2359, +0.2454, -0.4630, -0.0234, -0.1242, +0.0518,
+ +0.6156, +0.1568, +0.3287, -0.0841, -0.7317, -0.6159, +0.3588,
+ +0.1828, -0.9023, -1.1006, -0.0212, +0.2007, +0.5831, +0.0995,
+ -0.6283, -0.0894, +0.1098, -0.2749, -0.0411, -0.0119, +0.0558,
+ +0.1683, -0.0131, +0.1848, +0.0679, +0.0456, -0.2571, -0.9563, -0.2443
+ ],
+ [
+ -0.0073, -0.3201, -0.3817, -0.0192, -0.4109, -0.4282, -0.1132,
+ -0.4349, +0.2255, -0.0437, -0.6572, +0.2767, -0.4989, -0.4036,
+ -0.1763, +0.2089, -0.5215, +0.1290, -0.1541, -0.3489, +0.2339,
+ -0.0198, -0.0317, -0.9100, -0.0544, -0.6314, -0.1819, +0.2346,
+ -0.0081, +0.0007, -0.0257, -0.1465, -0.6833, -0.9600, -0.1040,
+ -0.1067, -1.1308, -0.2348, +0.1580, -0.9859, -0.9199, -0.0363,
+ -0.0562, +0.0475, -0.5149, +0.2848, -0.3803, -0.1797, -0.0309,
+ -0.1081, -1.3299, -0.1604, -0.1880, +0.0615, +0.1823, +0.0057,
+ +0.1575, +0.0888, -0.1895, +0.2093, -0.1036, -0.6154, +0.5185, +0.1521
+ ],
+ [
+ +0.2531, -0.6279, -1.4513, -0.1934, +0.0015, -0.4900, -0.2063,
+ -0.4151, +0.1763, -0.0243, -0.6314, -1.2217, -0.9091, -0.0730,
+ -0.4270, +0.0620, -0.6859, +0.0461, -0.0924, +0.3800, +0.1811,
+ +0.1697, -0.2316, -0.5443, +0.0866, +0.0782, +0.1150, -0.6990,
+ -1.1189, -0.3874, -0.4161, +0.0440, -0.7594, -0.2724, -0.5725,
+ +0.3213, +0.2200, +0.1760, -0.2150, +0.1958, -1.6232, -0.2854,
+ -0.0612, -0.2916, -0.0928, +0.0537, -1.0109, +0.4645, +0.0471,
+ +0.0559, +0.2336, +0.0665, +0.1497, -0.3873, -0.1014, +0.1958,
+ -0.6501, -0.1341, +0.1965, -0.4280, +0.2265, +0.0304, +0.6069, -0.3555
+ ],
+ [
+ -0.7091, -0.1624, +0.1640, -0.0758, -1.2377, -0.0772, +0.1476,
+ +0.2682, -0.1253, +0.2720, -0.1572, -0.0119, +0.3484, +0.4451,
+ +0.2922, +0.5946, -0.5605, +0.1464, +0.6736, -0.1512, -0.2042,
+ +0.3320, -1.2094, +0.0608, +0.7341, -0.0744, -0.5122, -0.3548,
+ -1.1743, +0.3937, -0.4435, -0.5681, -0.1948, +0.2073, -0.4939,
+ +0.2860, -0.0874, -0.1584, -0.5339, -0.6618, +0.4565, -0.0450,
+ -0.0703, +0.1782, +0.2719, -0.7235, +0.0849, -0.5152, -0.4409,
+ -0.1473, +0.1932, -0.5657, -1.0101, +0.2300, +0.1768, -0.2755,
+ -0.4970, +0.2075, +0.6405, -0.4757, -0.3832, -0.5012, -0.6960, -0.4705
+ ],
+ [
+ -0.2843, -0.5661, +0.1295, -0.6372, +0.6743, +0.3116, -0.1094,
+ +0.2181, +0.4413, +0.0471, +0.3553, +0.3585, +0.4372, -0.0685,
+ -0.0842, -0.4250, +0.4091, -0.3233, -0.2269, -0.0794, +0.8587,
+ +0.1432, -0.3835, -0.1686, +0.1641, -0.7328, -0.8287, -0.4402,
+ -1.3005, +0.5130, +0.0564, +0.1681, -0.3760, +0.0408, -0.1430,
+ -0.8277, +0.0467, -0.7583, -0.1697, -0.2131, +0.2831, +0.1558,
+ +0.2284, -0.2450, +0.0555, -0.1912, +0.0449, -0.2269, -0.3708,
+ +0.2114, -0.4205, -0.7571, -0.0382, -0.2707, -0.0797, -0.1280,
+ +0.0478, -0.0070, -0.1342, -0.9769, +0.2671, -1.0572, -0.0770, -0.9964
+ ],
+ [
+ +0.6900, +0.4678, -0.0557, -0.2668, +0.7300, -0.5408, -0.0688,
+ +0.0454, -0.5562, +0.0199, +0.3122, -0.6756, +0.5708, +0.1600,
+ +0.6282, +0.2039, -0.3018, +0.1667, -0.0453, -0.7653, -0.2430,
+ -0.4678, +0.1237, +0.2742, +0.2941, +0.0830, -1.0421, +0.3499,
+ -0.5175, +0.2747, +0.1062, -0.2901, -0.2809, +0.1417, +0.1436,
+ +0.3868, +0.5309, -0.0153, +0.0805, -0.2631, -0.0940, -0.1412,
+ +0.2611, -0.7766, -0.2855, -0.0439, -0.6175, +0.0947, +0.2999,
+ -0.0547, +0.5183, +0.2994, -0.8269, +0.0034, +0.0987, +0.5503,
+ -0.0088, +0.4137, +0.3632, -0.2834, -0.6923, -0.2821, -1.1406, -0.0749
+ ],
+ [
+ +0.1632, -0.4623, -0.1741, +0.0680, -0.9023, -0.0249, +0.4469,
+ -0.4021, -0.1585, +0.1242, +0.3737, -0.0057, +0.6399, -0.3139,
+ -0.2913, +0.1754, +0.0486, -0.4752, -0.1895, -0.3187, -0.2623,
+ +0.0258, -0.1153, +0.2278, +0.0386, -0.8582, +0.8477, -0.0064,
+ +0.4177, -0.0644, +0.5750, +0.4484, -0.1827, +0.3148, +0.1698,
+ -0.3985, +0.0600, -0.0887, -0.8542, -0.7936, -0.4169, +0.3954,
+ +0.1737, -0.3940, +0.0167, +0.1208, +0.0302, +0.0156, +0.0017,
+ +0.0780, -0.6662, +0.1520, +0.2476, -0.7796, -0.0420, +0.7442,
+ -0.1745, +0.1173, +0.5134, +0.3903, -0.0390, -0.2774, -0.0728, -0.5430
+ ],
+ [
+ +0.4816, -0.3489, +0.5506, -0.6623, -0.9104, -0.8120, -0.8344,
+ -0.2220, +0.3552, -0.0790, -0.8096, +0.2325, -0.3253, +0.1020,
+ +0.1459, -0.0834, -0.7332, -0.3141, -0.8383, +0.0168, +0.1568,
+ +0.5853, -0.1375, +0.1475, +0.6293, +0.2314, -1.1498, -0.3753,
+ -0.8417, -0.8575, -1.3400, -0.2256, -1.4539, -0.3584, -0.4006,
+ +0.1593, -0.9150, +0.6774, -0.2619, +0.1728, -0.2879, -0.1338,
+ -0.5645, +0.3988, +0.3520, +0.4010, -0.2041, +0.0341, -0.3362,
+ +0.2805, -2.0402, -0.6181, -0.7972, +0.1749, -0.6493, -1.4597,
+ -0.5267, +0.5981, +0.2521, -0.5638, -0.2909, -0.4402, -0.0561, +0.4762
+ ],
+ [
+ -0.4250, +0.1095, -0.0655, -0.1546, -0.2041, -0.1293, +0.2493,
+ -0.0696, +0.0848, +0.1911, -0.1816, -0.6701, -0.0172, +0.0131,
+ +0.0102, -0.3538, +0.3072, -0.4811, +0.1599, +0.0691, +0.1479,
+ +0.0118, +0.3573, +0.2026, -0.7681, -0.1526, -0.4309, +0.8109,
+ -1.1647, +0.2582, -0.5493, +0.2395, +0.5988, +0.0868, -0.3176,
+ -0.3688, +0.1128, -0.0358, -0.5428, +0.1570, -0.3296, -0.4567,
+ -0.4286, -0.1437, +0.1628, +0.0506, -0.1043, +0.3776, +0.3047,
+ +0.0809, +0.1967, -0.1743, -0.2635, -0.3714, -0.0760, -0.0980,
+ +0.3933, +0.1918, -0.0237, -0.3041, +0.2151, -0.2341, -0.1485, -0.0661
+ ],
+ [
+ +0.2394, +0.4236, +0.4937, +0.4839, +0.2579, -0.4842, +0.7196,
+ +0.3410, +0.2490, +0.5013, -0.5042, -0.5623, +0.2319, +0.1771,
+ +0.3028, +0.1137, +0.4389, -0.3229, -0.5965, -0.6932, +0.6443,
+ +0.7066, -0.0893, -0.6891, -0.2387, -0.2105, -0.6846, +0.0999,
+ -0.1248, -0.1359, +0.2185, +0.0941, +0.3376, -0.2558, -0.3110,
+ -0.0893, -0.1423, -0.4745, +0.0687, -0.2922, -0.0603, -0.0707,
+ -0.0455, +0.5964, -0.0152, -0.1886, +0.0025, +0.1093, +0.3974,
+ +0.3669, -0.3385, -0.4696, -0.0199, -0.6017, +0.4395, +0.6234,
+ -0.0496, -0.2090, -0.2171, +0.3449, -0.0730, -0.1001, -0.3171, +0.5123
+ ],
+ [
+ +0.0847, +0.1436, -0.3228, -0.3510, -0.7931, -0.0264, -0.3533,
+ +0.6762, -0.0224, -0.1094, -0.3798, +0.1935, -0.2485, -0.1415,
+ -0.5330, +0.2227, +0.1866, -0.3358, -1.9247, +0.1269, -0.0177,
+ +0.1557, -0.3095, +0.2560, +0.0238, +0.2123, +0.4908, -0.3848,
+ -0.0091, -0.2054, -0.1635, +0.0463, +0.0052, +0.2153, -0.0972,
+ +0.3529, -0.5443, +0.5997, -0.6787, -0.7814, -0.2001, +0.1732,
+ -0.1145, +0.2478, -0.2095, -1.0370, +0.0598, +0.1606, +0.3335,
+ +0.3511, +0.3206, -0.5018, +0.5416, -1.2949, -1.5172, +0.0665,
+ -0.3943, -0.6214, -0.0136, +0.2626, -0.2100, -0.0828, -0.3910, -0.3130
+ ],
+ [
+ +0.0901, +0.0253, +0.2478, +0.3539, -0.6675, +0.2158, +0.2303,
+ +0.4287, +0.1316, +0.1663, -0.0972, -0.6236, -0.1827, +0.0954,
+ +0.1095, -0.2775, +0.0321, +0.1237, -0.9309, +0.1208, +0.0141,
+ -0.5857, +0.2646, -0.0349, -0.5315, -0.0656, -0.1674, -0.4231,
+ +0.0615, -0.2795, +0.5309, +0.0471, +0.3718, +0.4552, -0.2424,
+ -0.0762, +0.2703, +0.0431, -0.2285, +0.1411, -0.3293, -0.1031,
+ -0.1698, -0.4149, -0.4501, +0.3116, +0.0163, -0.4347, +0.4256,
+ -0.1770, +0.1217, -0.4240, +0.2111, -1.9418, -0.5665, +0.1624,
+ +0.0666, -0.0973, +0.9793, -1.0486, +0.6492, +0.0490, -0.3199, -0.3808
+ ],
+ [
+ +0.2482, +0.3556, -0.1717, -0.9919, +0.7054, -1.2118, -0.5110,
+ -0.3328, -0.1633, +0.3957, +0.3085, +0.0137, +0.3065, +0.0052,
+ -0.0270, +0.0560, +0.2907, -0.6105, -0.4772, +0.1645, +0.0208,
+ -0.9893, +0.3875, +0.2657, +0.3233, -0.3869, +0.1572, +0.1036,
+ -0.1463, +0.0472, -0.3489, -0.3521, +0.0799, -0.6925, +0.0984,
+ +0.3195, +0.3130, +0.6108, +0.2780, +0.0603, -0.2143, -0.1337,
+ -0.2644, -0.5923, +0.2042, -0.4949, -0.0480, +0.3116, -0.1095,
+ +0.2364, -1.1135, -0.0363, -1.0648, +0.2119, -0.0442, +0.0743,
+ -0.0370, +0.2927, +0.2213, +0.2895, -0.1277, +0.4592, -0.5358, +0.1096
+ ],
+ [
+ -0.0645, -0.1623, -0.2801, +0.1601, +0.4115, +0.1034, +0.5808,
+ -0.3871, +0.0811, +0.1312, -1.2262, -0.3058, -0.4259, -1.4654,
+ -0.8499, -0.4536, -0.0568, +0.3527, -0.4492, +0.2055, +0.2393,
+ +0.3164, -0.1928, -0.1498, -0.4880, +0.1955, +0.2008, -1.0742,
+ +0.0050, -0.0898, +0.3253, -0.0754, +0.0392, -0.0040, +0.1946,
+ +0.0193, +0.0192, +0.4451, -0.7988, +0.0087, -0.2325, +0.2076,
+ +0.0636, -0.1281, +0.5703, +0.1476, +0.0923, -0.2612, -0.2150,
+ +0.3855, -0.2078, -0.1543, -0.2050, +0.3544, +0.0617, +0.0985,
+ -0.2980, -1.1922, -1.3932, +0.1081, +0.1347, -0.7791, +0.0098, +0.3203
+ ],
+ [
+ -0.2477, -0.0342, +0.0651, +0.4190, -0.1286, -0.1516, +0.3836,
+ -0.5551, -0.0254, +0.0229, +0.3122, -0.0037, -0.3752, +0.0208,
+ -0.2014, -1.0760, +0.0428, +0.9403, +0.0155, -0.2281, -0.5390,
+ -0.3031, -0.2937, -0.0763, +0.4585, +0.3504, -0.6128, +0.0253,
+ +0.1955, -1.3097, -0.4295, -0.7464, -0.3443, +0.0480, -0.2732,
+ -0.3435, -0.4001, +0.5535, -0.0008, -0.6926, +0.4328, +0.0657,
+ +0.1847, +0.0448, -0.5529, +0.3648, +0.4270, -0.0240, -0.0652,
+ +0.2067, +0.3803, -0.1376, -0.1249, +0.1560, -0.2670, -0.0751,
+ -0.1908, +0.4397, +0.1006, -0.0798, -0.5067, -0.0203, -0.7287, -0.5677
+ ],
+ [
+ -0.4990, -0.2926, -0.3664, +0.0513, +0.0405, +0.1084, +0.3047,
+ -0.5012, +0.0434, +0.1440, -0.6061, -0.0411, -0.6098, -0.8454,
+ +0.0514, -0.0952, +0.1158, -0.0216, +0.3436, -0.1477, +0.3443,
+ +0.1691, +0.1902, -0.5084, -0.3644, +0.1407, +0.2799, -1.1430,
+ -0.1313, -0.4736, +0.2768, -0.1113, +0.2119, +0.3614, +0.0707,
+ -0.4669, -0.0945, -0.0747, +0.2336, +0.0373, +0.3955, -0.0911,
+ -0.2888, -0.0373, -0.0459, -0.1130, +0.1475, +0.1832, -0.0709,
+ +0.1757, +0.0890, -0.2821, -0.2146, +0.2685, +0.2819, +0.2381,
+ +0.3611, +0.2664, -0.4607, +0.4548, -0.5928, -0.7542, +0.3888, -0.1321
+ ],
+ [
+ +0.2451, -0.0352, -0.0067, +0.5649, -1.3223, -0.0114, -0.2494,
+ +0.2709, -0.1561, +0.6785, -0.4168, -0.0214, +0.1366, -0.1545,
+ -0.0716, +0.2056, -0.5251, +0.2082, +0.0296, +0.1914, -0.5742,
+ +0.0196, -0.2925, +0.2337, +0.4122, -0.5012, +0.1940, +0.3099,
+ -0.9448, +0.4322, -0.5790, -0.3489, +0.0104, -1.0007, +0.2016,
+ +0.2950, +0.2477, -0.1989, -0.3270, -0.3255, -0.0711, +0.1675,
+ +0.1886, -0.3077, +0.6931, +0.0106, +0.0890, +0.2538, +0.3688,
+ -0.3061, -0.5655, +0.0562, +0.3011, +0.0977, -0.1398, -0.2165,
+ -0.7578, +0.0214, -0.4609, -0.2431, +0.0330, +0.2445, -0.0303, +0.0900
+ ],
+ [
+ -0.0365, -0.0273, +0.4411, -0.4758, -0.0957, +0.1289, -0.0185,
+ -0.6137, -0.6106, +0.2414, +0.4711, +0.0494, +0.0588, -0.1135,
+ -0.2285, +0.2474, -0.1030, -0.0374, -0.3801, +0.3589, -0.1773,
+ +0.0079, +0.0782, -0.0122, -0.0823, +0.7424, +0.0962, +0.4727,
+ -0.8676, +0.3077, +0.0557, +0.3209, -0.1592, -0.4861, +0.0395,
+ -0.9804, +0.1699, +0.4900, -0.0592, +0.2355, +0.1924, -0.5904,
+ +0.2611, +0.3920, +0.2856, -0.3913, +0.2407, -0.2500, -0.1903,
+ -0.5961, +0.1522, -0.0197, +0.0872, -0.1873, -0.3491, -0.1286,
+ +0.3000, -0.7042, +0.2894, -0.1837, +0.0561, +0.1254, -0.3829, +0.2918
+ ],
+ [
+ -0.3763, -0.4747, +0.4768, -0.0502, +0.1480, -0.1086, -1.4858,
+ -0.1386, -0.0867, +0.0294, -0.9916, -1.3011, -0.3439, -0.0785,
+ -0.0095, -0.0793, +0.1420, -0.4394, -0.4325, +0.0846, +0.1926,
+ +0.1353, +0.0876, -0.3864, -0.4143, -0.3908, +0.1920, -0.0516,
+ -0.3529, +0.1273, -0.8187, -0.3242, +0.3229, +0.3314, -0.0751,
+ +0.0271, -0.5786, -0.4159, -0.5292, -0.1346, -0.5713, +0.0241,
+ -0.3994, +0.6553, +0.1069, -0.3205, -0.1558, -0.0292, -0.1864,
+ +0.0467, -0.1643, -0.0032, -0.1768, -0.1139, +0.1924, +0.0858,
+ +0.1814, -1.0873, +0.2349, +0.8407, +0.3165, -0.3767, -0.2488, +0.5314
+ ],
+ [
+ +0.0194, -0.5392, -0.1518, -0.3236, -0.4986, +0.3160, -0.1412,
+ +0.0953, +0.7768, +0.3661, -0.5067, +0.0749, +0.3022, -0.0791,
+ +0.0717, -0.4890, -0.5433, +0.1542, -0.1284, -0.5432, +0.1367,
+ +0.4199, +0.0517, -0.2629, -0.2446, -0.5404, -0.0661, -0.8388,
+ +0.2460, -0.0568, +0.1513, -0.1651, -0.5316, -0.3067, +0.2167,
+ +0.3853, +0.1916, -0.3641, +0.1010, -0.6142, -0.3014, +0.0601,
+ -0.1717, -0.0344, -0.1642, +0.2797, -0.2147, +0.3422, +0.1077,
+ -0.3756, -0.3877, -0.0933, -0.2401, -0.9595, -0.2368, -0.1898,
+ -1.2555, +0.0958, +0.0762, -0.0292, +0.3576, -0.1580, -0.0738, -0.0079
+ ],
+ [
+ +0.0141, +0.0895, -1.2167, -0.2237, -0.3790, +0.1855, -0.3394,
+ -0.0038, -0.9612, -0.8003, -0.4690, -0.7451, -0.0575, -0.4595,
+ -0.1010, +0.0564, -0.2061, +0.0016, +0.2122, -0.5486, +0.2575,
+ +0.6701, -0.2359, -0.6095, +0.2275, +0.4353, -0.0755, +0.1635,
+ -1.1059, +0.0813, +0.5430, +0.2135, -0.7705, -0.3789, -0.4640,
+ +0.1618, -0.0749, -0.1601, -0.2568, +0.2982, -0.5505, -0.2380,
+ +0.2200, -0.7600, -0.3742, +0.0263, +0.0205, +0.2430, -0.1207,
+ -0.1844, -0.4536, +0.2157, -0.0314, +0.0561, +0.7357, +0.0529,
+ -0.7068, -0.0974, -0.7203, +0.2107, -0.4502, +0.0662, -0.4206, -0.3138
+ ],
+ [
+ +0.1017, -0.0354, -0.0509, -0.1870, +0.0343, +0.3647, +0.1347,
+ +0.2237, +0.3690, -0.9343, +0.1449, -0.5858, -0.2125, +0.5630,
+ -0.1528, -0.1546, -0.7001, -0.1598, +0.2196, -0.0277, -0.5136,
+ -0.8544, +0.0426, -0.5008, +0.1092, -0.0860, -0.0112, +0.0401,
+ -0.6656, -0.1314, +0.1416, +0.3360, +0.5900, -0.2389, +0.0217,
+ +0.1804, +0.2413, -0.5896, -0.4484, -0.0288, -0.3412, +0.5241,
+ -0.0806, +0.1861, -0.6325, -0.4081, -0.0944, +0.4332, -0.5102,
+ +0.1041, -0.1426, -0.2980, +0.1690, +0.1186, +0.2074, -1.0632,
+ +0.7055, -0.2705, -1.0567, -0.2129, -1.1142, +0.2914, +0.2099, +0.1106
+ ],
+ [
+ +0.3102, +0.1703, +0.3606, -0.0527, +0.1473, -0.2773, -0.0154,
+ +0.1442, -0.1247, +0.0323, -0.3110, -0.1122, +0.1576, +0.2158,
+ +0.1385, -0.2753, -0.1098, -0.7658, +0.2754, -0.0433, -0.0520,
+ +0.5368, +0.1772, -0.0695, -0.0489, -0.0608, +0.1372, +0.2162,
+ -0.2351, +0.2987, -0.1364, -0.2891, +0.3583, +0.1633, -0.3839,
+ +0.4315, -0.0990, +0.0823, +0.1158, +0.0991, -0.1278, -0.3236,
+ -1.2764, -0.6431, +0.1492, -0.3952, +0.1064, -0.1531, +0.2157,
+ +0.4975, -0.2037, -0.4894, -1.5186, +0.2924, -0.6009, -0.1678,
+ -0.1449, +0.1978, -0.3505, -0.0908, +0.0612, +0.2921, -0.0509, -0.1469
+ ],
+ [
+ +0.1539, -0.1646, +0.0906, -0.8074, -0.3751, -0.2480, -0.1706,
+ +0.0897, +0.1467, -0.2731, +0.0630, +0.1252, -0.3487, +0.1124,
+ +0.3977, -0.5022, -0.2230, -1.1773, +0.0916, -0.3775, -0.3700,
+ -1.3137, +0.2118, -0.0780, +0.2561, +0.3471, +0.2589, +0.5410,
+ -0.6811, -0.0975, +0.2142, +0.1334, -0.1160, +0.2675, -0.6791,
+ +0.0902, -0.0351, +0.1841, -0.1571, +0.0284, -0.1294, -0.2189,
+ -0.4384, -0.6264, +0.1533, -0.5177, +0.1915, -0.0130, +0.4706,
+ +0.0774, -0.1659, +0.1409, -0.1534, -0.0867, -0.3677, -0.2035,
+ -0.6024, +0.2904, -0.5581, -1.1772, +0.2702, -0.0471, +0.0550, -0.4774
+ ],
+ [
+ -0.0836, -0.4589, +0.3629, +0.2122, -0.8646, -0.0445, +0.0280,
+ +0.1863, +0.2066, -0.1308, -0.1080, -0.3527, -0.2431, +0.2671,
+ +0.2674, +0.0165, -0.0020, +0.3624, -0.5614, +0.5891, -0.3631,
+ -0.0238, -0.1281, -1.3143, -0.3550, +0.3269, +0.1919, -1.0129,
+ +0.4851, +0.0349, -0.0614, -1.2018, -0.6409, +0.7077, +0.1713,
+ +0.1755, -0.5143, +0.4006, -0.7570, -1.0930, -0.1735, +0.6484,
+ +0.2872, +0.2859, -0.4082, +0.2657, -0.3075, -0.1418, -0.1542,
+ -0.1517, -0.0277, -0.5681, -0.4103, +0.2963, -0.2609, -0.2730,
+ -0.4601, -0.1779, +0.1927, -0.8079, -0.2650, +0.0229, +0.1281, -0.5343
+ ],
+ [
+ -0.4350, +0.0553, -0.5729, -0.2978, -0.9495, -0.7255, -0.7779,
+ -1.1735, +0.1343, -0.3928, +0.2136, -0.2948, +0.1546, -0.9938,
+ -0.1214, -0.0147, +0.0305, -0.1277, +0.7548, +0.2856, +0.0463,
+ +0.0179, +0.0937, +0.8215, +0.2234, +0.1009, -0.3107, +0.0118,
+ -0.4554, -0.0069, +0.1453, +0.0118, -0.1247, -0.6418, -0.0716,
+ +0.4212, -0.5202, -0.0074, -1.1218, +0.1333, -0.0457, +0.3628,
+ +0.3515, -0.1092, -0.4001, -0.5215, +0.1932, +0.0911, +0.0685,
+ +0.0898, +0.0290, -0.5139, +0.0949, -0.1830, -0.5459, +0.1143,
+ -0.8995, -0.2821, +0.4568, +0.0758, -0.9298, -0.4243, +0.3363, -0.2241
+ ],
+ [
+ +0.3514, -0.1343, -0.1294, +0.2483, -1.1607, +0.2577, +0.1505,
+ +0.0614, -0.0038, +0.1206, -0.3880, +0.1227, +0.1437, +0.0353,
+ -0.2475, +0.1809, -0.0030, +0.5491, +0.3195, -0.1809, -0.3715,
+ +0.0359, -0.5749, +0.3637, +0.2684, +0.2354, +0.2458, +0.2446,
+ +0.1564, +0.3003, -0.0686, +0.2666, -0.4387, -0.7032, +0.2667,
+ +0.4540, -0.3143, -0.0387, -0.7421, -0.1658, +0.0813, +0.1450,
+ +0.0384, -0.0218, +0.0556, -0.0205, -0.1314, -0.0056, +0.1476,
+ +0.0417, +0.1668, +0.0552, +0.0224, +0.4450, -0.0994, +0.5961,
+ -0.6376, -0.5452, +0.0621, -0.0608, -0.2084, -0.1293, -0.0258, +0.2475
+ ],
+ [
+ -0.1171, -0.2599, -0.1720, -0.0803, +0.0339, +0.2908, -0.2794,
+ -0.3024, -0.3362, +0.1535, -0.6788, +0.0768, -0.4502, -0.3021,
+ -0.5293, +0.3125, -0.2088, -0.9037, -0.3597, +0.4170, +0.2103,
+ -0.3589, +0.0696, -0.1204, +0.0044, +0.0838, +0.0282, -0.5995,
+ -0.2631, -0.4564, +0.3498, -0.2223, -0.8802, -0.4124, +0.0308,
+ -0.0660, +0.0638, +0.1032, -0.1193, +0.0706, -0.6944, -0.4653,
+ -0.0051, -0.2518, +0.1609, -0.0292, +0.4536, -0.0411, +0.1867,
+ +0.1496, -0.2681, +0.5124, +0.1813, +0.2306, -0.0282, +0.1134,
+ -0.6127, +0.1256, -0.2708, -0.2768, -0.8077, +0.2824, -0.5783, +0.3528
+ ],
+ [
+ +0.2195, +0.0042, -0.2501, -0.5760, +0.2663, +0.2616, -1.4127,
+ -0.0305, +0.0709, +0.1793, -0.0951, +0.0447, -0.3207, -0.6272,
+ -0.0155, +0.1012, -0.0007, +0.1282, +0.4843, -0.0964, +0.2349,
+ +0.3481, -0.0057, +0.1658, -0.3583, +0.0888, +0.0394, +0.2364,
+ -0.3175, +0.2203, -0.1178, +0.1645, +0.0964, +0.3774, +0.4404,
+ -0.5199, +0.6773, +0.1753, +0.4348, +0.1499, -0.0905, -0.2781,
+ -0.0887, -0.4866, +0.0237, -0.4941, -0.0295, -0.3038, +0.3751,
+ -0.1036, -0.0868, +0.2667, -0.3343, -0.6834, -0.1344, -0.0162,
+ +0.2101, +0.2938, -0.2194, +0.1351, +0.0117, -0.0811, -0.2689, -0.2086
+ ],
+ [
+ +0.2790, -0.2113, -0.0294, -0.2711, -0.2345, +0.1162, -0.0328,
+ +0.2538, +0.5912, +0.1002, +0.2225, -0.5451, +0.4108, +0.0101,
+ +0.0081, -0.0407, +0.9695, -0.0133, -0.0273, +0.4477, +0.0020,
+ -0.8086, +0.3932, +0.1379, -0.9660, -0.2829, -0.2764, -0.4216,
+ -0.1525, +0.0447, +0.4320, +0.5953, -0.4424, +0.4349, +0.1270,
+ -1.0019, +0.8496, +0.1190, -0.0241, +0.3886, -0.2159, +0.1899,
+ +0.2716, +0.2144, +0.1521, +0.6238, -0.0974, -0.1747, -0.4646,
+ +0.1670, +0.0986, +0.2091, -0.4881, -0.5386, +0.7234, -0.2337,
+ +0.0926, -0.2680, -0.1878, +0.3848, +0.1225, -0.1042, -0.8029, +0.0488
+ ],
+ [
+ -0.0194, -0.1207, -0.7887, -0.1932, -0.7671, -0.6160, +0.5836,
+ -0.5835, -0.6046, +0.4231, -0.0390, +0.1148, -0.6782, -0.3514,
+ -0.2648, -0.0168, +0.0781, -0.2630, +0.0882, -0.6942, +0.3235,
+ -0.0105, +0.1153, +0.4368, -0.1751, -0.7266, +0.2544, -1.3023,
+ +0.2659, +0.1671, -0.2608, -0.8921, -0.3162, +0.3498, +0.3295,
+ +0.3511, +0.2690, +0.1425, -0.3212, -0.3263, +0.3445, +0.2796,
+ +0.2022, -0.6122, -0.1682, -0.2297, -0.8197, +0.2056, +0.1508,
+ +0.1413, -0.7759, -0.2761, +0.3577, -0.3738, -0.4012, +0.3824,
+ -0.3468, -0.0403, -0.0345, -1.2605, -0.2159, -0.1952, -0.2995, -1.1620
+ ],
+ [
+ +0.0024, -0.0664, +0.2425, -0.2706, -0.4890, -0.0621, +0.0284,
+ +0.1899, +0.3082, +0.0377, -0.0764, +0.0176, +0.1866, -0.4896,
+ -0.3989, +0.0462, -0.0192, -0.1653, -0.3642, +0.1768, -0.6478,
+ -0.0532, +0.0198, -0.7094, +0.0706, -0.0496, +0.4831, +0.1259,
+ +0.3517, -0.8037, +0.2697, -0.6875, +0.0155, +0.2172, -0.2454,
+ -0.0460, +0.0325, +0.3533, -0.7351, +0.0536, +0.3590, +0.0721,
+ +0.0898, +0.3589, -0.6221, -0.0299, +0.1699, +0.0649, +0.0230,
+ +0.0554, +0.0944, -0.3458, -0.0950, -0.7440, -0.3821, +0.1427,
+ +0.1813, -0.2649, +0.5347, +0.6652, -0.1711, +0.7013, +0.1752, -0.1868
+ ],
+ [
+ -0.1828, -0.6123, +0.6553, +0.1558, +0.3014, -0.4433, -0.7209,
+ +0.2053, +0.3311, -0.1320, -0.4184, -0.1434, +0.0526, +0.3701,
+ -0.0308, -0.3408, -0.2352, -0.3524, -0.1875, +0.2216, -0.2856,
+ +0.0646, +0.1154, +0.2610, +0.2901, +0.2325, -0.2882, +0.0842,
+ -1.1907, -0.2716, -0.7922, +0.7111, -1.2862, +0.0379, -0.4006,
+ +0.0314, -0.4250, +0.1251, -0.0795, +0.1266, -0.8298, -0.1187,
+ +0.3498, -0.9881, +0.0415, -0.7624, -0.0081, +0.6712, -0.3528,
+ -0.0880, -0.9316, -0.5180, +0.5190, +0.0895, -0.6918, -0.7873,
+ -0.9653, +0.2742, +0.1894, +0.0651, +0.0850, +0.3659, -0.0652, +0.4338
+ ],
+ [
+ +0.3964, +0.2627, +0.1103, +0.3970, +0.0069, +0.0609, -0.5005,
+ +0.1489, -0.1099, -0.0272, -0.2021, -0.2302, +0.5451, +0.2993,
+ +0.5454, -0.3649, -0.2674, +0.2017, -0.1702, +0.0644, -0.2060,
+ +0.1508, -0.3876, +0.1846, +0.2237, -0.0312, -0.0015, +0.2604,
+ +0.0666, +0.1684, -0.5425, +0.0538, -0.1207, -0.2343, +0.3771,
+ +0.0393, +0.0222, -0.7628, -0.0214, +0.0529, +0.3262, -0.1331,
+ +0.4950, +0.0991, +0.4385, +0.2752, +0.0735, -0.0804, +0.2287,
+ +0.1171, -0.0309, -0.0385, -0.1264, +0.1230, +0.7229, +0.1880,
+ -0.2943, -0.2166, -0.4507, +0.0930, -0.0285, +0.0990, +0.0044, +0.3985
+ ],
+ [
+ -0.0031, +0.5645, -0.1319, -0.5523, -0.4907, +0.4110, +0.3013,
+ -0.8591, +0.1433, -0.1375, -0.3205, +0.0561, -0.2520, -0.0548,
+ -0.2757, -0.3679, +0.3600, -0.3787, -0.5952, +0.0254, -0.9357,
+ -0.1175, -0.7752, +0.1179, -0.2159, +0.0500, -0.1339, +0.5283,
+ -0.9314, -0.6431, +0.1058, +0.3230, -0.1007, -0.1266, -0.5315,
+ -0.8632, -0.9976, +0.1715, -0.2625, +0.0601, +0.1164, +0.1491,
+ -0.0567, -0.2342, +0.0974, -0.1337, +0.1588, -0.1241, -0.5045,
+ +0.0436, -0.5320, +0.3478, +0.1662, +0.0267, -0.2026, -0.1873,
+ -0.3899, +0.3353, +0.0762, -0.8446, +0.4566, -0.1213, -0.1316, -0.1156
+ ],
+ [
+ +0.0788, -0.5533, -0.0632, +0.4225, -0.1865, +0.1681, +0.0134,
+ +0.7480, -0.3772, +0.5010, +0.2476, -0.1259, +0.3469, +0.4376,
+ +0.2804, -0.0866, -0.1412, -0.3347, -0.3281, -0.5378, +0.2721,
+ -0.0447, +0.0935, -0.0756, -0.1555, -0.8725, -0.0454, -0.0183,
+ -0.1579, +0.0542, -0.1080, -0.3307, +0.2024, +0.3322, +0.0422,
+ +0.1186, +0.3260, -0.2936, -0.3349, -0.4838, +0.0834, +0.0592,
+ -0.6705, -0.3260, +0.0743, +0.2571, +0.2412, +0.0242, +0.2629,
+ +0.0535, +0.5536, -0.2178, -0.6783, -0.1315, +0.1264, +0.3777,
+ +0.0022, +0.5147, +0.0381, -0.7052, -0.4232, +0.3291, +0.0325, -0.8253
+ ],
+ [
+ -0.4288, +0.1143, +0.0962, +0.7745, -0.6219, -0.6415, -0.5820,
+ -0.7458, +0.1792, -0.0657, -0.0073, -0.2255, -0.6996, +0.5389,
+ +0.0176, -0.5660, +0.1982, +0.0434, -0.5836, -0.0448, -0.2092,
+ -0.0071, +0.3852, -0.2947, -0.6535, +0.4864, -0.7791, -0.1412,
+ -0.1299, +0.3475, +0.1343, +0.3463, +0.1048, +0.0316, -0.5184,
+ -0.0222, -0.3967, -0.0674, +0.1681, +0.0684, +0.2178, -0.3731,
+ -0.1102, +0.2250, +0.0125, -0.2276, +0.3460, +0.5391, +0.2497,
+ +0.1035, -0.6424, -0.0980, -0.5851, -0.0769, -0.1334, -0.2680,
+ +0.2863, -0.2820, +0.3512, +0.4946, -0.5509, -0.3891, -0.5598, +0.1242
+ ],
+ [
+ +0.2275, -1.2861, +0.1299, -0.0979, -0.4085, -0.1043, +0.0712,
+ +0.5451, +0.3515, +0.3715, -0.5478, +0.2548, -0.2834, -0.0661,
+ +0.1657, -0.1720, +0.0069, +0.1588, -0.1688, -0.4428, -0.2631,
+ -0.1873, -0.8449, -0.1050, +0.1493, -0.2306, +0.2786, +0.1779,
+ -1.2995, +0.0726, -0.0404, -0.1492, -0.3769, -0.0255, -1.3681,
+ -0.4152, -0.2884, -0.0752, -0.4874, +0.0279, -0.1301, +0.2796,
+ -0.9356, +0.3804, +0.2122, +0.5285, +0.1615, -0.0558, -0.2161,
+ -0.0181, -0.8286, -0.1466, -0.5898, +0.2223, +0.3719, -1.2969,
+ -0.9986, +0.4289, -0.0471, -0.6719, +0.1405, +0.1363, +0.0252, -0.3354
+ ],
+ [
+ -0.3759, -0.6515, +0.0460, +0.0283, -0.8381, +0.3087, +0.3022,
+ -0.2319, +0.1286, -0.1438, +0.1850, -0.1800, -0.1794, +0.0986,
+ -0.1768, -0.0451, -0.2033, -0.1855, +0.6338, -0.4709, -0.5497,
+ +0.7151, -0.4716, -0.5314, +0.1111, +0.2166, -0.0352, -0.0598,
+ +0.3829, -0.0287, -0.0314, +0.0628, +0.1576, +0.2672, -1.1742,
+ -0.4661, -0.9687, +0.1184, -0.5358, -0.7947, +0.2941, +0.3904,
+ +0.5036, -0.0896, +0.1207, +0.1425, +0.2391, -0.0947, +0.0254,
+ -0.0128, -0.7186, -0.0005, -0.2771, +0.0802, -0.2057, -0.1500,
+ -0.0696, +0.1850, +0.3296, -0.1802, -0.8522, +0.1613, -0.3446, -0.9611
+ ],
+ [
+ -0.0172, +0.2102, +0.1269, -0.9535, -0.3040, +0.3378, +0.3050,
+ -0.2810, -0.2334, +0.2156, -0.0862, -0.1692, -0.2226, -0.2373,
+ -0.0424, -0.2194, +0.5642, +0.3826, -0.5695, +0.2485, -1.7143,
+ -0.1864, +0.3349, -0.0294, +0.2349, +0.1219, +0.3391, +0.2065,
+ +0.1599, -0.0162, +0.2464, +0.2802, +0.1396, +0.1066, +0.2178,
+ -0.2903, +0.2673, +0.4015, -0.0220, +0.3709, +0.6791, +0.1762,
+ -1.1385, -0.2852, +0.4311, -1.1372, +0.3373, +0.0017, +0.3223,
+ -0.5834, -1.0435, +0.1683, -1.1370, +0.0143, -0.0677, -0.0824,
+ +0.0469, -0.2916, +0.2428, +0.6020, +0.1504, +0.2878, +0.2507, -0.0694
+ ],
+ [
+ -0.2793, -1.2367, +0.1159, -0.2581, +0.3229, +0.0633, +0.0636,
+ +0.2241, +0.3225, -0.0054, -0.3638, -0.0872, -0.8421, -0.0888,
+ +0.0428, -0.2117, -0.1279, -0.3660, +0.3204, -0.1785, -0.0268,
+ +0.2952, +0.1293, -0.1686, +0.0307, +0.3396, +0.2283, +0.1379,
+ -0.0364, +0.1079, +0.2544, +0.0268, +0.2063, -0.2763, -0.3733,
+ +0.1734, -0.0365, +0.2843, +0.1328, +0.0068, +0.0526, -0.0669,
+ -0.7334, -0.0753, +0.0473, -0.2722, +0.2632, +0.2818, +0.3078,
+ -0.4365, -0.4914, -0.8685, -1.4296, +0.1319, +0.2325, -0.4812,
+ -0.1695, +0.1455, -0.4673, +0.2661, +0.2466, +0.1248, +0.5303, +0.2625
+ ],
+ [
+ -0.2681, +0.0662, -0.5923, -0.3222, -0.6338, -0.5358, +0.6831,
+ -0.0542, +0.4915, -0.0380, +0.0579, +0.3449, -0.6349, +0.4578,
+ +0.0056, -0.2389, -0.0125, -0.6983, +0.0123, +0.5005, -0.3100,
+ -0.1522, +0.1345, +0.5235, +0.6363, +0.1654, +0.1748, +0.2844,
+ +0.2939, -0.2889, +0.2093, -0.3874, -0.0596, +0.1637, -0.5551,
+ -0.2298, -2.1090, -0.6629, +0.3637, +0.1401, -0.3406, -0.2474,
+ -0.2669, -0.6201, -0.4406, +0.1284, +0.8146, +0.2618, -0.2990,
+ +0.5372, +0.4015, -0.4386, -0.3580, +0.3213, -0.1395, -0.1086,
+ -0.3120, +0.3592, -0.1714, -0.9797, -0.2330, -0.2895, +0.5740, -0.0750
+ ],
+ [
+ -0.9698, -0.8484, +0.0831, +0.3071, +0.3030, -0.3330, +0.2211,
+ +0.1237, +0.1860, -1.4592, +0.0474, -0.2930, -0.5213, -0.2863,
+ -0.4018, -0.5164, -0.7680, -1.2742, +0.1244, -0.6117, +0.3339,
+ -0.6391, +0.0054, -0.6506, +0.2615, -0.1341, +0.3390, -0.9834,
+ -0.5222, +0.5488, +0.1504, +0.1792, -0.0281, -0.2283, -0.7494,
+ -0.2537, -0.2610, -0.1271, -0.1880, +0.0840, +0.1234, +0.2401,
+ -0.1056, +0.1950, -0.4009, +0.0054, -0.2824, +0.5646, +0.2155,
+ -0.2039, -0.4253, +0.0929, +0.3874, +0.0945, -0.3247, -0.4850,
+ -0.3040, -1.0356, +0.1536, -0.0128, -0.2592, -0.8912, +0.0705, +0.3209
+ ],
+ [
+ -0.3948, -0.9965, +0.0050, +0.2379, +0.0539, +0.3259, +0.0382,
+ -0.1108, -0.2276, -0.4007, +0.0166, -0.5534, -0.2853, +0.4997,
+ +0.2019, +0.0453, +0.2201, -0.2351, -0.9356, -0.2385, -0.0424,
+ -0.5058, +0.4940, -0.6912, -0.4253, +0.0810, -0.3655, +0.1859,
+ -0.0412, -0.0912, +0.0632, -0.2972, +0.0772, +0.0487, -0.0515,
+ +0.1638, +0.3188, -0.1115, -0.2563, +0.4259, +0.2540, -0.0207,
+ -0.0622, +0.0273, -0.6594, +0.2525, +0.5872, +0.0366, -0.1142,
+ -0.2282, -0.1075, +0.8922, +0.1124, -1.6357, +0.2399, -0.0886,
+ +0.1945, -0.2365, -1.6711, -0.5883, +0.4049, -0.0049, -0.5896, -0.0418
+ ],
+ [
+ -0.4143, +0.1528, +0.4760, +0.1183, +0.0014, +0.2190, -0.0362,
+ -0.8062, +0.3214, +0.1326, +0.2072, +0.1400, +0.4244, -0.3917,
+ -0.8188, +0.4239, +0.1449, +0.2362, -0.5594, +0.6168, -0.3246,
+ +0.3341, -0.5919, +0.0815, +0.4067, +0.1814, +0.4408, -0.4474,
+ -0.2818, -0.0265, -0.1569, -0.4575, +0.4622, +0.2102, +0.1408,
+ +0.1323, -0.2570, +0.1578, +0.1281, +0.2395, +0.0889, +0.0440,
+ +0.3288, +0.3748, +0.0734, -0.1664, -0.5203, +0.0544, -0.0571,
+ +0.2111, +0.2552, -0.6038, +0.4826, +0.0443, -0.2141, +0.4272,
+ +0.2828, -0.6792, -0.6578, +0.3101, -0.0040, +0.2418, +0.1197, +0.0414
+ ],
+ [
+ +0.5036, -0.0710, -0.5354, -0.0832, +0.5295, -0.3346, -0.6920,
+ +0.2490, -0.0346, -0.6139, +0.5644, +0.5261, +0.0128, -0.5987,
+ +0.3123, -0.3102, -0.2144, +0.1843, -0.5506, -0.1807, +0.1333,
+ -0.2694, +0.2776, -0.3190, -0.1241, +0.2397, +0.0467, +0.1639,
+ -0.0202, +0.2547, +0.2727, +0.2766, +0.1032, +0.2433, -0.2080,
+ -0.1870, -0.1091, -1.2571, -0.5648, +0.3736, -0.6316, +0.2332,
+ +0.3590, -0.0994, -0.1051, +0.2673, +0.0045, -0.0055, +0.2778,
+ +0.3100, +0.5339, -0.3611, +0.0369, +0.0216, +0.3185, -0.8140,
+ +0.3609, -0.6879, -0.6326, +0.0915, +0.1364, -0.1097, -0.2144, +0.2251
+ ],
+ [
+ +0.5415, -0.3312, -0.7819, -0.5402, +0.0574, +0.2336, +0.0098,
+ +0.3032, +0.2109, -0.1144, -0.3755, +0.1675, +0.6641, -0.6918,
+ +0.2823, +0.3307, +0.0195, -0.2317, +0.0834, -0.3695, +0.7589,
+ -0.1579, +0.1433, -0.4708, -0.5547, +0.0167, -0.5846, -0.4162,
+ -0.0054, +0.4191, +0.0935, -0.3095, -0.0772, -0.5562, +0.0620,
+ -0.8387, -0.4571, -0.2059, +0.4216, -0.4745, -0.3587, -0.0113,
+ -0.4873, -0.3253, -0.2477, +0.2562, -0.1393, -0.2321, -0.3196,
+ -0.0813, -0.1766, -0.5138, +0.1283, +0.0956, -0.0365, +0.1988,
+ +0.1467, -0.0275, -0.0379, -0.0494, +0.0763, -0.0612, -0.4318, +0.2575
+ ],
+ [
+ -0.2761, -0.9689, -0.3303, -0.7023, -0.4928, -0.3009, +0.0291,
+ -0.4230, +0.5759, +0.0989, -0.8509, -0.1306, -0.0595, +0.1574,
+ -0.0485, +0.5048, +0.3384, -0.1445, -0.2781, -0.4470, +0.0887,
+ +0.2998, -0.0981, +0.6717, +0.0993, +0.1626, +0.2985, -0.0080,
+ -0.0010, +0.0653, +0.2250, +0.6091, +0.1562, +0.1161, +0.5716,
+ -0.2470, -0.4208, -0.5375, -1.1928, +0.1185, +0.8855, +0.3924,
+ +0.0061, -0.1286, +0.2825, -0.3767, -0.3815, +0.1588, -0.6792,
+ -1.0360, -0.1299, +0.4925, -0.0620, -0.7220, -0.7866, +0.1224,
+ -0.1552, -1.0134, +0.5721, -0.7248, -1.0616, -0.5778, +0.3760, -0.2161
+ ],
+ [
+ -0.5326, +0.7165, +0.0792, +0.2508, -0.2711, -0.2975, -0.0981,
+ -0.0309, -0.0226, -0.1754, -0.0990, -0.1178, -0.5456, +0.1010,
+ -0.3404, +0.0810, +0.4984, +0.2788, -0.3860, -0.1752, -0.6125,
+ -1.2417, +0.4557, -0.4470, +0.4315, -0.0454, -0.2439, -0.9114,
+ +0.6899, +0.5681, -0.3259, +0.4912, -1.0011, -0.4782, +0.8627,
+ +0.3346, -0.4200, +0.6671, -0.4101, +0.2222, -0.2604, -1.1758,
+ +0.5707, -0.5659, -0.1541, +0.0028, -0.6961, +0.1943, -1.2026,
+ -0.3061, -0.2279, +0.1856, -0.3946, +0.2157, +0.4633, +0.1402,
+ +0.2419, -0.6997, +0.2056, +0.6528, -0.4918, -0.0056, -0.3281, -0.0303
+ ],
+ [
+ -0.2521, -0.4440, +0.2354, -0.8008, -0.7654, -0.9568, -0.3908,
+ -0.1637, +0.1596, -0.2531, -0.0419, -0.0372, -0.3797, +0.1746,
+ +0.3741, +0.0963, -0.5509, -0.7025, -0.3153, +0.2185, -0.5326,
+ -0.9472, +0.2125, -0.0905, +0.1235, +0.0780, +0.2451, +0.1500,
+ -0.6441, -0.8495, -0.1646, -0.7545, -0.2271, -0.2027, +0.0191,
+ +0.1703, -0.4407, -0.9649, -0.0960, +0.1947, -0.7579, +0.0200,
+ +0.1715, -0.8105, -0.3087, -0.0016, +0.1807, +0.2233, -0.3559,
+ +0.1208, +0.6184, -0.3895, -0.0184, -0.0622, -0.2338, -0.2363,
+ -0.9124, +0.1358, -0.5606, -1.4253, -0.1812, -0.2845, +0.1957, -0.0284
+ ],
+ [
+ +0.2106, +0.1527, +0.0672, -0.4241, -0.5017, -0.5233, -0.2833,
+ +0.0599, -0.2671, +0.2882, -0.0645, -0.3441, -0.0450, +0.3017,
+ +0.5250, +0.0886, +0.1231, -0.3728, +0.3071, +0.0619, +0.3998,
+ +0.4689, -0.4973, +0.0398, -0.0601, +0.0153, -0.6525, +0.3215,
+ -0.3874, +0.0084, -0.9022, -0.6516, +0.0830, +0.1692, -0.2292,
+ +0.1235, -1.1122, -0.0030, +0.4186, -0.2612, -0.8774, -0.6022,
+ -0.1726, -0.3275, +0.1364, -1.1799, -0.0944, -0.1624, -0.3801,
+ -0.0173, +0.1695, -0.3159, -0.1089, +0.2296, -0.4541, +0.0854,
+ +0.3056, +0.2502, -0.1071, -0.1358, -0.6425, -0.2226, -0.5790, +0.0545
+ ],
+ [
+ +0.1139, -0.3351, +0.4969, -0.1394, -0.1872, +0.1136, -0.5034,
+ +0.4215, +0.0047, +0.3804, -0.2160, -0.2978, +0.0770, -0.1280,
+ +0.0935, -0.1517, +0.2508, +0.0238, +0.2649, +0.1492, -0.2315,
+ -0.1531, +0.3535, -0.3587, -0.0937, -0.0271, -0.1757, +0.0513,
+ -0.3445, -0.1265, +0.0707, +0.3534, +0.3746, +0.1297, -0.4518,
+ +0.1721, -0.1487, +0.1188, -0.0693, -0.3754, -0.0135, +0.3600,
+ -0.5287, +0.0960, +0.3786, -0.4262, -0.2394, -0.2733, +0.5393,
+ -0.0416, -0.6425, -0.1794, +0.2697, +0.0738, -0.0440, -0.4378,
+ +0.2735, +0.0333, +0.0073, +0.4403, +0.1354, +0.2958, +0.1619, -0.1507
+ ],
+ [
+ -0.5420, +0.0362, -0.4296, +0.0190, +0.2051, +0.3369, -0.3391,
+ -0.1887, -0.0326, +0.3692, +0.0149, -0.3465, +0.6006, -0.4643,
+ +0.0753, +0.4372, +0.2077, +0.1342, -0.8206, -0.0578, -0.2016,
+ +0.2382, +0.6409, -0.0740, -0.2623, -0.1396, -0.0616, +0.2323,
+ +0.0943, -0.1674, -0.4978, +0.8055, +0.3402, +0.2021, +0.1088,
+ -0.1912, -0.0790, +0.3857, +0.3156, +0.3516, -0.0174, -0.2086,
+ +0.1347, -0.0845, -0.3709, -0.3238, -0.8348, +0.1269, -0.0504,
+ +0.3153, +0.2908, +0.2420, -0.0790, -0.2399, +0.1506, +0.1858,
+ -0.1051, +0.0915, -0.1252, +0.1255, -0.0974, +0.5441, +0.0452, +0.3842
+ ],
+ [
+ +0.0955, +0.0485, +0.3281, +0.0474, +0.3446, -0.6093, -0.4275,
+ +0.3763, +0.3858, -0.1701, -0.1463, +0.2718, +0.2689, -0.3098,
+ +0.0246, -0.4480, +0.0518, -0.1522, -0.8059, +0.2289, +0.1221,
+ -0.3030, +0.1093, -0.1955, -0.0475, +0.0153, -0.3349, +0.1145,
+ -0.8206, -0.0766, -0.1023, +0.2766, -0.0855, +0.0702, -1.0922,
+ -0.3249, -0.5735, +0.0820, +0.3922, +0.2788, -0.0104, +0.0196,
+ +0.0290, -0.1168, -0.3654, -0.3279, -0.0258, -0.2164, +0.0979,
+ +0.1401, -0.9651, -0.2296, +0.0746, -0.2225, -0.2155, -0.7558,
+ +0.2613, -0.0114, -0.8169, -0.1495, +0.2781, +0.3386, -0.9345, +0.2608
+ ],
+ [
+ +0.5088, +0.2218, +0.1765, -0.0331, -0.3075, -0.2475, +0.5497,
+ +0.1426, -0.1553, +0.3819, +0.2006, -0.0863, +0.1830, +0.1197,
+ -0.0123, -0.3290, -0.1844, +0.4336, -0.0328, +0.1667, -0.1849,
+ +0.0575, -0.6713, +0.0672, -0.3829, -0.6262, -0.1215, -0.1144,
+ -0.2839, +0.1405, -0.3369, -0.2201, -0.4221, +0.3506, +0.1168,
+ -0.0560, +0.5997, -0.4228, +0.1629, -0.4290, +0.1672, -0.0236,
+ +0.1454, -0.6296, -0.3503, +0.3121, -0.6164, +0.0040, -0.4038,
+ -0.0525, -0.3641, -0.0239, -0.0257, -0.0226, +0.0809, +0.6442,
+ -0.4453, +0.2383, +0.2805, +0.0694, +0.0128, +0.3397, -0.3719, -0.2788
+ ],
+ [
+ -0.4670, -0.4915, -0.0640, -0.1080, +0.2980, -0.3258, +0.1757,
+ +0.2146, -0.1510, -0.0491, +0.0563, -0.3987, -0.4028, -0.3628,
+ +0.2874, +0.0314, +0.1795, -0.2589, -0.0268, +0.2839, +0.1206,
+ +0.2479, +0.4548, -0.3583, -0.0697, +0.2491, -0.0507, -0.4918,
+ +0.8737, +0.1426, +0.0454, -0.1107, +0.2844, +0.1997, -0.3644,
+ +0.0446, -0.0212, +0.1599, -0.3419, -0.6802, +0.0552, +0.2812,
+ -0.3779, +0.1032, -0.3777, -0.3186, -0.3213, +0.4516, +0.0486,
+ -0.0300, +0.5251, +0.2281, -0.6970, -0.8787, -0.2758, +0.0643,
+ -0.0935, -0.0450, +0.3067, +0.1487, -0.2221, -0.7158, +0.0694, +0.3405
+ ],
+ [
+ -0.0807, +0.1956, -0.7065, -0.1968, -0.4069, -0.5939, +0.1061,
+ -0.5533, -0.0029, +0.1155, +0.5999, +0.2973, -0.1382, -1.8868,
+ -0.0625, +0.1852, -0.3384, -0.3145, -0.7115, -1.2999, +0.2507,
+ +0.0126, -0.6911, -0.0353, -0.2144, -0.5896, +0.2757, +0.1991,
+ +0.4955, +0.1525, +0.0883, -0.3836, -0.5029, -0.9232, -0.0399,
+ -1.1315, -0.3385, -0.4110, +0.6206, -0.0164, +0.0728, -0.1295,
+ +0.3592, +0.1283, +0.1660, -0.8184, +0.2055, +0.0100, +0.0749,
+ -0.1921, -0.7224, -0.3581, +0.3517, -0.5052, -0.1384, +0.2164,
+ -1.1142, -0.2332, +0.1493, -1.4533, +0.0383, -0.1263, +0.3252, -0.5295
+ ],
+ [
+ +0.4723, +0.0690, +0.0814, -0.3747, -0.8142, +0.2669, -0.1641,
+ +0.3448, +0.2360, -0.1284, +0.2488, +0.1250, +0.1398, -0.3875,
+ +0.1035, -1.5125, +0.2221, +0.4065, -0.2947, -0.0980, +0.3115,
+ +0.0269, -0.1230, +0.3413, -0.1347, +0.1201, -0.6609, -0.1416,
+ +0.3478, +0.0002, -0.0886, +0.5476, +0.3687, +0.6390, -0.7058,
+ -1.8022, -0.5987, +0.1807, -0.4258, +0.6345, +0.3594, -0.1921,
+ -0.3109, -0.3026, +0.1414, -0.2782, +0.1817, -0.4103, +0.1402,
+ +0.4675, -0.5731, +0.0838, -0.2392, -0.6368, +0.0406, -0.2823,
+ -0.0034, +0.2043, +0.1200, +0.0025, +0.1826, +0.0479, -0.0833, -2.2805
+ ],
+ [
+ +0.2949, -0.1150, +0.1010, -0.3074, -0.9746, -0.6663, +0.0088,
+ -0.2697, -0.3506, +0.0307, +0.1338, -0.5369, +0.0397, +0.3680,
+ +0.1448, +0.2810, -0.6666, -0.0522, +0.2465, -0.0007, +0.1407,
+ -0.3858, -0.1713, +0.2521, +0.3547, +0.0813, +0.1617, -0.2469,
+ +0.1505, +0.0883, +0.1682, -0.1433, -0.5352, -0.4478, -0.2829,
+ +0.1012, -0.1545, +0.2683, +0.0461, +0.2103, -0.7766, -0.9584,
+ -0.3077, -1.1369, +0.2401, +0.3353, -0.6189, +0.1956, -0.1073,
+ -0.4741, +0.0010, -0.6126, +0.0567, +0.4589, -0.3578, +0.2795,
+ -0.2678, -0.2943, -0.5274, -0.0226, +0.0119, +0.2351, -0.2179, +0.2254
+ ],
+ [
+ -0.2141, +0.1382, +0.4498, +0.6240, -0.3318, -0.7858, -0.0516,
+ -0.4167, +0.1866, +0.2468, -0.3664, -0.8685, -0.0878, +0.1317,
+ +0.1082, +0.4507, -0.2831, +0.1331, -0.0394, +0.0402, -0.2291,
+ +0.3571, -0.3876, +0.0876, +0.4871, -0.8254, +0.2762, +0.0464,
+ -0.3720, -1.0204, -0.2339, -0.3136, -0.3625, -0.3413, +0.1632,
+ +0.5506, -0.3524, +0.3550, -0.4057, -0.4933, +0.3779, +0.0777,
+ +0.0433, -0.1397, -0.3430, -0.0584, -0.1373, -0.0246, -0.6115,
+ +0.3367, -0.2185, -0.0417, +0.4116, +0.2236, -0.0797, -0.0377,
+ -0.7056, +0.2603, +0.0040, -0.0374, -0.2992, +0.1517, -0.6489, +0.0531
+ ],
+ [
+ -0.1267, -0.5069, +0.2074, -0.2553, -0.4368, -0.4911, +0.3021,
+ -0.2026, -0.3328, -0.5599, -0.4192, -0.1039, +0.2192, -0.3493,
+ +0.4454, -0.0429, +0.2264, +0.2224, +0.4339, -0.4501, -0.0765,
+ -1.2330, +0.3052, -0.5080, -0.0426, -0.0030, -0.6783, +0.0537,
+ -0.1739, +0.2823, +0.4150, -0.3388, -0.1453, +0.3024, -0.1280,
+ +0.1714, -0.3645, -0.0861, -0.4287, +0.2726, -0.8224, +0.2332,
+ +0.0662, -0.2844, -0.1834, +0.2771, +0.0497, -0.3258, -0.6752,
+ +0.2520, +0.3726, +0.7169, +0.1558, -0.5803, -0.2885, -0.3842,
+ -0.3185, +0.3158, +0.1080, +0.1682, +0.0620, +0.3014, -0.1028, +0.1426
+ ],
+ [
+ -0.0723, -0.5000, +0.1487, -0.0095, -0.4658, -0.3077, -0.7908,
+ -0.4927, -0.5117, -0.3589, -0.9917, +0.5179, +0.2535, -0.7080,
+ -0.2462, +0.0268, -0.3043, +0.4264, +0.0668, -0.1914, +0.2648,
+ -0.3950, +0.3762, -0.4192, +0.2441, +0.1355, -0.7419, -0.6720,
+ +0.1731, +0.1542, -0.3981, +0.3598, +0.0109, -0.2058, +0.0691,
+ -1.2895, -0.1651, +0.1311, +0.4099, +0.2998, +0.3317, +0.2282,
+ +0.5977, +0.0649, -0.0173, -0.4743, +0.1518, -0.3689, -0.6426,
+ -0.4369, -0.7365, -0.6539, -0.0260, +0.0977, -0.0872, -0.7097,
+ +0.2004, -0.3222, -0.3049, -0.1635, +0.1556, +0.1445, -0.2192, -0.1735
+ ],
+ [
+ -0.8152, -0.2915, -0.2327, -0.2137, -0.1635, +0.2767, -0.0897,
+ +0.0506, +0.3301, -0.6531, -0.1230, +0.2334, -1.0137, +0.4155,
+ -0.2141, -0.3039, +0.1495, +0.2163, +0.2163, -0.0377, +0.0263,
+ +0.2615, -0.2307, +0.6041, -0.0230, +0.2658, -0.3772, -0.7199,
+ +0.1255, -0.3156, +0.5027, +0.0295, -0.0046, +0.0743, +0.1850,
+ +0.2075, -0.5971, -0.3057, +0.0794, -0.3854, +0.0672, +0.2752,
+ +0.5847, +0.5027, -0.6998, +0.3995, -0.0344, -0.5871, -0.4606,
+ -0.6819, +0.4443, -0.6050, +0.0125, -0.0160, +0.0141, -0.2969,
+ +0.0984, -0.2110, +0.1360, -0.0030, -0.2199, -0.2806, -0.4028, -0.2105
+ ],
+ [
+ +0.0086, +0.2366, -0.2388, -0.7499, +0.3473, -0.3351, +0.4687,
+ -0.6588, +0.3916, -0.8119, -0.5929, +0.2525, -0.7352, -0.2726,
+ +0.2062, +0.0520, +0.3612, -1.1951, +0.2574, -0.5112, -0.1439,
+ +0.1617, +0.1917, -1.9899, -0.1703, +0.3676, +0.2320, -0.0203,
+ -0.4018, +0.3225, +0.0675, -0.5493, -0.1561, +0.2205, +0.1122,
+ -0.8326, -0.9873, -0.2357, +0.6072, +0.3998, +0.0549, -0.2751,
+ +0.0890, -0.3323, +0.0969, -0.1550, +0.3064, +0.4299, +0.1660,
+ -0.1824, +0.2009, -0.3313, -0.0823, -0.2167, -0.1848, +0.2666,
+ +0.2336, -0.1165, -0.3577, -0.6992, +0.3805, -0.4676, +0.1645, +0.1216
+ ],
+ [
+ -0.5994, +0.2128, -0.4627, +0.0702, +0.3855, +0.1554, -0.0293,
+ +0.3617, +0.3152, -0.1431, +0.4439, +0.2291, -0.1586, -0.0755,
+ -0.4190, -0.3665, -0.0843, +0.0891, -0.2107, +0.1810, +0.1604,
+ +0.1431, +0.3822, -0.2960, +0.0394, +0.2106, -0.3115, +0.0588,
+ -0.0221, +0.2901, +0.2319, +0.0913, +0.0881, +0.1558, +0.2094,
+ -0.5158, -0.0340, +0.0142, +0.1323, +0.2055, -0.3577, +0.3536,
+ +0.0224, +0.0234, +0.0999, +0.3119, +0.0797, -0.4424, -0.2596,
+ +0.1601, -0.2896, -0.6153, +0.1903, -0.0908, +0.1287, +0.0787,
+ +0.1265, -0.8994, -0.5396, -0.0339, +0.2975, -0.2216, +0.1704, -0.1286
+ ],
+ [
+ -0.0142, +0.2379, -0.1136, -0.0227, +0.0428, +0.2032, -0.2604,
+ -0.5311, +0.0952, +0.2859, +0.2672, -0.3840, +0.2569, -0.5696,
+ +0.0714, -0.2037, +0.3220, +0.2425, -0.1276, -0.7212, +0.2417,
+ -0.0748, +0.2104, -0.1355, -0.2372, +0.0144, +0.4330, -0.0108,
+ -0.7008, +0.1504, -0.4478, -0.3534, -0.0906, +0.0781, +0.0750,
+ +0.3150, +0.0884, +0.5228, +0.0073, +0.1359, +0.2701, -0.2142,
+ -0.2422, -0.4849, +0.2584, -0.1368, -0.1542, +0.3142, +0.1448,
+ +0.0291, +0.1900, -0.3429, -1.3660, -0.1068, -0.0261, +0.0589,
+ +0.3062, +0.1114, -0.3424, -0.0476, -0.0689, -0.0977, +0.6588, +0.1288
+ ],
+ [
+ +0.1364, -0.1144, +0.1574, -0.3419, +0.1935, -0.0943, +0.2272,
+ -0.1504, +0.3254, +0.3180, -0.3487, +0.5566, -0.9484, -0.0958,
+ +0.1641, -0.5995, -0.2025, -0.2777, +0.0415, -0.1855, -0.1811,
+ -0.1807, +0.1249, -0.1251, -0.1046, -0.2293, +0.3936, -0.1513,
+ +0.0573, +0.0934, -0.0753, -0.0327, +0.0111, -0.0191, -0.4537,
+ +0.2813, +0.2061, -0.0505, +0.0374, -0.0946, +0.3502, +0.0734,
+ -1.0019, -1.0110, +0.3520, -0.3134, -0.0215, -0.2545, +0.1434,
+ -0.5697, -0.7286, -0.4365, -1.6550, +0.0742, -0.7167, -0.1912,
+ -1.1841, +0.0912, -0.6878, -0.3645, +0.2087, +0.5016, -0.1441, +0.1419
+ ],
+ [
+ -0.1610, -0.7360, +0.1001, -0.5159, -0.1114, -1.3956, -0.4303,
+ -0.1506, +0.0529, +0.1836, +0.2128, -0.3067, +0.0156, +0.1256,
+ -0.0579, -0.0213, -0.0353, -0.3984, -0.5750, -0.3961, +0.4362,
+ -0.0910, +0.2649, +0.1807, -1.0079, -0.6953, -0.4110, -0.0544,
+ -0.1440, -0.0898, +0.3983, +0.0142, +0.3467, +0.0764, +0.5826,
+ -1.0772, +0.1329, +0.1583, +0.4074, -0.4069, -0.2080, +0.0637,
+ -0.2797, +0.1188, -0.0272, +0.0528, -0.1775, +0.1708, -0.1801,
+ +0.3543, +0.1264, -0.8590, -0.4402, -0.3558, +0.3612, -0.3962,
+ +0.1641, +0.2552, -0.6210, -0.3405, -1.3635, -0.3804, -0.0130, -0.2085
+ ],
+ [
+ -0.3926, -0.4244, -0.8905, -0.1961, -0.1443, -0.9498, -0.3382,
+ -0.8519, -0.6429, -0.2444, -0.1375, -0.5616, +0.4198, -0.5713,
+ -0.2244, -0.1486, -0.1400, -0.2307, -0.0475, -0.2259, +0.1446,
+ +0.2832, -1.2677, -0.6729, +0.6527, +0.4285, -0.5992, +0.0715,
+ -0.6911, -0.4754, -0.9201, -0.4254, -0.7185, +0.0664, -0.4074,
+ -0.4005, -0.1831, +0.2600, -0.4282, -0.1873, -1.4707, +0.5088,
+ -0.4531, -0.0573, +0.4479, -0.3896, -1.3122, -0.2406, -0.7760,
+ -0.0552, -0.1311, +0.2692, -0.2829, -0.2300, -0.9993, +0.2252,
+ +0.6695, +0.0364, -0.1045, +0.0466, -0.8347, -0.3719, +0.2533, +0.1563
+ ],
+ [
+ -0.2412, +0.3157, -0.0911, -0.9888, +0.6987, +0.2569, -0.2099,
+ -0.1531, -0.3486, -0.3566, -0.1593, -0.0828, -1.2565, -0.1513,
+ -0.1533, -0.0785, -0.5587, +0.3774, +0.5322, +0.0573, -0.3218,
+ -0.0546, -0.1710, +0.2196, -0.1172, +0.2556, +0.2856, -0.2720,
+ +0.0261, +0.2103, +0.0640, -0.0452, -0.2239, -0.0712, +1.1437,
+ -0.7186, -0.2894, +0.5009, +0.1654, +0.1889, +0.5348, -0.2929,
+ +0.3507, +0.1541, -0.2035, -0.4617, +0.2521, +0.2938, +0.0196,
+ +0.1961, -0.5070, +0.5579, -0.1937, +0.0963, +0.1044, -0.1526,
+ +0.7057, -0.7649, -0.1567, -0.0077, -0.2938, +0.1193, -0.1897, -0.1215
+ ],
+ [
+ +0.3582, +0.0938, -0.0087, +0.2090, -0.9981, +0.3406, +0.2442,
+ +0.2977, +0.0398, -0.1321, +0.1777, -1.1774, +0.5394, -0.2764,
+ -0.0729, +0.1203, -0.0837, +0.1776, -0.1322, +0.3963, +0.0025,
+ +0.0991, -0.0755, -0.3995, +0.1701, +0.1077, -0.0413, -0.4130,
+ +0.0422, +0.2433, +0.0258, -0.1082, -0.1366, +0.0227, +0.0329,
+ -0.1431, +0.0231, -0.2993, -0.0951, -0.0591, -0.0835, +0.0814,
+ +0.0316, -0.3648, +0.4959, +0.4102, +0.2490, -0.3487, +0.2844,
+ +0.3580, -0.2262, -0.2718, +0.0704, +0.0435, +0.1235, +0.8514,
+ -0.3005, -0.6121, -0.0672, -1.0684, +0.2366, +0.1307, +0.2148, -0.4796
+ ],
+ [
+ +0.8412, +0.5887, -0.4191, +0.0875, -0.4845, +0.6013, +0.5707,
+ +0.3917, -0.0227, +0.4339, -1.0224, -0.7570, +0.3608, -0.2532,
+ +0.1064, +0.6448, -0.2207, -1.2217, +0.1895, -0.0188, +0.3665,
+ -0.4125, -0.2246, -0.3406, -0.3777, +0.1114, +0.0960, -1.4468,
+ +0.2017, -0.1103, -0.5602, -0.0740, -0.1705, -0.0307, +0.6227,
+ +0.5056, +0.0644, -0.3713, +0.2553, -0.0499, -0.1112, -0.3409,
+ +0.2212, +0.5274, +0.1242, -0.0929, +0.5207, -0.3954, +0.2206,
+ +0.6032, -0.1240, -0.3202, +0.5229, -0.3248, -0.2238, +0.0788,
+ +0.1125, -1.5450, -0.2782, -0.3103, +0.4263, +0.5339, -0.4021, -0.0213
+ ],
+ [
+ -0.1685, +0.2132, +0.2234, +0.1307, -0.4110, -0.3189, -0.4531,
+ +0.1865, -0.0200, -0.0282, +0.5585, -0.4741, -0.0928, -0.1840,
+ -0.4882, +0.0903, +0.2165, -0.3946, +0.1760, +0.4589, -0.1230,
+ +0.2934, +0.0979, +0.1098, +0.2834, +0.4592, -0.6382, +0.1312,
+ -0.7111, -0.3250, +0.0696, -0.2336, -0.1130, -0.1304, +0.4843,
+ +0.3157, -0.8460, -0.0586, +0.4201, -0.3655, +0.0920, +0.6134,
+ +0.3466, +0.2227, -0.4758, -0.0722, +0.0661, -0.9082, -0.1224,
+ +0.4001, -0.6238, +0.0766, +0.4568, +0.8708, +0.3388, -0.4030,
+ -0.1210, +0.0577, -0.0684, +0.1317, +0.0379, -0.7594, -0.8605, +0.1362
+ ],
+ [
+ +0.3891, -0.0004, +0.0555, -0.1140, -0.3759, +0.1374, +0.3610,
+ +0.0419, -0.3176, +0.3248, +0.2752, +0.0961, +0.4376, +0.2473,
+ +0.0575, +0.2554, -0.7989, +0.5068, -0.1314, -0.2717, -0.3923,
+ +0.1135, -0.3779, +0.1417, -0.0900, -0.5626, +0.0551, -0.1210,
+ -0.0790, -0.1690, -0.5073, -0.6554, -0.4579, -0.0294, +0.2184,
+ +0.3044, +0.3497, -0.7188, -0.2664, -0.7073, +0.2607, -0.2781,
+ +0.4217, -0.8461, -0.1371, +0.2458, +0.1470, -0.0571, +0.3661,
+ +0.1540, +0.0704, -0.1645, -0.1654, +0.2660, -0.1874, +0.7393,
+ -0.3254, +0.3798, +0.0534, -0.3681, -0.4176, +0.4060, -0.2834, -0.0005
+ ],
+ [
+ -0.0320, +0.0778, -0.0580, +0.5162, -0.3992, -0.2747, +0.3408,
+ +0.2020, -0.1224, -0.8774, +0.2791, -0.7213, -0.6805, +0.3189,
+ -0.0929, +0.0764, +0.4005, -0.1066, -0.1712, -0.7954, +0.0733,
+ +0.2352, -0.1182, +0.1373, +0.3099, +0.0808, -0.5416, +1.1081,
+ -0.5261, -0.2217, -0.0330, -0.1539, +0.2503, +0.5595, -0.2014,
+ +0.1417, +0.2703, -0.1015, +0.8298, -0.3646, +0.1370, +0.2641,
+ +0.2149, +0.1676, -0.4836, -0.0130, -1.0195, +0.0247, -0.0851,
+ -0.9918, -0.0406, +0.0383, -0.0550, +0.4607, +0.2914, +0.1750,
+ +0.2401, +0.3667, -1.1202, -0.3222, -0.0731, -0.0615, -0.3787, +0.4553
+ ],
+ [
+ -0.4131, -0.5941, -0.6169, -0.6164, -0.4406, -0.3381, -0.1022,
+ -0.0502, -0.0368, +0.4848, -0.4012, -0.1352, -0.2898, -0.0027,
+ +0.1197, +0.2204, +0.1906, -0.7479, -0.4403, +0.1008, -0.3108,
+ -0.3402, +0.4565, -1.1084, +0.1237, -0.2884, +0.0959, -0.1072,
+ -0.5372, +0.1698, +0.1137, -0.1729, +0.5687, -0.0171, -0.5504,
+ +0.5379, -0.0916, +0.3523, +0.1967, -0.8104, -0.2025, +0.3720,
+ -0.5468, -0.4242, -0.1023, -0.2784, +0.1138, +0.1413, +0.7391,
+ -0.3176, +0.4443, -0.2557, +0.1129, -0.3916, -0.7132, +0.2897,
+ -0.1364, +0.4325, -0.6139, -0.3159, +0.0334, +0.3121, -0.0236, -0.6013
+ ],
+ [
+ +0.3438, -0.2672, -0.2729, -0.8516, -0.7865, +0.2380, -0.2967,
+ -0.1444, -0.1531, +0.4419, +0.0100, -0.5118, +0.0695, -0.6206,
+ +0.0933, +0.3544, +0.5651, -0.2669, -0.5611, -0.1266, -0.1960,
+ +0.2097, +0.5543, +0.2757, -0.2284, -1.5897, +0.0603, +0.2600,
+ -0.0583, +0.0183, -0.1176, +0.2799, -0.0466, +0.1799, -0.1208,
+ +0.1377, +0.1683, -0.3353, -0.5734, -0.5524, -0.5980, +0.1921,
+ +0.2213, -0.5839, +0.0293, -0.6613, -0.6761, +0.0707, -0.3450,
+ -0.1691, -0.2508, -0.2959, +0.2573, -0.0742, -0.3314, +0.0760,
+ +0.5143, -0.5326, +0.1858, +0.0744, +0.3574, +0.2932, -0.6550, -0.1763
+ ],
+ [
+ -0.1878, +0.3530, +0.2846, -0.4720, -0.6593, +0.2894, +0.1681,
+ +0.1220, +0.3990, -0.5962, +0.3605, -0.2635, +0.0589, -0.0482,
+ -0.3337, +0.0602, +0.1452, -0.1377, +0.1189, +0.7641, +0.2783,
+ +0.3026, -0.2819, +0.1425, +0.4815, -0.0261, -0.6602, +0.2245,
+ +0.1700, -1.0549, +0.3293, -0.0214, -0.2830, +0.2202, +0.1940,
+ +0.3953, -0.5394, -0.2268, -0.0700, -0.5736, +0.0992, +0.3600,
+ +0.1267, +0.3211, -0.5622, -0.1395, -0.2889, -0.1606, +0.0129,
+ +0.4565, -0.0817, -0.3216, +0.0586, -0.3770, +0.1933, +0.5314,
+ -0.2282, +0.5116, -0.3646, -0.0844, -0.1667, +0.2177, -0.4722, +0.1682
+ ],
+ [
+ -0.6046, -0.0019, +0.7055, +0.0671, -0.5065, -0.8512, -0.0155,
+ -0.0531, +0.1195, -0.4814, -1.2434, -0.3227, +0.3413, -0.8682,
+ -0.8491, +0.6140, +0.2121, +0.0350, -0.3647, +0.6926, +0.0886,
+ -0.5127, +0.5188, -1.3790, -0.6758, -1.0013, +0.3871, +0.3379,
+ -0.2159, +0.0706, +0.5615, +0.7641, -0.0087, +0.0456, +0.4031,
+ -0.1160, +0.5081, -0.1776, -0.3154, +0.2156, +0.5289, -0.0052,
+ -0.2746, +0.2361, -0.7520, -0.1301, +0.3298, -0.1321, +0.4440,
+ -0.6782, -0.2450, -0.2377, -0.1662, -0.1527, +0.1268, -0.2387,
+ +0.8365, -0.9122, -0.1251, -0.1620, -0.0842, +0.3611, -0.2000, +0.5543
+ ],
+ [
+ -0.3054, -0.1114, -0.2290, +0.4891, -0.7619, -0.0520, -0.3236,
+ -0.6297, +0.3625, -0.1399, -0.2639, -0.1181, +0.0798, -0.3294,
+ -0.2301, +0.1280, +0.3002, +1.0975, -0.2288, -0.0913, -0.9323,
+ -0.1649, +0.3137, -0.1293, +0.2304, +0.2064, -0.4795, -0.1544,
+ -0.0805, -0.1257, -0.1547, +0.1534, -0.4968, -0.5140, -0.0610,
+ +0.5317, -0.6079, +0.2771, +0.2970, -0.1766, -0.4933, -0.0424,
+ +0.7516, -0.4173, -1.1842, +0.3461, -0.0435, +0.1062, -0.8075,
+ -0.5636, +0.7547, +0.0459, -0.3499, +0.1656, -0.4118, -0.5384,
+ -0.4461, -0.0754, -0.0632, -0.2161, -0.3203, +0.0456, +0.0656, -0.2893
+ ],
+ [
+ +0.0842, +0.2350, -0.2874, -0.7300, -0.3664, +0.3465, +0.1789,
+ +0.2259, +0.0675, -0.2017, +0.2220, +0.0256, +0.3503, +0.5651,
+ +0.0252, +0.0729, -0.0869, -0.1370, -0.2466, +0.0226, -0.2938,
+ -0.2426, -0.4704, +0.0995, +0.1053, +0.4180, +0.2697, +0.1746,
+ +0.2504, -0.3138, -0.4582, -0.6039, -0.1333, +0.0827, -0.1264,
+ +0.3337, -0.4454, -0.5489, -0.3235, -0.3897, -0.2475, -0.1961,
+ +0.1282, -0.4765, -0.3531, +0.3029, +0.5360, +0.0134, -0.0629,
+ +0.3819, +0.1028, -0.2920, -0.3325, +0.0562, -0.1956, +0.1254,
+ -0.6301, +0.3737, -0.1224, -0.8364, -0.5796, +0.2944, -0.1286, -0.4786
+ ],
+ [
+ +0.2911, -0.2918, -0.2983, -0.1799, +0.5004, +0.1641, -1.8806,
+ +0.2665, +0.2884, -1.0550, +0.6388, +0.1462, +0.1680, -0.0982,
+ -0.0077, -0.0693, -0.3434, +0.2433, +0.3355, -0.1851, +0.0465,
+ +0.1885, +0.2110, -0.2517, -0.3897, -0.4081, +0.1757, -0.3554,
+ +0.5196, +0.3916, -0.0051, +0.2256, -0.0817, +0.3246, +0.0079,
+ -1.0587, +0.0605, -0.2847, +0.1970, +0.4176, +0.2595, -0.6440,
+ -0.2987, -0.0802, -0.0082, +0.0894, +0.2301, +0.1005, +0.0890,
+ +0.0689, +0.3122, -0.3237, -0.6040, +0.0348, -0.5192, -0.2683,
+ +0.4273, -0.0652, -0.1506, -0.2352, +0.0493, +0.0534, +0.2133, +0.0982
+ ],
+ [
+ +0.3272, +0.1324, +0.0023, -0.2772, -1.0236, +0.0239, -0.2064,
+ +0.0468, -0.2204, +0.2162, -0.1171, -0.3942, +0.2313, -0.0039,
+ +0.0945, -0.2131, +0.2256, +0.7016, -0.0260, +0.1757, -0.0407,
+ +0.3079, -0.3533, +0.2725, +0.5806, +0.5924, -0.3883, -0.1294,
+ -0.1834, +0.1339, -0.1177, -0.2016, +0.1945, -0.3999, -0.2208,
+ +0.2980, -0.0075, +0.0909, +0.0309, -0.7034, +0.3555, -0.0051,
+ -0.2755, +0.0161, +0.5550, -0.4416, +0.1154, +0.2074, -0.2569,
+ -0.4099, -1.0087, -0.3479, +0.4183, -0.0786, -0.1718, +0.1801,
+ -0.0383, -0.1651, -0.2073, +0.4251, +0.1538, -0.1537, +0.3422, -0.5363
+ ],
+ [
+ -0.0005, -0.0823, -0.4054, -0.4387, -0.9801, -0.7941, -0.6260,
+ -0.2934, +0.2604, -0.4400, +0.4142, +0.2642, +0.2926, -0.0690,
+ +0.2422, -0.0340, +0.1123, -0.5302, -0.3629, +0.0005, -0.2184,
+ -0.9489, +0.2292, +0.4085, +0.1849, +0.4804, -0.1979, +0.4252,
+ -0.0989, -0.5815, -0.1266, -0.0716, +0.2599, +0.2402, -0.1451,
+ -0.1020, -0.4833, -0.0605, +0.2253, -0.3367, -1.1238, -0.3284,
+ -0.0642, -0.2709, +0.0412, -0.0656, +0.2200, +0.3204, +0.0376,
+ +0.2544, -0.0845, -0.7557, -0.1007, -0.0697, -0.3928, -0.0440,
+ -0.3349, -0.1664, +0.1248, -0.1058, -0.1661, -0.5682, -0.1187, -0.4495
+ ],
+ [
+ +0.3877, +0.1701, +0.2470, +0.3815, -0.7099, +0.4480, -0.3912,
+ +0.0509, +0.3866, +0.0605, -0.1034, -1.1513, -0.0388, +0.1839,
+ -0.0730, +0.2069, +0.1406, -0.2765, +0.0556, +0.3360, +0.3587,
+ +0.2648, -0.1238, -0.1401, -0.1359, -0.1055, +0.1128, +0.1099,
+ +0.0895, -0.2581, -0.3244, -0.2875, -0.0157, +0.3111, -0.3051,
+ +0.1191, -0.2008, +0.0276, +0.4500, -0.3447, -1.8635, -0.0225,
+ -0.0287, -0.1122, -0.3062, +0.0934, +0.0968, -0.0839, +0.1880,
+ +0.3712, -0.1919, +0.3895, -0.4872, -0.2177, -0.0260, +0.5779,
+ +0.1781, +0.4362, +0.3131, -0.8176, +0.2263, -0.5366, -0.3734, -0.2069
+ ],
+ [
+ -1.1235, -0.9674, -0.0259, +0.2390, -0.2322, -0.4858, -0.0673,
+ -0.0436, +0.4784, -0.5001, -0.1335, -0.0299, -0.1177, +0.5094,
+ -0.0886, -0.6063, -0.8532, +0.0729, +0.2496, -0.1499, -0.6113,
+ +0.1188, +0.1059, +0.1600, +0.0897, -0.1650, +0.7303, -0.6695,
+ +0.0782, +0.4738, -0.0097, +0.4754, +0.1041, -0.5552, -0.1545,
+ +0.1880, -0.0279, -0.6501, -0.4160, -0.1361, -0.0866, -0.3986,
+ +0.0944, +0.2977, -0.1807, +0.2639, +0.4842, +0.6219, +0.3545,
+ -0.1240, +0.1304, +0.2634, -0.0749, -0.1111, -0.1349, -0.0482,
+ -0.3663, -0.2051, +0.1262, +0.0840, +0.2020, -1.6679, +0.1338, -0.0481
+ ],
+ [
+ -0.0692, -1.0423, -0.6125, -0.4597, +0.0297, -0.4761, -0.4631,
+ -0.3290, -0.2766, +0.0555, +0.3061, -0.1475, -0.8444, -0.3880,
+ +0.2820, -0.4371, -0.0310, -0.8606, -0.9039, +0.0020, -0.0050,
+ +0.0948, +0.2473, -0.7799, -0.3398, -0.6164, -0.5401, -0.4733,
+ -0.4821, +0.4097, -0.5277, -0.2846, +0.0884, -0.2126, -0.0294,
+ +0.0071, +0.0244, +0.2756, -1.3022, +0.1808, -0.1945, -1.1679,
+ -0.4115, -0.1681, +0.4425, -0.0881, -0.1101, +0.2275, +0.1305,
+ -0.2721, -0.1444, -1.7055, -0.4794, +0.2592, +0.0446, -0.0600,
+ +0.2102, -0.1754, +0.0657, -0.2513, -0.1904, +0.1755, +0.3229, -0.0288
+ ],
+ [
+ +0.5168, -0.4403, +0.1617, -0.0585, -0.1969, -0.4617, -0.4481,
+ -0.5496, +0.5089, -0.7188, -0.1878, -0.1813, -0.2418, -0.0046,
+ +0.3130, -1.7845, +0.0638, -1.0377, -0.0172, -0.2044, -0.3992,
+ -0.5402, -0.5061, +0.3127, +0.3964, +0.1543, +0.1298, +0.1039,
+ +0.0507, +0.1353, -0.5773, -0.3090, +0.3562, +0.6026, -0.3442,
+ +0.3625, -0.6769, -0.1507, +0.1097, -0.3716, +0.0978, +0.0150,
+ -0.0408, -0.0370, +0.4052, -0.0185, +0.2788, -0.1076, -0.2841,
+ +0.0922, +0.1425, -0.2230, -0.8524, +0.0620, -0.5464, -0.1797,
+ +0.1239, +0.0314, +0.2159, -0.6538, -0.0031, -0.7640, -0.0217, -0.4866
+ ],
+ [
+ +0.2358, -0.2772, +0.2595, +0.6524, +0.3488, +0.0607, +0.1904,
+ +0.1577, +0.0482, +0.1901, -0.1420, -0.2318, +0.0705, +0.7032,
+ +0.1648, -0.1761, -0.3265, -0.1246, -0.2734, +0.1199, -0.5026,
+ +0.2313, -0.3349, +0.0078, -0.0800, -0.2408, +0.1623, -0.3919,
+ +0.3836, -0.0706, -0.6569, -0.6874, -0.2303, -0.1488, -0.2527,
+ +0.1399, -0.0429, -0.8683, +0.0116, -0.2729, +0.1803, -0.3104,
+ -0.0248, -0.2009, -0.3645, +0.8482, +0.2003, +0.1095, -0.2804,
+ +0.1855, +0.0342, -0.5573, -0.9607, +0.4382, +0.2139, +0.0982,
+ +0.0443, +0.1411, +0.0551, -0.1386, -1.3499, +0.2195, -0.0387, -0.1416
+ ],
+ [
+ -0.0189, -0.4482, -0.0687, -0.4171, -1.1698, +0.0934, -0.2861,
+ -0.1069, +0.2478, -0.2631, -0.6573, +0.4906, +0.3018, -0.2749,
+ -0.8819, -0.4961, -0.1743, +0.3760, -1.2279, +0.2292, +0.2814,
+ -0.0434, -0.4484, -0.1545, +0.3929, +0.0769, -0.0394, -0.0692,
+ -0.3811, -0.1864, +0.0444, -0.2080, -0.1870, -0.1867, +0.2350,
+ -0.7152, -0.1055, +0.0963, -1.0288, +0.0322, +0.2215, -0.4954,
+ +0.3377, -0.1467, +0.0027, -0.0491, -0.3208, -0.8264, -0.2718,
+ -0.2542, +0.0741, -0.2323, -0.1001, -1.0198, -0.2890, -0.1343,
+ -0.2319, -0.4908, +0.3050, -0.0255, +0.0115, -0.0030, -0.2358, -0.4015
+ ],
+ [
+ -0.1719, -0.4269, +0.5157, -0.3660, +0.0783, -0.2254, -0.7160,
+ +0.3215, +0.4847, -0.6721, -0.1024, +0.0750, -0.4257, +0.0658,
+ +0.1847, +0.2579, +0.1711, +0.1768, +0.0540, +0.0076, -0.0497,
+ +0.0019, -0.3865, +0.1233, +0.1422, +0.4548, +0.1440, -0.4759,
+ -1.1967, +0.2683, +0.1576, -0.0557, -0.8877, +0.3377, -1.0919,
+ -0.1791, -1.1117, +0.2514, -0.5695, +0.2673, -0.7146, +0.1625,
+ -1.1816, -0.2575, +0.2272, -0.9284, -0.4375, -0.2500, -0.5735,
+ +0.1477, -0.2161, -0.1063, -1.0993, +0.2553, -0.0129, +0.3550,
+ -0.4742, +0.1937, -0.5110, -0.4952, +0.3438, +0.0144, -0.0949, -0.1458
+ ],
+ [
+ +0.0636, +0.2933, -0.1864, -0.4025, -1.0270, -0.2597, -0.0660,
+ -0.2247, -0.0048, -0.6861, +0.1695, +0.1418, +0.1761, +0.2443,
+ -0.1339, -0.1673, +0.0148, +0.0555, -0.2577, -0.2610, -0.4787,
+ -0.4025, +0.3526, +0.0557, -0.3496, +0.5078, -0.8030, +0.4197,
+ +0.2154, -0.6415, -0.3827, -0.1026, -0.0396, +0.0502, +0.0724,
+ -0.2952, +0.4268, -0.0801, +0.2876, -0.1107, +0.4451, -0.2080,
+ +0.3860, -0.4921, -0.1323, -0.8016, -0.3088, +0.2469, -0.0782,
+ -0.1180, +0.0223, +0.0847, -0.0293, -0.6148, -0.1082, -0.2367,
+ -0.6443, +0.0539, +0.0207, -0.1587, -0.1582, +0.1998, -0.4013, +0.2739
+ ],
+ [
+ +0.0038, +0.1245, -0.3433, -0.4856, -0.4741, +0.4551, +0.5898,
+ -0.1498, +0.2642, +0.3023, +0.1732, -1.0681, -0.1445, +0.1467,
+ +0.0002, -0.1426, -0.9189, +0.1320, +0.0581, +0.0967, -0.0914,
+ +0.0801, +0.0305, +0.0327, +0.0905, -1.0551, +0.1300, -0.7099,
+ +0.2902, +0.1220, -0.1958, +0.0704, -1.2429, -0.1132, -0.2477,
+ +0.2343, -0.2246, -0.5217, -0.1491, -0.4591, +0.3662, -0.3556,
+ -0.6157, -0.8142, -0.1378, +0.1513, +0.2413, -0.0337, +0.6665,
+ -0.2057, +0.1610, -0.1389, -0.5894, +0.0005, +0.0621, +0.6012,
+ -0.1235, +0.5874, -0.5528, -0.2310, -0.1762, +0.1297, -0.1719, +0.0325
+ ],
+ [
+ +0.0008, +0.2486, +0.3471, -0.6321, +0.3799, -0.0780, -0.0376,
+ +0.0776, +0.2057, -0.6391, +0.1711, -0.0638, +0.0299, +0.1975,
+ -0.0466, -0.0290, -0.0443, +0.0426, -0.3097, +0.0908, +0.1078,
+ -0.3136, -0.0517, -0.0219, -0.3360, +0.3552, +0.2264, -0.8491,
+ +0.1069, +0.0375, +0.1422, -0.0855, -0.4314, +0.1987, -0.7457,
+ -0.4619, -0.2737, +0.4460, +0.0367, -0.0661, +0.1025, +0.4836,
+ +0.1807, +0.0178, -0.7587, -0.1794, -0.1558, -0.3419, -0.4544,
+ -0.3955, +0.2712, -0.4674, -1.1360, +0.0936, -0.1987, -0.1250,
+ -0.3655, -0.0430, -0.1751, +0.2196, +0.0193, +0.1743, -0.4942, +0.3843
+ ],
+ [
+ +0.1284, -0.8808, +0.3882, -0.1527, -0.0198, +0.0071, -0.1231,
+ -0.0403, -0.3053, +0.7561, -0.8750, -0.7770, +0.2674, -0.1818,
+ +0.0836, +0.1696, +0.1877, -0.2631, -0.7180, -0.1721, -0.3764,
+ +0.5574, +0.3879, -1.7586, +0.1584, +0.0229, -0.2597, -0.2745,
+ -0.0041, -0.7704, +0.2686, -0.6262, +0.2735, +0.2018, -0.1796,
+ +0.2239, +0.4402, +0.2529, -0.5100, -0.0231, -0.2497, -0.2817,
+ -0.1345, -0.3458, -0.2159, +0.2782, -0.1067, -0.4089, -0.1312,
+ +0.1312, +0.2225, +0.5538, -0.0014, -0.2335, -0.2113, +0.3140,
+ -0.2814, -1.0457, +0.2956, -0.0813, -0.0878, -0.2742, -0.2099, -0.1060
+ ],
+ [
+ +0.0774, -0.7316, +0.2640, +0.2897, +0.0154, -0.2817, -0.2962,
+ -0.2956, -0.2675, -0.0654, +0.2018, -0.3843, +0.1061, +0.3959,
+ -0.1483, -0.3143, -0.0607, -0.0341, -0.9169, +0.0874, -0.4429,
+ -0.4101, -0.2229, -0.0070, -0.2998, -0.5374, -0.1129, -0.5779,
+ -0.0182, -0.0070, +0.0043, -0.6822, -0.7798, +0.1554, -0.0940,
+ +0.1911, +0.5163, -0.1492, +0.3483, -0.5709, +0.0793, +0.2243,
+ +0.4628, +0.3321, -0.4983, -0.0078, +0.0161, -0.0902, +0.1897,
+ -0.1736, +0.2867, -0.3187, -0.8528, +0.5943, -0.6071, -0.3823,
+ -0.2354, +0.0569, +0.0469, -0.0745, +0.0970, +0.3657, -0.8127, +0.1084
+ ],
+ [
+ -0.0145, -0.5299, +0.2584, -0.1679, -0.5984, -0.9276, +0.2116,
+ +0.3666, -0.3246, -0.1920, -0.4188, -0.4159, +0.5277, -0.6807,
+ +0.1607, +0.1703, -0.5065, -0.0285, -0.0377, +0.3741, -0.5164,
+ +0.1889, -0.1941, -0.1753, -0.2329, -1.3540, -0.3580, +0.7976,
+ +0.3418, -0.3402, -0.5864, -0.2918, -0.3103, -0.8543, -0.4453,
+ -0.5695, -0.3897, -0.2154, -0.7735, +0.3474, -0.4120, +0.5434,
+ +0.5985, -0.4188, -0.6688, +0.0221, -0.3335, +0.0823, -0.9285,
+ +0.5000, -0.5239, -0.1289, +0.1898, -0.0251, -0.4911, -0.1460,
+ +0.3242, +0.5531, -0.2855, -0.0153, +0.3504, -0.7660, -0.5513, +0.5004
+ ],
+ [
+ +0.0273, -1.1660, -0.4373, -0.0665, +0.1115, +0.1340, -0.1542,
+ -1.0896, -0.0308, -0.6965, -0.4566, +0.4433, -0.4034, -0.5017,
+ +0.2259, -0.9126, -0.8050, +0.1053, -0.1586, -0.5198, +0.0862,
+ -0.6760, -1.0836, +0.1359, -0.2969, -0.5577, +0.0696, -0.4491,
+ -0.2396, +0.1705, -0.4238, -0.4414, +0.2904, -1.1770, -0.2532,
+ +0.2228, +0.2173, -0.0848, -0.0284, +0.1148, +0.2002, -0.8461,
+ -0.4833, -0.2364, +0.4290, -0.0140, -0.2397, +0.0003, -0.2664,
+ -0.8921, +0.4706, +0.2010, -0.4245, +0.2278, -0.1853, +0.3507,
+ -0.4354, -0.1236, +0.2643, +0.0153, -0.1940, -0.4305, +0.0677, -0.0475
+ ],
+ [
+ +0.0903, -1.0140, -0.3648, -0.2671, -0.9869, -1.1105, -0.1728,
+ -0.4584, +0.1077, -1.2754, -0.3594, -0.9522, +0.0033, -0.0398,
+ -0.0673, +0.5141, -0.3745, -0.4329, -0.3398, -0.1699, +0.0370,
+ -0.5619, -0.3187, -0.2753, +0.2649, -0.6796, -0.2249, +0.3044,
+ -0.8603, -0.2977, +0.1388, +0.0352, +0.3563, +0.4092, -0.8553,
+ -1.0842, +0.0022, -0.5831, -0.2512, +0.3504, -0.7838, +0.0974,
+ +0.3445, -0.5496, +0.2463, -0.3484, -1.0328, -0.1989, -0.2634,
+ -0.1709, +0.3680, -0.0917, -0.2035, -0.7795, -0.5149, +0.2160,
+ -0.9999, -0.3293, -1.0852, -0.1559, +0.3706, +0.0294, +0.1326, -0.4432
+ ],
+ [
+ -0.3382, -0.6195, +0.1247, -0.9739, -0.2695, +0.4227, +0.5390,
+ -0.6254, +0.7109, -0.4693, +0.4139, -0.1816, -0.3087, +0.4984,
+ -0.2314, -2.1260, +0.1874, -1.2938, -0.2536, +0.3450, -0.4624,
+ +0.2507, -0.2771, +0.1359, -0.1039, -0.2051, +0.9813, -0.1579,
+ +0.4289, +0.5024, +0.8469, +0.6266, -0.3238, +0.1631, -0.3280,
+ -0.0628, -1.0241, -0.2662, -0.4386, -0.1759, -0.0683, -0.2852,
+ -0.6328, -0.4171, -0.6023, -0.1489, +0.6873, +0.2652, +0.1424,
+ -1.4934, -0.4190, +0.1496, -0.1254, -0.1988, -0.9254, +0.0787,
+ -0.6244, +0.0852, -0.6942, +0.3636, +0.6130, -1.1516, -0.0166, +0.1482
+ ],
+ [
+ -0.6169, +0.1188, +0.3406, +0.1486, -0.6095, -0.1965, +0.3326,
+ +0.4358, +0.0495, -1.1649, -0.5144, +0.4749, -0.2066, -0.0452,
+ -0.8100, +0.3289, -0.4713, +0.3136, -0.4597, +0.3147, -0.3159,
+ -0.2916, +0.3687, +0.1243, +0.5095, +0.1617, -0.7095, +0.4710,
+ +0.0587, -0.6793, -0.2090, -0.1338, -0.1012, -0.4273, +0.2017,
+ +0.1794, -0.6143, +0.0151, -0.2607, -0.3144, +0.2775, +0.2231,
+ +0.3938, +0.0757, -0.6821, -0.0948, -0.0276, +0.4643, -0.4261,
+ +0.1980, -0.3515, -0.4316, -0.2730, +0.1513, +0.3709, -0.5053,
+ -0.3931, -0.0077, +0.4617, +0.2240, -0.5421, +0.0172, +0.3574, +0.3165
+ ],
+ [
+ -0.1494, +0.1755, -0.1157, -0.3965, -0.3154, -0.5596, -0.0307,
+ +0.1837, +0.0388, -0.0440, +0.5869, +0.1878, +0.2522, -0.4798,
+ -0.3823, +0.1313, -0.0318, +0.0430, +0.1159, +0.3460, -0.2264,
+ -0.2695, -0.1647, +0.9139, -0.2705, -1.4509, +0.8597, +0.1964,
+ -0.4520, +0.1905, -0.1044, +0.1410, +0.0431, +0.0959, +0.0074,
+ -0.7522, +0.2711, -0.0279, -0.5335, +0.3875, +0.1375, +0.1347,
+ +0.1622, -0.6972, +0.2821, +0.1858, +0.1513, +0.1948, +0.9353,
+ +0.1265, -0.4261, -0.7619, +0.0747, -0.3146, -0.0773, +0.2217,
+ +0.1078, +0.1632, -0.8363, -0.0736, -0.7793, +0.3148, +0.1152, -0.0871
+ ],
+ [
+ -0.1752, +0.5067, +0.2685, -0.3138, -0.1825, -1.1993, -0.5480,
+ -0.0802, +0.0464, +0.1444, -0.0249, -0.6009, -0.2998, -0.1202,
+ -0.1522, +0.2545, -0.3147, +0.0469, +0.2033, -0.1856, -0.1173,
+ -0.3927, +0.1988, -0.0460, +0.1827, +0.1227, +0.1774, -0.0260,
+ +0.3352, +0.2306, +0.1482, +0.0897, -0.5807, -0.4350, +0.4242,
+ -0.5245, +0.5988, +0.3664, +0.2803, +0.2254, +0.0257, -1.0348,
+ -0.0827, -0.3720, +0.0641, -0.0757, +0.3361, +0.1720, -0.0170,
+ -0.1818, -0.7976, +0.6775, +0.1444, -0.0576, +0.1275, -0.0842,
+ -0.2819, -0.3301, -0.1414, +0.0448, -0.2871, +0.2704, -0.0597, +0.3678
+ ],
+ [
+ -0.4166, -0.1664, +0.4311, +0.2548, +0.0251, +0.0090, -0.1093,
+ -0.0026, +0.0234, -0.4495, +0.2458, -0.4985, +0.0709, -0.0913,
+ -0.3304, -0.7517, +0.2261, +0.0720, +0.0285, +0.0063, -0.1014,
+ -0.0074, +0.0738, +0.2781, -0.0023, +0.0906, -0.3204, +0.2005,
+ +0.2953, +0.1304, -0.1219, +0.2426, -0.3057, +0.1381, +0.2148,
+ -0.2981, -0.0340, -0.0236, +0.1463, +0.1595, +0.2486, +0.3110,
+ +0.2315, -0.1590, -0.3630, -0.1236, -0.5037, +0.3045, +0.3508,
+ +0.4195, -0.4814, +0.4588, -1.0159, -0.1006, +0.3944, -0.5326,
+ -0.2366, +0.1164, -0.1002, +0.3154, -1.3383, -0.0688, -0.5051, +0.3699
+ ],
+ [
+ -0.7197, +0.1504, -0.1446, -0.1339, -0.1417, -0.8162, +0.1944,
+ +0.7188, +0.2220, -0.0700, -0.3646, +0.2094, -0.5074, -0.4900,
+ +0.0540, -0.1434, +0.0774, -0.0898, -0.6445, -1.3980, +0.1683,
+ -0.0078, +0.1635, -1.7522, -0.1579, +0.0890, -0.1984, -0.1460,
+ -0.2629, -0.1298, +0.0776, -0.2910, -0.6156, -0.1294, -0.1896,
+ +0.0145, -0.0966, -0.4646, +0.2838, -1.2625, -0.3026, +0.3173,
+ +0.0627, -0.2735, -0.5908, +0.4986, -0.2053, -0.1533, -0.1913,
+ -0.3208, -0.9794, -0.1901, -0.2732, +0.2572, +0.1799, -0.2724,
+ -0.0612, +0.3570, -0.1317, -0.2146, -0.1356, +0.1379, -0.1355, -0.0752
+ ],
+ [
+ -0.6539, -0.0727, -0.3427, +0.2905, -0.8430, -0.1184, -1.0977,
+ +0.1251, -0.3407, -0.7221, -1.2782, +0.3135, -0.5871, -0.6889,
+ +0.2488, -0.0093, -0.3846, +0.0363, -0.3364, -0.1874, -0.4212,
+ -0.3552, -0.0608, +0.2429, +0.1007, +0.1632, -0.0480, -0.6035,
+ -1.1736, +0.3253, -0.3441, +0.1198, +0.4950, -0.5443, +0.0941,
+ +0.1484, -0.2168, +0.0281, -0.1605, +0.3858, -0.5413, -1.0550,
+ -0.3714, +0.5328, -0.0108, -0.3914, +0.3519, -0.0481, +0.1556,
+ -0.5657, -0.0249, -0.0100, +0.0097, -0.2173, -0.0652, +0.1465,
+ -0.0911, -0.3613, -0.7631, +0.0362, +0.5869, -0.9699, +0.3223, -0.0013
+ ],
+ [
+ -0.1603, +0.3650, +0.5134, +0.5864, +0.0150, -0.1627, -1.0264,
+ -0.3798, +0.2746, -0.4213, -0.6696, -0.1510, +0.2925, -0.1033,
+ +0.1605, +0.2035, +0.2847, -0.2705, -0.7426, +0.1778, -0.2366,
+ -0.5919, -0.5160, -0.2858, +0.0174, +0.2660, -0.5899, +0.2780,
+ -0.1739, -0.3548, -0.2082, +0.2561, +0.2203, -0.4143, -0.1662,
+ +0.3997, -0.1140, +0.3797, +0.1374, -0.4189, -0.0794, +0.2233,
+ +0.0798, -0.2465, +0.1627, -0.7068, +0.0921, +0.1746, -0.1801,
+ +0.0973, -0.3874, +0.1683, -0.1716, -0.2131, -0.1740, -0.2968,
+ +0.0111, -0.1467, +0.3081, +0.1584, -0.2410, -0.1039, -0.0486, +0.1736
+ ],
+ [
+ -0.2541, -0.2942, +0.7954, -0.3406, +0.0833, -0.7064, +0.4935,
+ -0.8418, -0.4647, +0.0957, -0.0341, +0.1078, +0.1308, -0.1374,
+ -0.3026, -0.5658, +0.7016, +0.4218, -0.8008, +0.1745, +0.1244,
+ -0.3131, -0.0462, -0.2624, -0.9678, +0.0175, -1.4123, -0.5639,
+ -0.4396, -0.3965, +0.3948, -0.5819, +0.0683, +0.4224, -0.2057,
+ +0.3409, +0.0405, +0.3297, +0.4343, +0.1012, +0.0315, -0.1699,
+ +0.1734, -0.3161, -0.9861, +0.0318, -0.9950, -0.2561, -0.6608,
+ +0.0695, -0.2817, -0.3608, +0.0228, -0.1920, +0.6605, -1.0173,
+ -0.1881, -0.0018, -1.4576, -0.1873, +0.0563, -0.1610, -1.3073, -0.4878
+ ],
+ [
+ -0.4730, +0.3181, -0.9216, +0.0616, -0.0595, -0.3835, -1.0827,
+ -0.2049, +0.3268, -0.0025, +0.4207, +0.0695, +0.2867, -0.6964,
+ -0.2021, -0.3313, +0.2401, -0.5865, +0.1225, +0.0662, -0.0395,
+ -0.3217, +0.0283, -0.6146, +0.3855, +0.4659, -0.1366, +0.1905,
+ -0.4189, -0.0221, +0.0485, -0.0824, -0.0852, +0.3699, -1.1362,
+ -0.3399, -0.3045, +0.4129, -0.0479, -0.2226, -0.1424, +0.1984,
+ +0.1308, -0.0697, -0.1180, -0.0040, +0.0799, -0.5004, -0.2016,
+ +0.3574, -0.0379, -0.1902, -0.2152, -0.1548, -0.2587, -0.0184,
+ +0.1557, -0.8546, +0.0033, -0.5034, -0.0296, -0.7283, -0.2543, -0.5056
+ ],
+ [
+ -0.3047, -0.4435, -0.0328, +0.1094, +0.2118, +0.0936, +0.1051,
+ -0.3049, -0.2984, -0.2139, +0.4623, +0.0697, +0.0438, -0.0070,
+ +0.0173, -0.0140, +0.3330, +0.1464, -0.8054, -0.5374, +0.2089,
+ +0.0343, -0.0500, +0.2463, -0.5428, +0.3249, -0.2111, +0.1987,
+ +0.3385, +0.0350, +0.2139, +0.2606, +0.0579, +0.1967, +0.2805,
+ -0.6701, +0.1659, +0.1625, -0.0811, +0.1512, +0.2602, +0.0735,
+ +0.3579, +0.1876, -0.1828, +0.2517, -0.2081, -0.0434, -0.0671,
+ -0.2775, -0.0324, +0.0956, +0.1478, -0.5488, +0.4217, +0.3050,
+ +0.1241, -0.1265, -0.0378, -0.4110, +0.0372, +0.1242, -0.5133, -0.4433
+ ],
+ [
+ -0.0908, -0.4056, +1.0407, +0.2022, +0.3277, +0.0473, -0.2004,
+ -0.0019, +0.6105, -0.2085, -0.3269, -0.5087, -0.9063, +0.4416,
+ -0.5120, -0.6012, -0.0893, +0.7692, -0.8258, +0.2614, +0.3312,
+ +0.2587, -0.2327, +0.2353, +0.2126, -0.9841, -0.9045, -1.6272,
+ -0.0327, -0.2158, +0.1556, -1.2507, +0.1904, +0.2771, -0.1323,
+ +0.0612, -0.2321, -0.0461, -0.0934, -0.6754, +0.1108, +0.4772,
+ -0.0157, +0.1737, +0.2587, +0.3093, -0.4642, -0.2549, -0.6423,
+ +0.7156, -0.0731, +0.2901, -0.8073, +0.5818, -0.0272, +0.4151,
+ +0.6385, -0.4803, +0.5069, +0.1455, -0.6939, -0.5308, -0.1173, +0.3071
+ ],
+ [
+ +0.0517, -0.4560, -0.5719, -0.6117, -0.1617, -1.0319, -1.3503,
+ +0.2440, +0.2115, +0.0598, -0.1558, -0.5093, -0.4359, -1.0329,
+ -0.2702, +0.6932, +0.7264, -0.6596, -0.8755, -0.0335, -0.1665,
+ +0.2618, +0.3496, -0.3067, -0.2615, -0.5898, -0.0792, -0.0211,
+ -0.1784, -0.1019, +0.3617, +0.1576, +0.2354, -0.3653, -0.2507,
+ -0.6275, -0.0337, +0.4102, -0.9432, -0.2444, -0.6182, -0.1471,
+ -0.0926, +0.1671, -0.8133, +0.3371, -0.0011, +0.4394, -0.5574,
+ +0.0047, -0.1289, -1.0679, +0.0061, +0.1657, +0.0043, +0.0216,
+ -0.3186, -0.1413, +0.1294, +0.4513, -0.4948, +0.3693, -0.1198, +0.0882
+ ],
+ [
+ +0.0040, -0.4130, -0.1497, +0.1240, -0.0150, -0.8052, +0.0120,
+ -0.5317, -0.1766, -0.5743, +0.1538, -0.1543, +0.3415, +0.3493,
+ +0.2536, -0.7229, -0.0653, -0.1433, -2.7258, -0.3427, -0.1859,
+ +0.0050, -0.3057, -0.1605, +0.2688, -0.5278, -0.3073, +0.1964,
+ +0.6694, +0.0137, -0.2008, -0.2361, -0.1387, -0.0223, -0.0853,
+ +0.1436, -0.1557, +0.2564, -1.0089, -0.6109, +0.2781, +0.1629,
+ +0.1666, -0.1351, -0.3322, +0.1780, -0.8044, +0.4328, -0.6413,
+ +0.2032, -0.2698, -0.0661, -0.2372, +0.1637, -0.1807, +0.4428,
+ +0.0628, +0.4494, +0.1031, -0.1792, -0.7799, -0.0583, -0.2036, +0.3183
+ ],
+ [
+ -0.0603, -0.9099, +0.3309, +0.0880, -1.0803, -0.1118, -0.1298,
+ -0.1775, +0.2533, +0.3987, -0.5975, -0.1113, +0.2020, -0.0156,
+ -0.0979, -0.1306, +0.1531, -0.1246, +0.3544, +0.3535, -0.1467,
+ -0.5855, -0.4307, +0.1979, -0.3168, -0.3793, +0.0741, -0.1397,
+ -0.6970, +0.1966, -0.1540, +0.2032, +0.3120, -0.4629, +0.0909,
+ -0.7293, +0.2610, -0.7788, +0.0532, +0.2694, -0.2469, -1.1975,
+ -0.2844, +0.0471, +0.1458, +0.1922, -0.3000, -0.2814, -0.4190,
+ -0.2708, -0.2938, +0.0716, -0.5238, -0.1817, +0.3848, -0.2661,
+ -0.0399, -0.1237, -0.0065, -1.0783, +0.0090, -0.2122, -0.2348, +0.1777
+ ],
+ [
+ +0.3301, +0.3029, +0.2309, -0.2222, -0.3760, +0.2900, +0.4730,
+ +0.3653, +0.1257, -0.2469, +0.0678, -0.3140, -0.1101, -0.3410,
+ +0.2531, -0.1499, +0.1895, +0.3933, -0.0175, +0.1947, +0.3018,
+ +0.1375, +0.1816, -0.0375, -0.0476, -0.3521, -0.1531, +0.1851,
+ -0.0556, +0.0737, +0.0242, -0.0522, +0.2391, +0.3069, -0.8566,
+ -0.2267, -0.4648, +0.0512, +0.1738, -0.1233, +0.3117, -0.1392,
+ -0.2971, -1.6641, +0.0319, -0.2886, +0.2520, -0.4421, -0.0578,
+ +0.1778, +0.0562, -0.0425, -0.2082, -0.4188, -0.4602, +0.3081,
+ -0.0443, +0.1036, -0.6564, -0.0622, +0.4363, -0.2111, +0.3930, -0.4231
+ ],
+ [
+ -0.2303, -0.3073, +0.0881, -0.0259, +0.1158, -0.1876, -0.4537,
+ -0.1588, -0.0792, -0.2001, +0.0530, -0.2474, +0.1344, +0.2636,
+ +0.1983, -0.9749, +0.1990, -0.0957, -0.5147, -0.2180, +0.1174,
+ +0.1786, +0.1739, -0.3798, -0.0471, +0.1633, -0.1721, -0.0853,
+ +0.2622, +0.2510, -0.0152, -0.1403, -0.4670, -0.0056, +0.1107,
+ -0.6130, +0.0380, +0.2772, +0.2147, +0.4764, +0.2957, -0.1803,
+ +0.0094, -0.0602, +0.0961, +0.1071, -0.1469, +0.3588, +0.1152,
+ +0.2732, -0.0841, +0.1434, -0.8871, +0.1359, +0.4381, -0.3618,
+ -0.1783, +0.0244, -0.3266, +0.2683, +0.0475, +0.2396, +0.2882, +0.2097
+ ],
+ [
+ -0.3898, +0.1630, +0.1282, -0.3963, -0.4884, -0.4047, +0.2388,
+ -0.1641, -0.2076, -0.5232, -0.0945, +0.0596, +0.4917, -0.9385,
+ -0.6932, +0.0820, -0.1105, +0.1518, -1.0556, +0.2921, -0.1624,
+ -1.1541, -0.3967, -0.0768, +0.2946, -0.1138, -0.6109, +0.4627,
+ -0.0852, -0.4616, -0.3002, +0.3148, +0.4467, -1.3130, +0.0544,
+ -0.6324, -0.2650, +0.4150, -0.0212, -0.6526, +0.0006, +0.1399,
+ +0.3180, +0.2171, -0.2745, +0.1383, +0.3992, -0.1085, -0.8361,
+ +0.4735, +0.3327, -0.2108, -0.1326, +0.1012, -0.1039, -0.7952,
+ -1.0795, -0.8962, +0.2586, -0.1086, -0.1492, +0.1341, +0.4539, +0.0087
+ ],
+ [
+ -0.7632, -0.3424, -0.8353, +0.2849, +0.4074, +0.3540, -0.0225,
+ -1.0280, -0.0935, -0.1287, -0.9041, -0.2897, -1.2458, -0.9333,
+ -0.3642, +0.1682, -0.0609, -0.3427, -0.8061, +0.0809, -0.0527,
+ +0.2854, +0.0572, -0.9497, -0.1074, -0.4606, -0.3741, -0.1462,
+ -0.0244, +0.1021, -0.1344, -1.4004, +0.2785, +0.0365, +0.0607,
+ -0.0216, +0.2336, +0.2448, +0.3313, +0.0876, -0.0096, -0.0115,
+ +0.2235, +0.1732, +0.0449, +0.2710, -0.4689, +0.3985, +0.3226,
+ -0.4791, +0.1363, -0.2898, -0.2764, +0.2951, +0.1026, +0.2428,
+ +0.4613, -0.6892, -0.6060, +0.0831, +0.0033, +0.0969, +0.1732, +0.1978
+ ],
+ [
+ -0.4818, -0.4774, -1.1071, +0.3249, +0.2093, +0.0438, -0.9925,
+ -0.4215, +0.0589, -1.1715, +0.0919, +0.0382, -0.8698, -0.4791,
+ -0.7492, -0.8701, +0.0800, +0.0196, -0.7821, +0.1573, +0.5803,
+ -0.1820, -0.0484, +0.3254, +0.1583, +0.2182, -0.2223, -0.5444,
+ -0.6228, -0.7236, -0.1355, +0.2437, -0.0066, +0.2737, +0.2386,
+ -0.4084, -0.8557, +0.2213, -0.6375, +0.2682, -0.1000, -0.3804,
+ -0.0290, -0.0049, -0.3404, -0.4885, -0.1223, -0.2278, -0.4468,
+ +0.0452, -0.4968, -0.1218, +0.3995, -1.0746, -0.7465, -0.3371,
+ +0.4305, -1.6123, -0.1957, -0.1523, +0.1393, -0.8650, -0.1711, -0.3793
+ ],
+ [
+ -0.1557, -1.0601, -0.4499, -0.1604, -0.5255, -0.4208, -0.6083,
+ +0.3356, -0.0805, +0.2551, +0.0412, -0.1619, +0.2200, -0.8917,
+ -0.4723, -1.0188, +0.4529, -0.0400, -0.0839, +0.0217, -0.3820,
+ +0.3089, +0.2091, +0.1926, +0.0795, +0.1515, +0.1128, -0.3851,
+ -0.1858, +0.3644, +0.2686, -0.1214, +0.5001, -0.9542, +0.0416,
+ -0.0110, -0.8521, +0.2699, -0.7884, -0.0235, -0.6484, +0.3534,
+ -0.7125, +0.2728, +0.0038, -0.3497, +0.2039, +0.2628, +0.4429,
+ +0.2073, -1.0902, -0.1620, +0.3977, +0.5173, -0.4190, -0.5424,
+ +0.1696, +0.4501, -0.1723, +0.3870, +0.3782, -0.4795, -0.0925, +0.1928
+ ],
+ [
+ -0.1994, +0.0819, -0.9161, -0.0627, -0.3875, -0.1237, -0.3848,
+ +0.1303, -0.5012, -0.0149, -0.0410, +0.9109, -0.0172, +0.2573,
+ -0.0970, +0.1189, -0.2560, +0.2362, -0.0120, -0.0293, +0.0847,
+ -0.2890, +0.1035, -1.1365, -0.6136, +0.0283, -0.6735, -0.3893,
+ -0.2377, +0.1533, -0.1454, +0.4457, +0.0874, -0.6123, +0.0648,
+ -0.0958, +0.3596, -0.9314, -0.0837, +0.4202, -0.2286, -0.3712,
+ +0.0654, -0.1894, +0.7228, -0.0053, +0.2753, +0.1067, +0.2597,
+ -0.0419, -0.5189, -0.0970, +0.3215, +0.0511, +0.1690, -0.5153,
+ -0.7584, -1.0287, +0.6774, +0.2733, -0.0217, -0.5480, -0.0327, +0.0814
+ ],
+ [
+ -0.0850, -0.2497, -0.2107, -0.2141, +0.3072, +0.3229, -0.1949,
+ +0.1294, -0.2154, -0.5436, -0.2756, +0.1585, -0.3081, -0.2884,
+ +0.0584, +0.3902, +0.5601, -0.0324, -0.8309, +0.0884, +0.4890,
+ +0.2771, +0.1323, +0.2234, -0.5563, +0.2813, -1.1535, +0.3736,
+ -0.8677, +0.2691, +0.1412, +0.4179, +0.3897, -0.2039, +0.0885,
+ -0.2746, -0.3438, +0.6083, +0.1196, +0.6909, +0.3943, -0.4563,
+ -0.2028, +0.3160, +0.4372, -0.3929, -0.6564, -0.2445, -0.3547,
+ -0.0069, +0.3304, +0.2863, +0.0022, -0.6024, +0.0905, -0.0902,
+ +0.3029, -0.2148, +0.3599, +0.3216, +0.5142, -0.8270, +0.3086, +0.2275
+ ]])
-weights_final_w = np.array([
-[ +0.0101, -0.1948, +0.2128, -0.4291, +0.4975, +0.0586],
-[ +0.1211, -0.3286, -0.5959, +0.2402, +0.2022, +0.0405],
-[ -0.0318, +0.3342, +0.1579, -0.4639, -0.4456, -0.2342],
-[ +0.0856, +0.0638, +0.3259, +0.2046, -0.4004, +0.4999],
-[ -0.6462, -0.0369, -1.1351, +0.9906, +0.0352, -0.6781],
-[ -0.3719, -0.1071, +0.3581, +0.5559, +0.1965, -0.3970],
-[ +0.0816, -0.1766, -0.6672, +0.0872, -0.5773, -0.3138],
-[ -0.0914, +0.1054, +0.0728, +0.5491, +0.4499, +0.1875],
-[ +0.2443, +0.0085, -0.2355, +0.3129, -0.1762, -0.0077],
-[ -0.1181, -0.6764, +0.4602, +0.1629, +0.0420, +0.2435],
-[ +0.0605, +0.0850, -0.6874, -0.0096, +0.4599, -0.2271],
-[ +0.5245, -0.2946, -0.1789, +0.5927, +0.0829, +0.5251],
-[ +0.4504, -0.4831, +0.0163, +0.0061, +0.5226, -0.4811],
-[ +0.5086, -0.2366, +0.0043, -0.1165, -0.2790, -0.5078],
-[ +0.1296, +0.0196, +0.1396, -0.1705, +0.2290, -0.2673],
-[ -0.0323, -0.1554, +0.4492, -0.6847, +0.0767, +0.0235],
-[ -0.0142, +0.3304, -0.2269, +0.0771, +0.2548, -0.0215],
-[ -0.3389, +0.0605, -0.1767, +0.1649, +0.3932, +0.4187],
-[ +0.0447, -0.2753, +0.7056, -0.3268, -0.4054, +0.3856],
-[ +0.3863, +0.0820, +0.1836, -0.1025, -0.0837, +0.3728],
-[ +0.1172, +0.2514, -0.2447, -0.0147, +0.3737, -0.1232],
-[ +0.4822, -0.1587, +0.0189, +0.1085, -0.2107, +0.1819],
-[ -0.3112, +0.2384, -0.0983, +0.3085, +0.3343, -0.1824],
-[ +0.1329, -0.7842, +0.5067, -0.1467, +0.6028, -0.1696],
-[ +0.0913, -0.2866, +0.1866, +0.0102, -0.2893, +0.1818],
-[ -0.0842, +0.0903, +0.0537, +0.2681, +0.6005, -0.3763],
-[ +0.4081, -0.5070, -0.2256, +0.4282, -0.2310, +0.0178],
-[ +0.1979, +0.1552, +0.7038, -0.0276, +0.1008, +0.4311],
-[ +0.0105, +0.0500, -0.5326, -0.1960, -0.0029, +0.7599],
-[ +0.0132, +0.1029, +0.0586, +0.2432, -0.0545, -0.3576],
-[ -0.1861, +0.2730, -0.1026, +0.2567, +0.1899, +0.0994],
-[ +0.2804, +0.4976, +0.0234, -0.0693, +0.1044, -0.1782],
-[ +0.1651, -0.0445, -0.1732, -0.1439, +0.1910, -0.2900],
-[ +0.0575, +0.0506, -0.5541, -0.0837, +0.1331, +0.0596],
-[ -0.5366, -0.2095, +0.2158, +0.1478, +0.1552, -0.2847],
-[ -0.2239, -0.5064, +0.2553, +0.6997, -0.2814, -0.5053],
-[ -0.5875, -0.2929, -0.3054, +0.4141, +0.0547, +0.2617],
-[ +0.4712, +0.1022, +0.2665, +0.1481, +0.2837, +0.3440],
-[ +0.3937, +0.3063, +0.4430, -0.5654, +0.0932, -0.1030],
-[ +0.0561, +0.7068, +0.1140, -0.0612, +0.1575, -0.4454],
-[ -0.4082, -0.3756, -0.0447, +0.5955, +0.2170, +0.2459],
-[ +0.3779, +0.1477, -0.2120, -0.3360, -0.3584, +0.1333],
-[ -0.1877, +0.1041, -0.2141, -0.0261, +0.0121, +0.5809],
-[ +0.5229, +0.3220, +0.4367, -0.1934, +0.0125, +0.3250],
-[ -0.0197, -0.0964, +0.6821, +0.0876, +0.1429, -0.2392],
-[ -0.3900, +0.3254, -0.1975, +0.2021, -0.4072, +0.2072],
-[ +0.2660, -0.2046, +0.2172, +0.2520, +0.1637, -0.0179],
-[ -0.0649, -0.0451, +0.0873, +0.0077, -0.3684, -0.0634],
-[ +0.1304, +0.2106, +0.0804, +0.0554, -0.2718, -0.4081],
-[ +0.3119, +0.1979, -0.2498, +0.0328, +0.2566, +0.2054],
-[ +0.0622, +0.2239, -0.7600, -0.2464, -0.3213, -0.4771],
-[ -0.3352, +0.4833, +0.0830, +0.3854, -0.0733, -0.0983],
-[ +0.2465, +0.0722, -0.0776, +0.2516, +0.5810, +0.5918],
-[ -0.2167, -0.2138, +0.2410, -0.3535, -0.4878, -0.4168],
-[ -0.0991, +0.4950, +0.0633, +0.2891, -0.5150, +0.1257],
-[ -0.0267, -0.5339, -0.2769, -0.0796, +0.0055, -0.2304],
-[ +0.2994, +0.3536, -0.3556, +0.3602, -0.1715, -0.3168],
-[ +0.1544, -0.5746, -0.1126, -0.4654, +0.1188, -0.0478],
-[ +0.4130, -0.7358, +0.0469, +0.0414, -0.0352, -0.5242],
-[ -0.3941, +0.6807, +0.0670, +0.6347, +0.0394, +0.2293],
-[ -0.0101, +0.1363, +0.6806, -0.1179, +0.1445, -0.0643],
-[ -0.5794, +0.1603, -0.3438, -0.5360, -0.0372, +0.1549],
-[ -0.0897, +1.1163, +0.4080, +0.1319, +0.1437, +0.0088],
-[ +0.2344, +0.4274, -0.1515, +0.0379, -0.2166, -0.0852]
+weights_dense2_b = np.array([
+ +0.3157, -0.0138, +0.1347, +0.2792, -0.0769, +0.0847, -0.0819, +0.2974,
+ +0.1350, -0.0025, +0.0698, -0.2427, +0.2004, +0.2309, +0.1715, +0.0219,
+ +0.1258, +0.1784, +0.3261, +0.1711, -0.0779, +0.1550, +0.1433, +0.0774,
+ -0.1676, -0.0443, -0.1684, +0.1624, +0.0597, +0.0358, +0.1652, +0.1075,
+ +0.0770, +0.1979, +0.1490, -0.0719, +0.1036, +0.0766, +0.2915, -0.1048,
+ +0.1366, +0.0610, +0.2238, +0.1660, +0.0433, +0.3754, -0.0812, -0.0851,
+ +0.2820, +0.2110, +0.0232, -0.0167, -0.2433, -0.0042, +0.2591, -0.0215,
+ +0.0927, +0.1470, -0.0324, +0.2150, -0.1883, +0.0956, +0.1331, +0.2330
])
-weights_final_b = np.array([ +0.0090, +0.2404, +0.1022, +0.1035, +0.0621, -0.0160])
+weights_final_w = np.array(
+ [[+0.0101, -0.1948, +0.2128, -0.4291, +0.4975, +0.0586],
+ [+0.1211, -0.3286, -0.5959, +0.2402, +0.2022, +0.0405],
+ [-0.0318, +0.3342, +0.1579, -0.4639, -0.4456, -0.2342],
+ [+0.0856, +0.0638, +0.3259, +0.2046, -0.4004, +0.4999],
+ [-0.6462, -0.0369, -1.1351, +0.9906, +0.0352, -0.6781],
+ [-0.3719, -0.1071, +0.3581, +0.5559, +0.1965, -0.3970],
+ [+0.0816, -0.1766, -0.6672, +0.0872, -0.5773, -0.3138],
+ [-0.0914, +0.1054, +0.0728, +0.5491, +0.4499, +0.1875],
+ [+0.2443, +0.0085, -0.2355, +0.3129, -0.1762, -0.0077],
+ [-0.1181, -0.6764, +0.4602, +0.1629, +0.0420, +0.2435],
+ [+0.0605, +0.0850, -0.6874, -0.0096, +0.4599, -0.2271],
+ [+0.5245, -0.2946, -0.1789, +0.5927, +0.0829, +0.5251],
+ [+0.4504, -0.4831, +0.0163, +0.0061, +0.5226, -0.4811],
+ [+0.5086, -0.2366, +0.0043, -0.1165, -0.2790, -0.5078],
+ [+0.1296, +0.0196, +0.1396, -0.1705, +0.2290, -0.2673],
+ [-0.0323, -0.1554, +0.4492, -0.6847, +0.0767, +0.0235],
+ [-0.0142, +0.3304, -0.2269, +0.0771, +0.2548, -0.0215],
+ [-0.3389, +0.0605, -0.1767, +0.1649, +0.3932, +0.4187],
+ [+0.0447, -0.2753, +0.7056, -0.3268, -0.4054, +0.3856],
+ [+0.3863, +0.0820, +0.1836, -0.1025, -0.0837, +0.3728],
+ [+0.1172, +0.2514, -0.2447, -0.0147, +0.3737, -0.1232],
+ [+0.4822, -0.1587, +0.0189, +0.1085, -0.2107, +0.1819],
+ [-0.3112, +0.2384, -0.0983, +0.3085, +0.3343, -0.1824],
+ [+0.1329, -0.7842, +0.5067, -0.1467, +0.6028, -0.1696],
+ [+0.0913, -0.2866, +0.1866, +0.0102, -0.2893, +0.1818],
+ [-0.0842, +0.0903, +0.0537, +0.2681, +0.6005, -0.3763],
+ [+0.4081, -0.5070, -0.2256, +0.4282, -0.2310, +0.0178],
+ [+0.1979, +0.1552, +0.7038, -0.0276, +0.1008, +0.4311],
+ [+0.0105, +0.0500, -0.5326, -0.1960, -0.0029, +0.7599],
+ [+0.0132, +0.1029, +0.0586, +0.2432, -0.0545, -0.3576],
+ [-0.1861, +0.2730, -0.1026, +0.2567, +0.1899, +0.0994],
+ [+0.2804, +0.4976, +0.0234, -0.0693, +0.1044, -0.1782],
+ [+0.1651, -0.0445, -0.1732, -0.1439, +0.1910, -0.2900],
+ [+0.0575, +0.0506, -0.5541, -0.0837, +0.1331, +0.0596],
+ [-0.5366, -0.2095, +0.2158, +0.1478, +0.1552, -0.2847],
+ [-0.2239, -0.5064, +0.2553, +0.6997, -0.2814, -0.5053],
+ [-0.5875, -0.2929, -0.3054, +0.4141, +0.0547, +0.2617],
+ [+0.4712, +0.1022, +0.2665, +0.1481, +0.2837, +0.3440],
+ [+0.3937, +0.3063, +0.4430, -0.5654, +0.0932, -0.1030],
+ [+0.0561, +0.7068, +0.1140, -0.0612, +0.1575, -0.4454],
+ [-0.4082, -0.3756, -0.0447, +0.5955, +0.2170, +0.2459],
+ [+0.3779, +0.1477, -0.2120, -0.3360, -0.3584, +0.1333],
+ [-0.1877, +0.1041, -0.2141, -0.0261, +0.0121, +0.5809],
+ [+0.5229, +0.3220, +0.4367, -0.1934, +0.0125, +0.3250],
+ [-0.0197, -0.0964, +0.6821, +0.0876, +0.1429, -0.2392],
+ [-0.3900, +0.3254, -0.1975, +0.2021, -0.4072, +0.2072],
+ [+0.2660, -0.2046, +0.2172, +0.2520, +0.1637, -0.0179],
+ [-0.0649, -0.0451, +0.0873, +0.0077, -0.3684, -0.0634],
+ [+0.1304, +0.2106, +0.0804, +0.0554, -0.2718, -0.4081],
+ [+0.3119, +0.1979, -0.2498, +0.0328, +0.2566, +0.2054],
+ [+0.0622, +0.2239, -0.7600, -0.2464, -0.3213, -0.4771],
+ [-0.3352, +0.4833, +0.0830, +0.3854, -0.0733, -0.0983],
+ [+0.2465, +0.0722, -0.0776, +0.2516, +0.5810, +0.5918],
+ [-0.2167, -0.2138, +0.2410, -0.3535, -0.4878, -0.4168],
+ [-0.0991, +0.4950, +0.0633, +0.2891, -0.5150, +0.1257],
+ [-0.0267, -0.5339, -0.2769, -0.0796, +0.0055, -0.2304],
+ [+0.2994, +0.3536, -0.3556, +0.3602, -0.1715, -0.3168],
+ [+0.1544, -0.5746, -0.1126, -0.4654, +0.1188, -0.0478],
+ [+0.4130, -0.7358, +0.0469, +0.0414, -0.0352, -0.5242],
+ [-0.3941, +0.6807, +0.0670, +0.6347, +0.0394, +0.2293],
+ [-0.0101, +0.1363, +0.6806, -0.1179, +0.1445, -0.0643],
+ [-0.5794, +0.1603, -0.3438, -0.5360, -0.0372, +0.1549],
+ [-0.0897, +1.1163, +0.4080, +0.1319, +0.1437, +0.0088],
+ [+0.2344, +0.4274, -0.1515, +0.0379, -0.2166, -0.0852]])
+
+weights_final_b = np.array(
+ [+0.0090, +0.2404, +0.1022, +0.1035, +0.0621, -0.0160])
+# yapf: enable
-if __name__=="__main__":
- main()
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/kukaCamGymEnvTest.py b/examples/pybullet/gym/pybullet_envs/examples/kukaCamGymEnvTest.py
index 00fe0d6b3..6cf9909cb 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/kukaCamGymEnvTest.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/kukaCamGymEnvTest.py
@@ -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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest.py b/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest.py
index 3917f08cf..818bdd0ab 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest.py
@@ -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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest2.py b/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest2.py
index 5c7f245c3..d94702cf0 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest2.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/kukaGymEnvTest2.py
@@ -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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/kuka_setup.py b/examples/pybullet/gym/pybullet_envs/examples/kuka_setup.py
index 38d32b844..1fcda0832 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/kuka_setup.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/kuka_setup.py
@@ -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)
-
-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)
-
-objects = [p.loadURDF("kuka_iiwa/model_vr_limits.urdf", 1.400000,-0.200000,0.600000,0.000000,0.000000,0.000000,1.000000)]
+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])
+
+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)
+]
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)
-
-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)]
+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.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)
-
-
-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)]
+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])
+
+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])
-
-objects = [p.loadURDF("husky/husky.urdf", 2.000000,-5.000000,1.000000,0.000000,0.000000,0.000000,1.000000)]
+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)
+]
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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/laikago.py b/examples/pybullet/gym/pybullet_envs/examples/laikago.py
index b256f2a04..081573cc0 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/laikago.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/laikago.py
@@ -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)
-
-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):
+ 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]
+
+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)
diff --git a/examples/pybullet/gym/pybullet_envs/examples/minitaur_gym_env_example.py b/examples/pybullet/gym/pybullet_envs/examples/minitaur_gym_env_example.py
index 8057b2dc5..06337da40 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/minitaur_gym_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/minitaur_gym_env_example.py
@@ -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()
-
-if __name__ == '__main__':
- 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()
+if __name__ == '__main__':
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py b/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py
index d640951b0..3e4488e30 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/racecarGymEnvTest.py
@@ -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()
+
+ 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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/racecarZEDGymEnvTest.py b/examples/pybullet/gym/pybullet_envs/examples/racecarZEDGymEnvTest.py
index cee459e70..4d529c476 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/racecarZEDGymEnvTest.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/racecarZEDGymEnvTest.py
@@ -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)
-
-if __name__=="__main__":
- 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)
+
+
+if __name__ == "__main__":
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/runServer.py b/examples/pybullet/gym/pybullet_envs/examples/runServer.py
index bcd95f812..054fe66a4 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/runServer.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/runServer.py
@@ -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)
diff --git a/examples/pybullet/gym/pybullet_envs/examples/testBike.py b/examples/pybullet/gym/pybullet_envs/examples/testBike.py
index e36922fdc..62475c60d 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/testBike.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/testBike.py
@@ -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.
-
-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)
-
- 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])
+plane = p.loadURDF("plane100.urdf", [0, 0, 0])
+timestep = 1. / 240.
+
+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)
+
+ 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):
-
- 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);
-
-
+p.getCameraImage(320, 200) #,renderer=p.ER_BULLET_HARDWARE_OPENGL )
+
+while (1):
+
+ 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)
diff --git a/examples/pybullet/gym/pybullet_envs/examples/testEnv.py b/examples/pybullet/gym/pybullet_envs/examples/testEnv.py
index 61f9bd0f7..5d30d27af 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/testEnv.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/testEnv.py
@@ -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()
diff --git a/examples/pybullet/gym/pybullet_envs/examples/testMJCF.py b/examples/pybullet/gym/pybullet_envs/examples/testMJCF.py
index ebdef3b38..76a889c6a 100644
--- a/examples/pybullet/gym/pybullet_envs/examples/testMJCF.py
+++ b/examples/pybullet/gym/pybullet_envs/examples/testMJCF.py
@@ -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) \ No newline at end of file
+ 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)
diff --git a/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py b/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py
index 1ece4b4e5..d601c130b 100644
--- a/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py
+++ b/examples/pybullet/gym/pybullet_envs/gym_locomotion_envs.py
@@ -6,175 +6,192 @@ from robot_locomotors import Hopper, Walker2D, HalfCheetah, Ant, Humanoid, Human
class WalkerBaseBulletEnv(MJCFBaseBulletEnv):
- def __init__(self, robot, render=False):
- # print("WalkerBase::__init__ start")
- MJCFBaseBulletEnv.__init__(self, robot, render)
-
- self.camera_x = 0
- self.walk_target_x = 1e3 # kilometer away
- self.walk_target_y = 0
- self.stateId=-1
-
-
- def create_single_player_scene(self, bullet_client):
- self.stadium_scene = SinglePlayerStadiumScene(bullet_client, gravity=9.8, timestep=0.0165/4, frame_skip=4)
- return self.stadium_scene
-
- def reset(self):
- if (self.stateId>=0):
- #print("restoreState self.stateId:",self.stateId)
- self._p.restoreState(self.stateId)
-
- r = MJCFBaseBulletEnv.reset(self)
- self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING,0)
-
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(self._p,
- self.stadium_scene.ground_plane_mjcf)
- self.ground_ids = set([(self.parts[f].bodies[self.parts[f].bodyIndex], self.parts[f].bodyPartIndex) for f in
- self.foot_ground_object_names])
- self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING,1)
- if (self.stateId<0):
- self.stateId=self._p.saveState()
- #print("saving state self.stateId:",self.stateId)
-
-
- return r
-
- def _isDone(self):
- return self._alive < 0
-
- def move_robot(self, init_x, init_y, init_z):
- "Used by multiplayer stadium to move sideways, to another running lane."
- self.cpp_robot.query_position()
- pose = self.cpp_robot.root_part.pose()
- pose.move_xyz(init_x, init_y, init_z) # Works because robot loads around (0,0,0), and some robots have z != 0 that is left intact
- self.cpp_robot.set_pose(pose)
-
- electricity_cost = -2.0 # cost for using motors -- this parameter should be carefully tuned against reward for making progress, other values less improtant
- stall_torque_cost = -0.1 # cost for running electric current through a motor even at zero rotational speed, small
- foot_collision_cost = -1.0 # touches another leg, or other objects, that cost makes robot avoid smashing feet into itself
- foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
- joints_at_limit_cost = -0.1 # discourage stuck joints
-
- def step(self, a):
- if not self.scene.multiplayer: # if multiplayer, action first applied to all robots, then global step() called, then _step() for all robots with the same actions
- self.robot.apply_action(a)
- self.scene.global_step()
-
- state = self.robot.calc_state() # also calculates self.joints_at_limit
-
- self._alive = float(self.robot.alive_bonus(state[0]+self.robot.initial_z, self.robot.body_rpy[1])) # state[0] is body height above ground, body_rpy[1] is pitch
- done = self._isDone()
- if not np.isfinite(state).all():
- print("~INF~", state)
- done = True
-
- potential_old = self.potential
- self.potential = self.robot.calc_potential()
- progress = float(self.potential - potential_old)
-
- feet_collision_cost = 0.0
- for i,f in enumerate(self.robot.feet): # TODO: Maybe calculating feet contacts could be done within the robot code
- contact_ids = set((x[2], x[4]) for x in f.contact_list())
- #print("CONTACT OF '%d' WITH %d" % (contact_ids, ",".join(contact_names)) )
- if (self.ground_ids & contact_ids):
- #see Issue 63: https://github.com/openai/roboschool/issues/63
- #feet_collision_cost += self.foot_collision_cost
- self.robot.feet_contact[i] = 1.0
- else:
- self.robot.feet_contact[i] = 0.0
-
-
- electricity_cost = self.electricity_cost * float(np.abs(a*self.robot.joint_speeds).mean()) # let's assume we have DC motor with controller, and reverse current braking
- electricity_cost += self.stall_torque_cost * float(np.square(a).mean())
-
- joints_at_limit_cost = float(self.joints_at_limit_cost * self.robot.joints_at_limit)
- debugmode=0
- if(debugmode):
- print("alive=")
- print(self._alive)
- print("progress")
- print(progress)
- print("electricity_cost")
- print(electricity_cost)
- print("joints_at_limit_cost")
- print(joints_at_limit_cost)
- print("feet_collision_cost")
- print(feet_collision_cost)
-
- self.rewards = [
- self._alive,
- progress,
- electricity_cost,
- joints_at_limit_cost,
- feet_collision_cost
- ]
- if (debugmode):
- print("rewards=")
- print(self.rewards)
- print("sum rewards")
- print(sum(self.rewards))
- self.HUD(state, a, done)
- self.reward += sum(self.rewards)
-
- return state, sum(self.rewards), bool(done), {}
-
- def camera_adjust(self):
- x, y, z = self.body_xyz
- self.camera_x = 0.98*self.camera_x + (1-0.98)*x
- self.camera.move_and_look_at(self.camera_x, y-2.0, 1.4, x, y, 1.0)
+
+ def __init__(self, robot, render=False):
+ # print("WalkerBase::__init__ start")
+ MJCFBaseBulletEnv.__init__(self, robot, render)
+
+ self.camera_x = 0
+ self.walk_target_x = 1e3 # kilometer away
+ self.walk_target_y = 0
+ self.stateId = -1
+
+ def create_single_player_scene(self, bullet_client):
+ self.stadium_scene = SinglePlayerStadiumScene(bullet_client,
+ gravity=9.8,
+ timestep=0.0165 / 4,
+ frame_skip=4)
+ return self.stadium_scene
+
+ def reset(self):
+ if (self.stateId >= 0):
+ #print("restoreState self.stateId:",self.stateId)
+ self._p.restoreState(self.stateId)
+
+ r = MJCFBaseBulletEnv.reset(self)
+ self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 0)
+
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.robot.addToScene(
+ self._p, self.stadium_scene.ground_plane_mjcf)
+ self.ground_ids = set([(self.parts[f].bodies[self.parts[f].bodyIndex],
+ self.parts[f].bodyPartIndex) for f in self.foot_ground_object_names])
+ self._p.configureDebugVisualizer(pybullet.COV_ENABLE_RENDERING, 1)
+ if (self.stateId < 0):
+ self.stateId = self._p.saveState()
+ #print("saving state self.stateId:",self.stateId)
+
+ return r
+
+ def _isDone(self):
+ return self._alive < 0
+
+ def move_robot(self, init_x, init_y, init_z):
+ "Used by multiplayer stadium to move sideways, to another running lane."
+ self.cpp_robot.query_position()
+ pose = self.cpp_robot.root_part.pose()
+ pose.move_xyz(
+ init_x, init_y, init_z
+ ) # Works because robot loads around (0,0,0), and some robots have z != 0 that is left intact
+ self.cpp_robot.set_pose(pose)
+
+ electricity_cost = -2.0 # cost for using motors -- this parameter should be carefully tuned against reward for making progress, other values less improtant
+ stall_torque_cost = -0.1 # cost for running electric current through a motor even at zero rotational speed, small
+ foot_collision_cost = -1.0 # touches another leg, or other objects, that cost makes robot avoid smashing feet into itself
+ foot_ground_object_names = set(["floor"]) # to distinguish ground and other objects
+ joints_at_limit_cost = -0.1 # discourage stuck joints
+
+ def step(self, a):
+ if not self.scene.multiplayer: # if multiplayer, action first applied to all robots, then global step() called, then _step() for all robots with the same actions
+ self.robot.apply_action(a)
+ self.scene.global_step()
+
+ state = self.robot.calc_state() # also calculates self.joints_at_limit
+
+ self._alive = float(
+ self.robot.alive_bonus(
+ state[0] + self.robot.initial_z,
+ self.robot.body_rpy[1])) # state[0] is body height above ground, body_rpy[1] is pitch
+ done = self._isDone()
+ if not np.isfinite(state).all():
+ print("~INF~", state)
+ done = True
+
+ potential_old = self.potential
+ self.potential = self.robot.calc_potential()
+ progress = float(self.potential - potential_old)
+
+ feet_collision_cost = 0.0
+ for i, f in enumerate(
+ self.robot.feet
+ ): # TODO: Maybe calculating feet contacts could be done within the robot code
+ contact_ids = set((x[2], x[4]) for x in f.contact_list())
+ #print("CONTACT OF '%d' WITH %d" % (contact_ids, ",".join(contact_names)) )
+ if (self.ground_ids & contact_ids):
+ #see Issue 63: https://github.com/openai/roboschool/issues/63
+ #feet_collision_cost += self.foot_collision_cost
+ self.robot.feet_contact[i] = 1.0
+ else:
+ self.robot.feet_contact[i] = 0.0
+
+ electricity_cost = self.electricity_cost * float(np.abs(a * self.robot.joint_speeds).mean(
+ )) # let's assume we have DC motor with controller, and reverse current braking
+ electricity_cost += self.stall_torque_cost * float(np.square(a).mean())
+
+ joints_at_limit_cost = float(self.joints_at_limit_cost * self.robot.joints_at_limit)
+ debugmode = 0
+ if (debugmode):
+ print("alive=")
+ print(self._alive)
+ print("progress")
+ print(progress)
+ print("electricity_cost")
+ print(electricity_cost)
+ print("joints_at_limit_cost")
+ print(joints_at_limit_cost)
+ print("feet_collision_cost")
+ print(feet_collision_cost)
+
+ self.rewards = [
+ self._alive, progress, electricity_cost, joints_at_limit_cost, feet_collision_cost
+ ]
+ if (debugmode):
+ print("rewards=")
+ print(self.rewards)
+ print("sum rewards")
+ print(sum(self.rewards))
+ self.HUD(state, a, done)
+ self.reward += sum(self.rewards)
+
+ return state, sum(self.rewards), bool(done), {}
+
+ def camera_adjust(self):
+ x, y, z = self.body_xyz
+ self.camera_x = 0.98 * self.camera_x + (1 - 0.98) * x
+ self.camera.move_and_look_at(self.camera_x, y - 2.0, 1.4, x, y, 1.0)
+
class HopperBulletEnv(WalkerBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Hopper()
- WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
+ def __init__(self, render=False):
+ self.robot = Hopper()
+ WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
class Walker2DBulletEnv(WalkerBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Walker2D()
- WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
+ def __init__(self, render=False):
+ self.robot = Walker2D()
+ WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
class HalfCheetahBulletEnv(WalkerBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = HalfCheetah()
- WalkerBaseBulletEnv.__init__(self, self.robot, render)
- def _isDone(self):
- return False
+ def __init__(self, render=False):
+ self.robot = HalfCheetah()
+ WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
+ def _isDone(self):
+ return False
+
class AntBulletEnv(WalkerBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Ant()
- WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
+ def __init__(self, render=False):
+ self.robot = Ant()
+ WalkerBaseBulletEnv.__init__(self, self.robot, render)
+
class HumanoidBulletEnv(WalkerBaseBulletEnv):
- def __init__(self, robot=Humanoid(), render=False):
- self.robot = robot
- WalkerBaseBulletEnv.__init__(self, self.robot, render)
- self.electricity_cost = 4.25*WalkerBaseBulletEnv.electricity_cost
- self.stall_torque_cost = 4.25*WalkerBaseBulletEnv.stall_torque_cost
+
+ def __init__(self, robot=Humanoid(), render=False):
+ self.robot = robot
+ WalkerBaseBulletEnv.__init__(self, self.robot, render)
+ self.electricity_cost = 4.25 * WalkerBaseBulletEnv.electricity_cost
+ self.stall_torque_cost = 4.25 * WalkerBaseBulletEnv.stall_torque_cost
+
class HumanoidFlagrunBulletEnv(HumanoidBulletEnv):
- random_yaw = True
+ random_yaw = True
+
+ def __init__(self, render=False):
+ self.robot = HumanoidFlagrun()
+ HumanoidBulletEnv.__init__(self, self.robot, render)
- def __init__(self, render=False):
- self.robot = HumanoidFlagrun()
- HumanoidBulletEnv.__init__(self, self.robot, render)
+ def create_single_player_scene(self, bullet_client):
+ s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
+ s.zero_at_running_strip_start_line = False
+ return s
- def create_single_player_scene(self, bullet_client):
- s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
- s.zero_at_running_strip_start_line = False
- return s
class HumanoidFlagrunHarderBulletEnv(HumanoidBulletEnv):
- random_lean = True # can fall on start
+ random_lean = True # can fall on start
- def __init__(self, render=False):
- self.robot = HumanoidFlagrunHarder()
- self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
- HumanoidBulletEnv.__init__(self, self.robot, render)
+ def __init__(self, render=False):
+ self.robot = HumanoidFlagrunHarder()
+ self.electricity_cost /= 4 # don't care that much about electricity, just stand up!
+ HumanoidBulletEnv.__init__(self, self.robot, render)
- def create_single_player_scene(self, bullet_client):
- s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
- s.zero_at_running_strip_start_line = False
- return s
+ def create_single_player_scene(self, bullet_client):
+ s = HumanoidBulletEnv.create_single_player_scene(self, bullet_client)
+ s.zero_at_running_strip_start_line = False
+ return s
diff --git a/examples/pybullet/gym/pybullet_envs/gym_manipulator_envs.py b/examples/pybullet/gym/pybullet_envs/gym_manipulator_envs.py
index 8ac4f8ad2..9fef7e615 100644
--- a/examples/pybullet/gym/pybullet_envs/gym_manipulator_envs.py
+++ b/examples/pybullet/gym/pybullet_envs/gym_manipulator_envs.py
@@ -5,229 +5,250 @@ from robot_manipulators import Reacher, Pusher, Striker, Thrower
class ReacherBulletEnv(MJCFBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Reacher()
- MJCFBaseBulletEnv.__init__(self, self.robot, render)
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0165, frame_skip=1)
+ def __init__(self, render=False):
+ self.robot = Reacher()
+ MJCFBaseBulletEnv.__init__(self, self.robot, render)
- def step(self, a):
- assert (not self.scene.multiplayer)
- self.robot.apply_action(a)
- self.scene.global_step()
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0165, frame_skip=1)
- state = self.robot.calc_state() # sets self.to_target_vec
+ def step(self, a):
+ assert (not self.scene.multiplayer)
+ self.robot.apply_action(a)
+ self.scene.global_step()
- potential_old = self.potential
- self.potential = self.robot.calc_potential()
+ state = self.robot.calc_state() # sets self.to_target_vec
- electricity_cost = (
- -0.10 * (np.abs(a[0] * self.robot.theta_dot) + np.abs(a[1] * self.robot.gamma_dot)) # work torque*angular_velocity
- - 0.01 * (np.abs(a[0]) + np.abs(a[1])) # stall torque require some energy
- )
- stuck_joint_cost = -0.1 if np.abs(np.abs(self.robot.gamma) - 1) < 0.01 else 0.0
- self.rewards = [float(self.potential - potential_old), float(electricity_cost), float(stuck_joint_cost)]
- self.HUD(state, a, False)
- return state, sum(self.rewards), False, {}
+ potential_old = self.potential
+ self.potential = self.robot.calc_potential()
- def camera_adjust(self):
- x, y, z = self.robot.fingertip.pose().xyz()
- x *= 0.5
- y *= 0.5
- self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
+ electricity_cost = (
+ -0.10 * (np.abs(a[0] * self.robot.theta_dot) + np.abs(a[1] * self.robot.gamma_dot)
+ ) # work torque*angular_velocity
+ - 0.01 * (np.abs(a[0]) + np.abs(a[1])) # stall torque require some energy
+ )
+ stuck_joint_cost = -0.1 if np.abs(np.abs(self.robot.gamma) - 1) < 0.01 else 0.0
+ self.rewards = [
+ float(self.potential - potential_old),
+ float(electricity_cost),
+ float(stuck_joint_cost)
+ ]
+ self.HUD(state, a, False)
+ return state, sum(self.rewards), False, {}
+ def camera_adjust(self):
+ x, y, z = self.robot.fingertip.pose().xyz()
+ x *= 0.5
+ y *= 0.5
+ self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
-class PusherBulletEnv(MJCFBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Pusher()
- MJCFBaseBulletEnv.__init__(self, self.robot, render)
-
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
-
- def step(self, a):
- self.robot.apply_action(a)
- self.scene.global_step()
-
- state = self.robot.calc_state() # sets self.to_target_vec
-
- potential_old = self.potential
- self.potential = self.robot.calc_potential()
-
- joint_vel = np.array([
- self.robot.shoulder_pan_joint.get_velocity(),
- self.robot.shoulder_lift_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.elbow_flex_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.wrist_flex_joint.get_velocity(),
- self.robot.wrist_roll_joint.get_velocity()
- ])
-
- action_product = np.matmul(np.abs(a), np.abs(joint_vel))
- action_sum = np.sum(a)
-
- electricity_cost = (
- -0.10 * action_product # work torque*angular_velocity
- - 0.01 * action_sum # stall torque require some energy
- )
-
- stuck_joint_cost = 0
- for j in self.robot.ordered_joints:
- if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
- stuck_joint_cost += -0.1
- self.rewards = [float(self.potential - potential_old), float(electricity_cost), float(stuck_joint_cost)]
- self.HUD(state, a, False)
- return state, sum(self.rewards), False, {}
-
- def calc_potential(self):
- return -100 * np.linalg.norm(self.to_target_vec)
-
- def camera_adjust(self):
- x, y, z = self.robot.fingertip.pose().xyz()
- x *= 0.5
- y *= 0.5
- self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
-
-
-class StrikerBulletEnv(MJCFBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Striker()
- MJCFBaseBulletEnv.__init__(self, self.robot, render)
- self._striked = False
- self._min_strike_dist = np.inf
- self.strike_threshold = 0.1
-
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
+class PusherBulletEnv(MJCFBaseBulletEnv):
- def step(self, a):
- self.robot.apply_action(a)
- self.scene.global_step()
+ def __init__(self, render=False):
+ self.robot = Pusher()
+ MJCFBaseBulletEnv.__init__(self, self.robot, render)
- state = self.robot.calc_state() # sets self.to_target_vec
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
- potential_old = self.potential
- self.potential = self.robot.calc_potential()
+ def step(self, a):
+ self.robot.apply_action(a)
+ self.scene.global_step()
- joint_vel = np.array([
- self.robot.shoulder_pan_joint.get_velocity(),
- self.robot.shoulder_lift_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.elbow_flex_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.wrist_flex_joint.get_velocity(),
- self.robot.wrist_roll_joint.get_velocity()
- ])
+ state = self.robot.calc_state() # sets self.to_target_vec
- action_product = np.matmul(np.abs(a), np.abs(joint_vel))
- action_sum = np.sum(a)
+ potential_old = self.potential
+ self.potential = self.robot.calc_potential()
- electricity_cost = (
- -0.10 * action_product # work torque*angular_velocity
- - 0.01 * action_sum # stall torque require some energy
- )
+ joint_vel = np.array([
+ self.robot.shoulder_pan_joint.get_velocity(),
+ self.robot.shoulder_lift_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.elbow_flex_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.wrist_flex_joint.get_velocity(),
+ self.robot.wrist_roll_joint.get_velocity()
+ ])
- stuck_joint_cost = 0
- for j in self.robot.ordered_joints:
- if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
- stuck_joint_cost += -0.1
+ action_product = np.matmul(np.abs(a), np.abs(joint_vel))
+ action_sum = np.sum(a)
- dist_object_finger = self.robot.object.pose().xyz() - self.robot.fingertip.pose().xyz()
- reward_dist_vec = self.robot.object.pose().xyz() - self.robot.target.pose().xyz() # TODO: Should the object and target really belong to the robot? Maybe split this off
+ electricity_cost = (
+ -0.10 * action_product # work torque*angular_velocity
+ - 0.01 * action_sum # stall torque require some energy
+ )
- self._min_strike_dist = min(self._min_strike_dist, np.linalg.norm(reward_dist_vec))
+ stuck_joint_cost = 0
+ for j in self.robot.ordered_joints:
+ if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
+ stuck_joint_cost += -0.1
- if np.linalg.norm(dist_object_finger) < self.strike_threshold:
- self._striked = True
- self._strike_pos = self.robot.fingertip.pose().xyz()
+ self.rewards = [
+ float(self.potential - potential_old),
+ float(electricity_cost),
+ float(stuck_joint_cost)
+ ]
+ self.HUD(state, a, False)
+ return state, sum(self.rewards), False, {}
- if self._striked:
- reward_near_vec = self.robot.object.pose().xyz() - self._strike_pos
- else:
- reward_near_vec = self.robot.object.pose().xyz() - self.robot.fingertip.pose().xyz()
+ def calc_potential(self):
+ return -100 * np.linalg.norm(self.to_target_vec)
- reward_near = - np.linalg.norm(reward_near_vec)
+ def camera_adjust(self):
+ x, y, z = self.robot.fingertip.pose().xyz()
+ x *= 0.5
+ y *= 0.5
+ self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
- reward_dist = - np.linalg.norm(self._min_strike_dist)
- reward_ctrl = - np.square(a).sum()
- self.rewards = [float(self.potential - potential_old), float(electricity_cost), float(stuck_joint_cost),
- 3 * reward_dist, 0.1 * reward_ctrl, 0.5 * reward_near]
- self.HUD(state, a, False)
- return state, sum(self.rewards), False, {}
- def calc_potential(self):
- return -100 * np.linalg.norm(self.to_target_vec)
+class StrikerBulletEnv(MJCFBaseBulletEnv):
- def camera_adjust(self):
- x, y, z = self.robot.fingertip.pose().xyz()
- x *= 0.5
- y *= 0.5
- self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
+ def __init__(self, render=False):
+ self.robot = Striker()
+ MJCFBaseBulletEnv.__init__(self, self.robot, render)
+ self._striked = False
+ self._min_strike_dist = np.inf
+ self.strike_threshold = 0.1
+
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=9.81, timestep=0.0020, frame_skip=5)
+
+ def step(self, a):
+ self.robot.apply_action(a)
+ self.scene.global_step()
+
+ state = self.robot.calc_state() # sets self.to_target_vec
+
+ potential_old = self.potential
+ self.potential = self.robot.calc_potential()
+
+ joint_vel = np.array([
+ self.robot.shoulder_pan_joint.get_velocity(),
+ self.robot.shoulder_lift_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.elbow_flex_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.wrist_flex_joint.get_velocity(),
+ self.robot.wrist_roll_joint.get_velocity()
+ ])
+
+ action_product = np.matmul(np.abs(a), np.abs(joint_vel))
+ action_sum = np.sum(a)
+
+ electricity_cost = (
+ -0.10 * action_product # work torque*angular_velocity
+ - 0.01 * action_sum # stall torque require some energy
+ )
+
+ stuck_joint_cost = 0
+ for j in self.robot.ordered_joints:
+ if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
+ stuck_joint_cost += -0.1
+
+ dist_object_finger = self.robot.object.pose().xyz() - self.robot.fingertip.pose().xyz()
+ reward_dist_vec = self.robot.object.pose().xyz() - self.robot.target.pose().xyz(
+ ) # TODO: Should the object and target really belong to the robot? Maybe split this off
+
+ self._min_strike_dist = min(self._min_strike_dist, np.linalg.norm(reward_dist_vec))
+
+ if np.linalg.norm(dist_object_finger) < self.strike_threshold:
+ self._striked = True
+ self._strike_pos = self.robot.fingertip.pose().xyz()
+
+ if self._striked:
+ reward_near_vec = self.robot.object.pose().xyz() - self._strike_pos
+ else:
+ reward_near_vec = self.robot.object.pose().xyz() - self.robot.fingertip.pose().xyz()
+
+ reward_near = -np.linalg.norm(reward_near_vec)
+
+ reward_dist = -np.linalg.norm(self._min_strike_dist)
+ reward_ctrl = -np.square(a).sum()
+ self.rewards = [
+ float(self.potential - potential_old),
+ float(electricity_cost),
+ float(stuck_joint_cost), 3 * reward_dist, 0.1 * reward_ctrl, 0.5 * reward_near
+ ]
+ self.HUD(state, a, False)
+ return state, sum(self.rewards), False, {}
+
+ def calc_potential(self):
+ return -100 * np.linalg.norm(self.to_target_vec)
+
+ def camera_adjust(self):
+ x, y, z = self.robot.fingertip.pose().xyz()
+ x *= 0.5
+ y *= 0.5
+ self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
class ThrowerBulletEnv(MJCFBaseBulletEnv):
- def __init__(self, render=False):
- self.robot = Thrower()
- MJCFBaseBulletEnv.__init__(self, self.robot, render)
-
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0020, frame_skip=5)
-
- def step(self, a):
- self.robot.apply_action(a)
- self.scene.global_step()
- state = self.robot.calc_state() # sets self.to_target_vec
-
- potential_old = self.potential
- self.potential = self.robot.calc_potential()
-
- joint_vel = np.array([
- self.robot.shoulder_pan_joint.get_velocity(),
- self.robot.shoulder_lift_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.elbow_flex_joint.get_velocity(),
- self.robot.upper_arm_roll_joint.get_velocity(),
- self.robot.wrist_flex_joint.get_velocity(),
- self.robot.wrist_roll_joint.get_velocity()
- ])
-
- action_product = np.matmul(np.abs(a), np.abs(joint_vel))
- action_sum = np.sum(a)
-
- electricity_cost = (
- -0.10 * action_product # work torque*angular_velocity
- - 0.01 * action_sum # stall torque require some energy
- )
-
- stuck_joint_cost = 0
- for j in self.robot.ordered_joints:
- if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
- stuck_joint_cost += -0.1
-
- object_xy = self.robot.object.pose().xyz()[:2]
- target_xy = self.robot.target.pose().xyz()[:2]
-
- if not self.robot._object_hit_ground and self.robot.object.pose().xyz()[2] < -0.25: # TODO: Should the object and target really belong to the robot? Maybe split this off
- self.robot._object_hit_ground = True
- self.robot._object_hit_location = self.robot.object.pose().xyz()
-
- if self.robot._object_hit_ground:
- object_hit_xy = self.robot._object_hit_location[:2]
- reward_dist = -np.linalg.norm(object_hit_xy - target_xy)
- else:
- reward_dist = -np.linalg.norm(object_xy - target_xy)
- reward_ctrl = - np.square(a).sum()
-
- self.rewards = [float(self.potential - potential_old), float(electricity_cost), float(stuck_joint_cost),
- reward_dist, 0.002 * reward_ctrl]
- self.HUD(state, a, False)
- return state, sum(self.rewards), False, {}
-
- def camera_adjust(self):
- x, y, z = self.robot.fingertip.pose().xyz()
- x *= 0.5
- y *= 0.5
- self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
+
+ def __init__(self, render=False):
+ self.robot = Thrower()
+ MJCFBaseBulletEnv.__init__(self, self.robot, render)
+
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=0.0, timestep=0.0020, frame_skip=5)
+
+ def step(self, a):
+ self.robot.apply_action(a)
+ self.scene.global_step()
+ state = self.robot.calc_state() # sets self.to_target_vec
+
+ potential_old = self.potential
+ self.potential = self.robot.calc_potential()
+
+ joint_vel = np.array([
+ self.robot.shoulder_pan_joint.get_velocity(),
+ self.robot.shoulder_lift_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.elbow_flex_joint.get_velocity(),
+ self.robot.upper_arm_roll_joint.get_velocity(),
+ self.robot.wrist_flex_joint.get_velocity(),
+ self.robot.wrist_roll_joint.get_velocity()
+ ])
+
+ action_product = np.matmul(np.abs(a), np.abs(joint_vel))
+ action_sum = np.sum(a)
+
+ electricity_cost = (
+ -0.10 * action_product # work torque*angular_velocity
+ - 0.01 * action_sum # stall torque require some energy
+ )
+
+ stuck_joint_cost = 0
+ for j in self.robot.ordered_joints:
+ if np.abs(j.current_relative_position()[0]) - 1 < 0.01:
+ stuck_joint_cost += -0.1
+
+ object_xy = self.robot.object.pose().xyz()[:2]
+ target_xy = self.robot.target.pose().xyz()[:2]
+
+ if not self.robot._object_hit_ground and self.robot.object.pose().xyz(
+ )[2] < -0.25: # TODO: Should the object and target really belong to the robot? Maybe split this off
+ self.robot._object_hit_ground = True
+ self.robot._object_hit_location = self.robot.object.pose().xyz()
+
+ if self.robot._object_hit_ground:
+ object_hit_xy = self.robot._object_hit_location[:2]
+ reward_dist = -np.linalg.norm(object_hit_xy - target_xy)
+ else:
+ reward_dist = -np.linalg.norm(object_xy - target_xy)
+ reward_ctrl = -np.square(a).sum()
+
+ self.rewards = [
+ float(self.potential - potential_old),
+ float(electricity_cost),
+ float(stuck_joint_cost), reward_dist, 0.002 * reward_ctrl
+ ]
+ self.HUD(state, a, False)
+ return state, sum(self.rewards), False, {}
+
+ def camera_adjust(self):
+ x, y, z = self.robot.fingertip.pose().xyz()
+ x *= 0.5
+ y *= 0.5
+ self.camera.move_and_look_at(0.3, 0.3, 0.3, x, y, z)
diff --git a/examples/pybullet/gym/pybullet_envs/gym_pendulum_envs.py b/examples/pybullet/gym/pybullet_envs/gym_pendulum_envs.py
index 07924c453..310874de8 100644
--- a/examples/pybullet/gym/pybullet_envs/gym_pendulum_envs.py
+++ b/examples/pybullet/gym/pybullet_envs/gym_pendulum_envs.py
@@ -3,83 +3,90 @@ from .env_bases import MJCFBaseBulletEnv
from robot_pendula import InvertedPendulum, InvertedPendulumSwingup, InvertedDoublePendulum
import gym, gym.spaces, gym.utils, gym.utils.seeding
import numpy as np
-import pybullet
+import pybullet
import os, sys
+
class InvertedPendulumBulletEnv(MJCFBaseBulletEnv):
- def __init__(self):
- self.robot = InvertedPendulum()
- MJCFBaseBulletEnv.__init__(self, self.robot)
- self.stateId=-1
-
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
-
- def reset(self):
- if (self.stateId>=0):
- #print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
- self._p.restoreState(self.stateId)
- r = MJCFBaseBulletEnv.reset(self)
- if (self.stateId<0):
- self.stateId = self._p.saveState()
- #print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
- return r
-
- def step(self, a):
- self.robot.apply_action(a)
- self.scene.global_step()
- state = self.robot.calc_state() # sets self.pos_x self.pos_y
- vel_penalty = 0
- if self.robot.swingup:
- reward = np.cos(self.robot.theta)
- done = False
- else:
- reward = 1.0
- done = np.abs(self.robot.theta) > .2
- self.rewards = [float(reward)]
- self.HUD(state, a, done)
- return state, sum(self.rewards), done, {}
-
- def camera_adjust(self):
- self.camera.move_and_look_at(0,1.2,1.0, 0,0,0.5)
+
+ def __init__(self):
+ self.robot = InvertedPendulum()
+ MJCFBaseBulletEnv.__init__(self, self.robot)
+ self.stateId = -1
+
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
+
+ def reset(self):
+ if (self.stateId >= 0):
+ #print("InvertedPendulumBulletEnv reset p.restoreState(",self.stateId,")")
+ self._p.restoreState(self.stateId)
+ r = MJCFBaseBulletEnv.reset(self)
+ if (self.stateId < 0):
+ self.stateId = self._p.saveState()
+ #print("InvertedPendulumBulletEnv reset self.stateId=",self.stateId)
+ return r
+
+ def step(self, a):
+ self.robot.apply_action(a)
+ self.scene.global_step()
+ state = self.robot.calc_state() # sets self.pos_x self.pos_y
+ vel_penalty = 0
+ if self.robot.swingup:
+ reward = np.cos(self.robot.theta)
+ done = False
+ else:
+ reward = 1.0
+ done = np.abs(self.robot.theta) > .2
+ self.rewards = [float(reward)]
+ self.HUD(state, a, done)
+ return state, sum(self.rewards), done, {}
+
+ def camera_adjust(self):
+ self.camera.move_and_look_at(0, 1.2, 1.0, 0, 0, 0.5)
+
class InvertedPendulumSwingupBulletEnv(InvertedPendulumBulletEnv):
- def __init__(self):
- self.robot = InvertedPendulumSwingup()
- MJCFBaseBulletEnv.__init__(self, self.robot)
- self.stateId=-1
+
+ def __init__(self):
+ self.robot = InvertedPendulumSwingup()
+ MJCFBaseBulletEnv.__init__(self, self.robot)
+ self.stateId = -1
+
class InvertedDoublePendulumBulletEnv(MJCFBaseBulletEnv):
- def __init__(self):
- self.robot = InvertedDoublePendulum()
- MJCFBaseBulletEnv.__init__(self, self.robot)
- self.stateId = -1
- def create_single_player_scene(self, bullet_client):
- return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
-
- def reset(self):
- if (self.stateId>=0):
- self._p.restoreState(self.stateId)
- r = MJCFBaseBulletEnv.reset(self)
- if (self.stateId<0):
- self.stateId = self._p.saveState()
- return r
-
- def step(self, a):
- self.robot.apply_action(a)
- self.scene.global_step()
- state = self.robot.calc_state() # sets self.pos_x self.pos_y
- # upright position: 0.6 (one pole) + 0.6 (second pole) * 0.5 (middle of second pole) = 0.9
- # using <site> tag in original xml, upright position is 0.6 + 0.6 = 1.2, difference +0.3
- dist_penalty = 0.01 * self.robot.pos_x ** 2 + (self.robot.pos_y + 0.3 - 2) ** 2
- # v1, v2 = self.model.data.qvel[1:3] TODO when this fixed https://github.com/bulletphysics/bullet3/issues/1040
- #vel_penalty = 1e-3 * v1**2 + 5e-3 * v2**2
- vel_penalty = 0
- alive_bonus = 10
- done = self.robot.pos_y + 0.3 <= 1
- self.rewards = [float(alive_bonus), float(-dist_penalty), float(-vel_penalty)]
- self.HUD(state, a, done)
- return state, sum(self.rewards), done, {}
-
- def camera_adjust(self):
- self.camera.move_and_look_at(0,1.2,1.2, 0,0,0.5)
+
+ def __init__(self):
+ self.robot = InvertedDoublePendulum()
+ MJCFBaseBulletEnv.__init__(self, self.robot)
+ self.stateId = -1
+
+ def create_single_player_scene(self, bullet_client):
+ return SingleRobotEmptyScene(bullet_client, gravity=9.8, timestep=0.0165, frame_skip=1)
+
+ def reset(self):
+ if (self.stateId >= 0):
+ self._p.restoreState(self.stateId)
+ r = MJCFBaseBulletEnv.reset(self)
+ if (self.stateId < 0):
+ self.stateId = self._p.saveState()
+ return r
+
+ def step(self, a):
+ self.robot.apply_action(a)
+ self.scene.global_step()
+ state = self.robot.calc_state() # sets self.pos_x self.pos_y
+ # upright position: 0.6 (one pole) + 0.6 (second pole) * 0.5 (middle of second pole) = 0.9
+ # using <site> tag in original xml, upright position is 0.6 + 0.6 = 1.2, difference +0.3
+ dist_penalty = 0.01 * self.robot.pos_x**2 + (self.robot.pos_y + 0.3 - 2)**2
+ # v1, v2 = self.model.data.qvel[1:3] TODO when this fixed https://github.com/bulletphysics/bullet3/issues/1040
+ #vel_penalty = 1e-3 * v1**2 + 5e-3 * v2**2
+ vel_penalty = 0
+ alive_bonus = 10
+ done = self.robot.pos_y + 0.3 <= 1
+ self.rewards = [float(alive_bonus), float(-dist_penalty), float(-vel_penalty)]
+ self.HUD(state, a, done)
+ return state, sum(self.rewards), done, {}
+
+ def camera_adjust(self):
+ self.camera.move_and_look_at(0, 1.2, 1.2, 0, 0, 0.5)
diff --git a/examples/pybullet/gym/pybullet_envs/kerasrl_utils.py b/examples/pybullet/gym/pybullet_envs/kerasrl_utils.py
index 1ccedce5c..8045fff6c 100644
--- a/examples/pybullet/gym/pybullet_envs/kerasrl_utils.py
+++ b/examples/pybullet/gym/pybullet_envs/kerasrl_utils.py
@@ -1,28 +1,32 @@
-
import re
from gym import error
import glob
- # checkpoints/KerasDDPG-InvertedPendulum-v0-20170701190920_actor.h5
+# checkpoints/KerasDDPG-InvertedPendulum-v0-20170701190920_actor.h5
weight_save_re = re.compile(r'^(?:\w+\/)+?(\w+-v\d+)-(\w+-v\d+)-(\d+)(?:_\w+)?\.(\w+)$')
+
def get_fields(weight_save_name):
- match = weight_save_re.search(weight_save_name)
- if not match:
- raise error.Error('Attempted to read a malformed weight save: {}. (Currently all weight saves must be of the form {}.)'.format(id,weight_save_re.pattern))
- return match.group(1), match.group(2), int(match.group(3))
+ match = weight_save_re.search(weight_save_name)
+ if not match:
+ raise error.Error(
+ 'Attempted to read a malformed weight save: {}. (Currently all weight saves must be of the form {}.)'
+ .format(id, weight_save_re.pattern))
+ return match.group(1), match.group(2), int(match.group(3))
+
def get_latest_save(file_folder, agent_name, env_name, version_number):
- """
+ """
Returns the properties of the latest weight save. The information can be used to generate the loading path
:return:
"""
- path = "%s%s"% (file_folder, "*.h5")
- file_list = glob.glob(path)
- latest_file_properties = []
- file_properties = []
- for f in file_list:
- file_properties = get_fields(f)
- if file_properties[0] == agent_name and file_properties[1] == env_name and (latest_file_properties == [] or file_properties[2] > latest_file_properties[2]):
- latest_file_properties = file_properties
+ path = "%s%s" % (file_folder, "*.h5")
+ file_list = glob.glob(path)
+ latest_file_properties = []
+ file_properties = []
+ for f in file_list:
+ file_properties = get_fields(f)
+ if file_properties[0] == agent_name and file_properties[1] == env_name and (
+ latest_file_properties == [] or file_properties[2] > latest_file_properties[2]):
+ latest_file_properties = file_properties
- return latest_file_properties
+ return latest_file_properties
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py
index b28b04f64..8b1378917 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/__init__.py
@@ -1,3 +1 @@
-
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/__init__.py
index 139597f9c..8b1378917 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/__init__.py
@@ -1,2 +1 @@
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras.py b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras.py
index 016fee5ea..57b27068f 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras.py
@@ -1,4 +1,3 @@
-
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
@@ -22,9 +21,7 @@ def main(unused_argv):
# fix random seed for reproducibility
numpy.random.seed(7)
# load pima indians dataset
- dataset = numpy.loadtxt(
- FLAGS.input_filename,
- delimiter=",")
+ dataset = numpy.loadtxt(FLAGS.input_filename, delimiter=",")
# split into input (X) and output (Y) variables
x = dataset[:, 0:3]
y = dataset[:, 3]
@@ -38,28 +35,27 @@ def main(unused_argv):
model.add(Dense(1, activation="linear"))
# Compile model (use adam or sgd)
- model.compile(
- loss="mean_squared_error",
- optimizer="adam",
- metrics=["mean_squared_error"])
+ model.compile(loss="mean_squared_error", optimizer="adam", metrics=["mean_squared_error"])
# checkpoint
filepath = "/tmp/keras/weights-improvement-{epoch:02d}-{val_loss:.2f}.hdf5"
- checkpoint = ModelCheckpoint(
- filepath, monitor="val_loss", verbose=1, save_best_only=True, mode="min")
+ checkpoint = ModelCheckpoint(filepath,
+ monitor="val_loss",
+ verbose=1,
+ save_best_only=True,
+ mode="min")
callbacks_list = [checkpoint]
# Fit the model
# model.fit(X, Y, epochs=150, batch_size=10)
# model.fit(X, Y, epochs=150, batch_size=10, callbacks=callbacks_list)
- model.fit(
- x,
- y,
- validation_split=0.34,
- epochs=4500,
- batch_size=1024,
- callbacks=callbacks_list,
- verbose=0)
+ model.fit(x,
+ y,
+ validation_split=0.34,
+ epochs=4500,
+ batch_size=1024,
+ callbacks=callbacks_list,
+ verbose=0)
# evaluate the model
scores = model.evaluate(x, y)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras_lstm.py b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras_lstm.py
index f3a45a1dd..35f7a16a1 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras_lstm.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/actuatornet_keras_lstm.py
@@ -75,8 +75,8 @@ reframed = series_to_supervised(scaled, lag_steps, 1)
print("reframed before drop=", reframed)
# drop columns we don't want to predict
-reframed.drop(reframed.columns[[3,7,11,15,19]], axis=1, inplace=True)
-print("after drop=",reframed.head())
+reframed.drop(reframed.columns[[3, 7, 11, 15, 19]], axis=1, inplace=True)
+print("after drop=", reframed.head())
#dummy = scaler.inverse_transform(reframed)
#print(dummy)
@@ -104,17 +104,17 @@ test = values[n_train_hours:, :]
train_X, train_y = train[:, :-1], train[:, -1]
test_X, test_y = test[:, :-1], test[:, -1]
-print("train_X.shape[1]=",train_X.shape[1])
-
+print("train_X.shape[1]=", train_X.shape[1])
# design network
-useLSTM=True
+useLSTM = True
if useLSTM:
# reshape input to be 3D [samples, timesteps, features]
- train_X = train_X.reshape((train_X.shape[0], lag_steps+1, int(train_X.shape[1]/(lag_steps+1))))
- test_X = test_X.reshape((test_X.shape[0], lag_steps+1, int(test_X.shape[1]/(lag_steps+1))))
+ train_X = train_X.reshape(
+ (train_X.shape[0], lag_steps + 1, int(train_X.shape[1] / (lag_steps + 1))))
+ test_X = test_X.reshape((test_X.shape[0], lag_steps + 1, int(test_X.shape[1] / (lag_steps + 1))))
model = Sequential()
- model.add(LSTM(40, input_shape=(train_X.shape[1], train_X.shape[2])))
+ model.add(LSTM(40, input_shape=(train_X.shape[1], train_X.shape[2])))
model.add(Dropout(0.05))
model.add(Dense(8, activation='sigmoid'))
model.add(Dense(8, activation='sigmoid'))
@@ -128,39 +128,37 @@ else:
model.add(Dense(1, activation="linear"))
#model.compile(loss='mae', optimizer='adam')
-model.compile(
- loss='mean_squared_error', optimizer='adam', metrics=['mean_squared_error'])
+model.compile(loss='mean_squared_error', optimizer='adam', metrics=['mean_squared_error'])
# checkpoint
filepath = '/tmp/keras/weights-improvement-{epoch:02d}-{val_loss:.2f}.hdf5'
-checkpoint = ModelCheckpoint(
- filepath, monitor='val_loss', verbose=1, save_best_only=True, mode='min')
+checkpoint = ModelCheckpoint(filepath,
+ monitor='val_loss',
+ verbose=1,
+ save_best_only=True,
+ mode='min')
callbacks_list = [checkpoint]
# fit network
-history = model.fit(
- train_X,
- train_y,
- epochs=1500,
- batch_size=32,
- callbacks=callbacks_list,
- validation_data=(test_X, test_y),
- verbose=2,
- shuffle=False)
+history = model.fit(train_X,
+ train_y,
+ epochs=1500,
+ batch_size=32,
+ callbacks=callbacks_list,
+ validation_data=(test_X, test_y),
+ verbose=2,
+ shuffle=False)
# plot history
-
-data = np.array([[[1.513535008329887299,3.234624992847829894e-01,1.731481043119239782,1.741165415165205399,
-1.534267104753672228e+00,1.071354965017878635e+00,1.712386127673626302e+00]]])
-
+data = np.array([[[
+ 1.513535008329887299, 3.234624992847829894e-01, 1.731481043119239782, 1.741165415165205399,
+ 1.534267104753672228e+00, 1.071354965017878635e+00, 1.712386127673626302e+00
+]]])
#prediction = model.predict(data)
#print("prediction=",prediction)
-
pyplot.plot(history.history['loss'], label='train')
pyplot.plot(history.history['val_loss'], label='test')
pyplot.legend()
pyplot.show()
-
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/minitaur_raibert_controller_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/minitaur_raibert_controller_example.py
index 0be299a75..40e6b4799 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/minitaur_raibert_controller_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/minitaur_raibert_controller_example.py
@@ -15,9 +15,8 @@ FLAGS = tf.app.flags.FLAGS
flags.DEFINE_float("motor_kp", 1.0, "The position gain of the motor.")
flags.DEFINE_float("motor_kd", 0.015, "The speed gain of the motor.")
-flags.DEFINE_float(
- "control_latency", 0.006, "The latency between sensor measurement and action"
- " execution the robot.")
+flags.DEFINE_float("control_latency", 0.006, "The latency between sensor measurement and action"
+ " execution the robot.")
flags.DEFINE_string("log_path", ".", "The directory to write the log file.")
@@ -31,37 +30,34 @@ def speed(t):
def main(argv):
- del argv
- env = minitaur_gym_env.MinitaurGymEnv(
- urdf_version=minitaur_gym_env.RAINBOW_DASH_V0_URDF_VERSION,
- control_time_step=0.006,
- action_repeat=6,
- pd_latency=0.0,
- control_latency=FLAGS.control_latency,
- motor_kp=FLAGS.motor_kp,
- motor_kd=FLAGS.motor_kd,
- remove_default_joint_damping=True,
- leg_model_enabled=False,
- render=True,
- on_rack=False,
- accurate_motor_model_enabled=True,
- log_path=FLAGS.log_path)
- env.reset()
+ del argv
+ env = minitaur_gym_env.MinitaurGymEnv(urdf_version=minitaur_gym_env.RAINBOW_DASH_V0_URDF_VERSION,
+ control_time_step=0.006,
+ action_repeat=6,
+ pd_latency=0.0,
+ control_latency=FLAGS.control_latency,
+ motor_kp=FLAGS.motor_kp,
+ motor_kd=FLAGS.motor_kd,
+ remove_default_joint_damping=True,
+ leg_model_enabled=False,
+ render=True,
+ on_rack=False,
+ accurate_motor_model_enabled=True,
+ log_path=FLAGS.log_path)
+ env.reset()
+
+ controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(env.minitaur)
+
+ tstart = env.minitaur.GetTimeSinceReset()
+ for _ in range(1000):
+ t = env.minitaur.GetTimeSinceReset() - tstart
+ controller.behavior_parameters = (minitaur_raibert_controller.BehaviorParameters(
+ desired_forward_speed=speed(t)))
+ controller.update(t)
+ env.step(controller.get_action())
+
+ #env.close()
- controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(
- env.minitaur)
-
- tstart = env.minitaur.GetTimeSinceReset()
- for _ in range(1000):
- t = env.minitaur.GetTimeSinceReset() - tstart
- controller.behavior_parameters = (
- minitaur_raibert_controller.BehaviorParameters(
- desired_forward_speed=speed(t)))
- controller.update(t)
- env.step(controller.get_action())
-
- #env.close()
if __name__ == "__main__":
tf.app.run(main)
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/proto2csv.py b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/proto2csv.py
index 893c831e0..2e04313e8 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/proto2csv.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/actuatornet/proto2csv.py
@@ -35,12 +35,11 @@ def main(argv):
#print("motorState.velocity=",motorState.velocity)
#print("motorState.action=",motorState.action)
#print("motorState.torque=",motorState.torque)
- recs.append([motorState.angle,motorState.velocity,motorState.action,motorState.torque])
-
+ recs.append([motorState.angle, motorState.velocity, motorState.action, motorState.torque])
+
a = numpy.array(recs)
numpy.savetxt(FLAGS.csv_file, a, delimiter=",")
+
if __name__ == "__main__":
tf.app.run(main)
-
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py
index 8d1c8b69c..8b1378917 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/__init__.py
@@ -1 +1 @@
-
+
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/__init__.py
index 26a87baf9..6f4c222dd 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Proximal Policy Optimization algorithm."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/algorithm.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/algorithm.py
index 81b18b7b4..032eac760 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/algorithm.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/algorithm.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Proximal Policy Optimization algorithm.
Based on John Schulman's implementation in Python and Theano:
@@ -30,9 +29,7 @@ from . import memory
from . import normalize
from . import utility
-
-_NetworkOutput = collections.namedtuple(
- 'NetworkOutput', 'policy, mean, logstd, value, state')
+_NetworkOutput = collections.namedtuple('NetworkOutput', 'policy, mean, logstd, value, state')
class PPOAlgorithm(object):
@@ -53,44 +50,46 @@ class PPOAlgorithm(object):
self._is_training = is_training
self._should_log = should_log
self._config = config
- self._observ_filter = normalize.StreamingNormalize(
- self._batch_env.observ[0], center=True, scale=True, clip=5,
- name='normalize_observ')
- self._reward_filter = normalize.StreamingNormalize(
- self._batch_env.reward[0], center=False, scale=True, clip=10,
- name='normalize_reward')
+ self._observ_filter = normalize.StreamingNormalize(self._batch_env.observ[0],
+ center=True,
+ scale=True,
+ clip=5,
+ name='normalize_observ')
+ self._reward_filter = normalize.StreamingNormalize(self._batch_env.reward[0],
+ center=False,
+ scale=True,
+ clip=10,
+ name='normalize_reward')
# Memory stores tuple of observ, action, mean, logstd, reward.
- template = (
- self._batch_env.observ[0], self._batch_env.action[0],
- self._batch_env.action[0], self._batch_env.action[0],
- self._batch_env.reward[0])
- self._memory = memory.EpisodeMemory(
- template, config.update_every, config.max_length, 'memory')
+ template = (self._batch_env.observ[0], self._batch_env.action[0], self._batch_env.action[0],
+ self._batch_env.action[0], self._batch_env.reward[0])
+ self._memory = memory.EpisodeMemory(template, config.update_every, config.max_length, 'memory')
self._memory_index = tf.Variable(0, False)
use_gpu = self._config.use_gpu and utility.available_gpus()
with tf.device('/gpu:0' if use_gpu else '/cpu:0'):
# Create network variables for later calls to reuse.
- self._network(
- tf.zeros_like(self._batch_env.observ)[:, None],
- tf.ones(len(self._batch_env)), reuse=None)
+ self._network(tf.zeros_like(self._batch_env.observ)[:, None],
+ tf.ones(len(self._batch_env)),
+ reuse=None)
cell = self._config.network(self._batch_env.action.shape[1].value)
with tf.variable_scope('ppo_temporary'):
- self._episodes = memory.EpisodeMemory(
- template, len(batch_env), config.max_length, 'episodes')
- self._last_state = utility.create_nested_vars(
- cell.zero_state(len(batch_env), tf.float32))
- self._last_action = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_action')
- self._last_mean = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_mean')
- self._last_logstd = tf.Variable(
- tf.zeros_like(self._batch_env.action), False, name='last_logstd')
- self._penalty = tf.Variable(
- self._config.kl_init_penalty, False, dtype=tf.float32)
- self._policy_optimizer = self._config.policy_optimizer(
- self._config.policy_lr, name='policy_optimizer')
- self._value_optimizer = self._config.value_optimizer(
- self._config.value_lr, name='value_optimizer')
+ self._episodes = memory.EpisodeMemory(template, len(batch_env), config.max_length,
+ 'episodes')
+ self._last_state = utility.create_nested_vars(cell.zero_state(len(batch_env), tf.float32))
+ self._last_action = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_action')
+ self._last_mean = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_mean')
+ self._last_logstd = tf.Variable(tf.zeros_like(self._batch_env.action),
+ False,
+ name='last_logstd')
+ self._penalty = tf.Variable(self._config.kl_init_penalty, False, dtype=tf.float32)
+ self._policy_optimizer = self._config.policy_optimizer(self._config.policy_lr,
+ name='policy_optimizer')
+ self._value_optimizer = self._config.value_optimizer(self._config.value_lr,
+ name='value_optimizer')
def begin_episode(self, agent_indices):
"""Reset the recurrent states and stored episode.
@@ -118,23 +117,24 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('perform/'):
observ = self._observ_filter.transform(observ)
- network = self._network(
- observ[:, None], tf.ones(observ.shape[0]), self._last_state)
- action = tf.cond(
- self._is_training, network.policy.sample, lambda: network.mean)
+ network = self._network(observ[:, None], tf.ones(observ.shape[0]), self._last_state)
+ action = tf.cond(self._is_training, network.policy.sample, lambda: network.mean)
logprob = network.policy.log_prob(action)[:, 0]
# pylint: disable=g-long-lambda
- summary = tf.cond(self._should_log, lambda: tf.summary.merge([
- tf.summary.histogram('mean', network.mean[:, 0]),
- tf.summary.histogram('std', tf.exp(network.logstd[:, 0])),
- tf.summary.histogram('action', action[:, 0]),
- tf.summary.histogram('logprob', logprob)]), str)
+ summary = tf.cond(
+ self._should_log, lambda: tf.summary.merge([
+ tf.summary.histogram('mean', network.mean[:, 0]),
+ tf.summary.histogram('std', tf.exp(network.logstd[:, 0])),
+ tf.summary.histogram('action', action[:, 0]),
+ tf.summary.histogram('logprob', logprob)
+ ]), str)
# Remember current policy to append to memory in the experience callback.
with tf.control_dependencies([
utility.assign_nested_vars(self._last_state, network.state),
self._last_action.assign(action[:, 0]),
self._last_mean.assign(network.mean[:, 0]),
- self._last_logstd.assign(network.logstd[:, 0])]):
+ self._last_logstd.assign(network.logstd[:, 0])
+ ]):
return tf.check_numerics(action[:, 0], 'action'), tf.identity(summary)
def experience(self, observ, action, reward, unused_done, unused_nextob):
@@ -155,15 +155,14 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('experience/'):
- return tf.cond(
- self._is_training,
- lambda: self._define_experience(observ, action, reward), str)
+ return tf.cond(self._is_training, lambda: self._define_experience(observ, action, reward),
+ str)
def _define_experience(self, observ, action, reward):
"""Implement the branch of experience() entered during training."""
- update_filters = tf.summary.merge([
- self._observ_filter.update(observ),
- self._reward_filter.update(reward)])
+ update_filters = tf.summary.merge(
+ [self._observ_filter.update(observ),
+ self._reward_filter.update(reward)])
with tf.control_dependencies([update_filters]):
if self._config.train_on_agent_action:
# NOTE: Doesn't seem to change much.
@@ -174,14 +173,16 @@ class PPOAlgorithm(object):
norm_observ = self._observ_filter.transform(observ)
norm_reward = tf.reduce_mean(self._reward_filter.transform(reward))
# pylint: disable=g-long-lambda
- summary = tf.cond(self._should_log, lambda: tf.summary.merge([
- update_filters,
- self._observ_filter.summary(),
- self._reward_filter.summary(),
- tf.summary.scalar('memory_size', self._memory_index),
- tf.summary.histogram('normalized_observ', norm_observ),
- tf.summary.histogram('action', self._last_action),
- tf.summary.scalar('normalized_reward', norm_reward)]), str)
+ summary = tf.cond(
+ self._should_log, lambda: tf.summary.merge([
+ update_filters,
+ self._observ_filter.summary(),
+ self._reward_filter.summary(),
+ tf.summary.scalar('memory_size', self._memory_index),
+ tf.summary.histogram('normalized_observ', norm_observ),
+ tf.summary.histogram('action', self._last_action),
+ tf.summary.scalar('normalized_reward', norm_reward)
+ ]), str)
return summary
def end_episode(self, agent_indices):
@@ -199,20 +200,16 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('end_episode/'):
- return tf.cond(
- self._is_training,
- lambda: self._define_end_episode(agent_indices), str)
+ return tf.cond(self._is_training, lambda: self._define_end_episode(agent_indices), str)
def _define_end_episode(self, agent_indices):
"""Implement the branch of end_episode() entered during training."""
episodes, length = self._episodes.data(agent_indices)
space_left = self._config.update_every - self._memory_index
- use_episodes = tf.range(tf.minimum(
- tf.shape(agent_indices)[0], space_left))
+ use_episodes = tf.range(tf.minimum(tf.shape(agent_indices)[0], space_left))
episodes = [tf.gather(elem, use_episodes) for elem in episodes]
- append = self._memory.replace(
- episodes, tf.gather(length, use_episodes),
- use_episodes + self._memory_index)
+ append = self._memory.replace(episodes, tf.gather(length, use_episodes),
+ use_episodes + self._memory_index)
with tf.control_dependencies([append]):
inc_index = self._memory_index.assign_add(tf.shape(use_episodes)[0])
with tf.control_dependencies([inc_index]):
@@ -229,8 +226,7 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('training'):
- assert_full = tf.assert_equal(
- self._memory_index, self._config.update_every)
+ assert_full = tf.assert_equal(self._memory_index, self._config.update_every)
with tf.control_dependencies([assert_full]):
data = self._memory.data()
(observ, action, old_mean, old_logstd, reward), length = data
@@ -238,21 +234,17 @@ class PPOAlgorithm(object):
length = tf.identity(length)
observ = self._observ_filter.transform(observ)
reward = self._reward_filter.transform(reward)
- policy_summary = self._update_policy(
- observ, action, old_mean, old_logstd, reward, length)
+ policy_summary = self._update_policy(observ, action, old_mean, old_logstd, reward, length)
with tf.control_dependencies([policy_summary]):
value_summary = self._update_value(observ, reward, length)
with tf.control_dependencies([value_summary]):
- penalty_summary = self._adjust_penalty(
- observ, old_mean, old_logstd, length)
+ penalty_summary = self._adjust_penalty(observ, old_mean, old_logstd, length)
with tf.control_dependencies([penalty_summary]):
- clear_memory = tf.group(
- self._memory.clear(), self._memory_index.assign(0))
+ clear_memory = tf.group(self._memory.clear(), self._memory_index.assign(0))
with tf.control_dependencies([clear_memory]):
- weight_summary = utility.variable_summaries(
- tf.trainable_variables(), self._config.weight_summaries)
- return tf.summary.merge([
- policy_summary, value_summary, penalty_summary, weight_summary])
+ weight_summary = utility.variable_summaries(tf.trainable_variables(),
+ self._config.weight_summaries)
+ return tf.summary.merge([policy_summary, value_summary, penalty_summary, weight_summary])
def _update_value(self, observ, reward, length):
"""Perform multiple update steps of the value baseline.
@@ -269,10 +261,9 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('update_value'):
- loss, summary = tf.scan(
- lambda _1, _2: self._update_value_step(observ, reward, length),
- tf.range(self._config.update_epochs_value),
- [0., ''], parallel_iterations=1)
+ loss, summary = tf.scan(lambda _1, _2: self._update_value_step(observ, reward, length),
+ tf.range(self._config.update_epochs_value), [0., ''],
+ parallel_iterations=1)
print_loss = tf.Print(0, [tf.reduce_mean(loss)], 'value loss: ')
with tf.control_dependencies([loss, print_loss]):
return summary[self._config.update_epochs_value // 2]
@@ -289,15 +280,13 @@ class PPOAlgorithm(object):
Tuple of loss tensor and summary tensor.
"""
loss, summary = self._value_loss(observ, reward, length)
- gradients, variables = (
- zip(*self._value_optimizer.compute_gradients(loss)))
- optimize = self._value_optimizer.apply_gradients(
- zip(gradients, variables))
+ gradients, variables = (zip(*self._value_optimizer.compute_gradients(loss)))
+ optimize = self._value_optimizer.apply_gradients(zip(gradients, variables))
summary = tf.summary.merge([
summary,
tf.summary.scalar('gradient_norm', tf.global_norm(gradients)),
- utility.gradient_summaries(
- zip(gradients, variables), dict(value=r'.*'))])
+ utility.gradient_summaries(zip(gradients, variables), dict(value=r'.*'))
+ ])
with tf.control_dependencies([optimize]):
return [tf.identity(loss), tf.identity(summary)]
@@ -317,18 +306,17 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('value_loss'):
value = self._network(observ, length).value
- return_ = utility.discounted_return(
- reward, length, self._config.discount)
+ return_ = utility.discounted_return(reward, length, self._config.discount)
advantage = return_ - value
- value_loss = 0.5 * self._mask(advantage ** 2, length)
+ value_loss = 0.5 * self._mask(advantage**2, length)
summary = tf.summary.merge([
tf.summary.histogram('value_loss', value_loss),
- tf.summary.scalar('avg_value_loss', tf.reduce_mean(value_loss))])
+ tf.summary.scalar('avg_value_loss', tf.reduce_mean(value_loss))
+ ])
value_loss = tf.reduce_mean(value_loss)
return tf.check_numerics(value_loss, 'value_loss'), summary
- def _update_policy(
- self, observ, action, old_mean, old_logstd, reward, length):
+ def _update_policy(self, observ, action, old_mean, old_logstd, reward, length):
"""Perform multiple update steps of the policy.
The advantage is computed once at the beginning and shared across
@@ -347,35 +335,28 @@ class PPOAlgorithm(object):
Summary tensor.
"""
with tf.name_scope('update_policy'):
- return_ = utility.discounted_return(
- reward, length, self._config.discount)
+ return_ = utility.discounted_return(reward, length, self._config.discount)
value = self._network(observ, length).value
if self._config.gae_lambda:
- advantage = utility.lambda_return(
- reward, value, length, self._config.discount,
- self._config.gae_lambda)
+ advantage = utility.lambda_return(reward, value, length, self._config.discount,
+ self._config.gae_lambda)
else:
advantage = return_ - value
mean, variance = tf.nn.moments(advantage, axes=[0, 1], keep_dims=True)
advantage = (advantage - mean) / (tf.sqrt(variance) + 1e-8)
advantage = tf.Print(
- advantage, [tf.reduce_mean(return_), tf.reduce_mean(value)],
- 'return and value: ')
- advantage = tf.Print(
- advantage, [tf.reduce_mean(advantage)],
- 'normalized advantage: ')
+ advantage, [tf.reduce_mean(return_), tf.reduce_mean(value)], 'return and value: ')
+ advantage = tf.Print(advantage, [tf.reduce_mean(advantage)], 'normalized advantage: ')
# pylint: disable=g-long-lambda
- loss, summary = tf.scan(
- lambda _1, _2: self._update_policy_step(
- observ, action, old_mean, old_logstd, advantage, length),
- tf.range(self._config.update_epochs_policy),
- [0., ''], parallel_iterations=1)
+ loss, summary = tf.scan(lambda _1, _2: self._update_policy_step(
+ observ, action, old_mean, old_logstd, advantage, length),
+ tf.range(self._config.update_epochs_policy), [0., ''],
+ parallel_iterations=1)
print_loss = tf.Print(0, [tf.reduce_mean(loss)], 'policy loss: ')
with tf.control_dependencies([loss, print_loss]):
return summary[self._config.update_epochs_policy // 2]
- def _update_policy_step(
- self, observ, action, old_mean, old_logstd, advantage, length):
+ def _update_policy_step(self, observ, action, old_mean, old_logstd, advantage, length):
"""Compute the current policy loss and perform a gradient update step.
Args:
@@ -390,23 +371,19 @@ class PPOAlgorithm(object):
Tuple of loss tensor and summary tensor.
"""
network = self._network(observ, length)
- loss, summary = self._policy_loss(
- network.mean, network.logstd, old_mean, old_logstd, action,
- advantage, length)
- gradients, variables = (
- zip(*self._policy_optimizer.compute_gradients(loss)))
- optimize = self._policy_optimizer.apply_gradients(
- zip(gradients, variables))
+ loss, summary = self._policy_loss(network.mean, network.logstd, old_mean, old_logstd, action,
+ advantage, length)
+ gradients, variables = (zip(*self._policy_optimizer.compute_gradients(loss)))
+ optimize = self._policy_optimizer.apply_gradients(zip(gradients, variables))
summary = tf.summary.merge([
summary,
tf.summary.scalar('gradient_norm', tf.global_norm(gradients)),
- utility.gradient_summaries(
- zip(gradients, variables), dict(policy=r'.*'))])
+ utility.gradient_summaries(zip(gradients, variables), dict(policy=r'.*'))
+ ])
with tf.control_dependencies([optimize]):
return [tf.identity(loss), tf.identity(summary)]
- def _policy_loss(
- self, mean, logstd, old_mean, old_logstd, action, advantage, length):
+ def _policy_loss(self, mean, logstd, old_mean, old_logstd, action, advantage, length):
"""Compute the policy loss composed of multiple components.
1. The policy gradient loss is importance sampled from the data-collecting
@@ -430,24 +407,20 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('policy_loss'):
entropy = utility.diag_normal_entropy(mean, logstd)
- kl = tf.reduce_mean(self._mask(utility.diag_normal_kl(
- old_mean, old_logstd, mean, logstd), length), 1)
+ kl = tf.reduce_mean(
+ self._mask(utility.diag_normal_kl(old_mean, old_logstd, mean, logstd), length), 1)
policy_gradient = tf.exp(
utility.diag_normal_logpdf(mean, logstd, action) -
utility.diag_normal_logpdf(old_mean, old_logstd, action))
- surrogate_loss = -tf.reduce_mean(self._mask(
- policy_gradient * tf.stop_gradient(advantage), length), 1)
+ surrogate_loss = -tf.reduce_mean(
+ self._mask(policy_gradient * tf.stop_gradient(advantage), length), 1)
kl_penalty = self._penalty * kl
cutoff_threshold = self._config.kl_target * self._config.kl_cutoff_factor
- cutoff_count = tf.reduce_sum(
- tf.cast(kl > cutoff_threshold, tf.int32))
- with tf.control_dependencies([tf.cond(
- cutoff_count > 0,
- lambda: tf.Print(0, [cutoff_count], 'kl cutoff! '), int)]):
- kl_cutoff = (
- self._config.kl_cutoff_coef *
- tf.cast(kl > cutoff_threshold, tf.float32) *
- (kl - cutoff_threshold) ** 2)
+ cutoff_count = tf.reduce_sum(tf.cast(kl > cutoff_threshold, tf.int32))
+ with tf.control_dependencies(
+ [tf.cond(cutoff_count > 0, lambda: tf.Print(0, [cutoff_count], 'kl cutoff! '), int)]):
+ kl_cutoff = (self._config.kl_cutoff_coef * tf.cast(kl > cutoff_threshold, tf.float32) *
+ (kl - cutoff_threshold)**2)
policy_loss = surrogate_loss + kl_penalty + kl_cutoff
summary = tf.summary.merge([
tf.summary.histogram('entropy', entropy),
@@ -459,7 +432,8 @@ class PPOAlgorithm(object):
tf.summary.histogram('policy_loss', policy_loss),
tf.summary.scalar('avg_surr_loss', tf.reduce_mean(surrogate_loss)),
tf.summary.scalar('avg_kl_penalty', tf.reduce_mean(kl_penalty)),
- tf.summary.scalar('avg_policy_loss', tf.reduce_mean(policy_loss))])
+ tf.summary.scalar('avg_policy_loss', tf.reduce_mean(policy_loss))
+ ])
policy_loss = tf.reduce_mean(policy_loss, 0)
return tf.check_numerics(policy_loss, 'policy_loss'), summary
@@ -481,30 +455,30 @@ class PPOAlgorithm(object):
"""
with tf.name_scope('adjust_penalty'):
network = self._network(observ, length)
- assert_change = tf.assert_equal(
- tf.reduce_all(tf.equal(network.mean, old_mean)), False,
- message='policy should change')
+ assert_change = tf.assert_equal(tf.reduce_all(tf.equal(network.mean, old_mean)),
+ False,
+ message='policy should change')
print_penalty = tf.Print(0, [self._penalty], 'current penalty: ')
with tf.control_dependencies([assert_change, print_penalty]):
- kl_change = tf.reduce_mean(self._mask(utility.diag_normal_kl(
- old_mean, old_logstd, network.mean, network.logstd), length))
+ kl_change = tf.reduce_mean(
+ self._mask(utility.diag_normal_kl(old_mean, old_logstd, network.mean, network.logstd),
+ length))
kl_change = tf.Print(kl_change, [kl_change], 'kl change: ')
maybe_increase = tf.cond(
kl_change > 1.3 * self._config.kl_target,
# pylint: disable=g-long-lambda
- lambda: tf.Print(self._penalty.assign(
- self._penalty * 1.5), [0], 'increase penalty '),
+ lambda: tf.Print(self._penalty.assign(self._penalty * 1.5), [0], 'increase penalty '),
float)
maybe_decrease = tf.cond(
kl_change < 0.7 * self._config.kl_target,
# pylint: disable=g-long-lambda
- lambda: tf.Print(self._penalty.assign(
- self._penalty / 1.5), [0], 'decrease penalty '),
+ lambda: tf.Print(self._penalty.assign(self._penalty / 1.5), [0], 'decrease penalty '),
float)
with tf.control_dependencies([maybe_increase, maybe_decrease]):
return tf.summary.merge([
tf.summary.scalar('kl_change', kl_change),
- tf.summary.scalar('penalty', self._penalty)])
+ tf.summary.scalar('penalty', self._penalty)
+ ])
def _mask(self, tensor, length):
"""Set padding elements of a batch of sequences to zero.
@@ -548,11 +522,14 @@ class PPOAlgorithm(object):
with tf.device('/gpu:0' if use_gpu else '/cpu:0'):
observ = tf.check_numerics(observ, 'observ')
cell = self._config.network(self._batch_env.action.shape[1].value)
- (mean, logstd, value), state = tf.nn.dynamic_rnn(
- cell, observ, length, state, tf.float32, swap_memory=True)
+ (mean, logstd, value), state = tf.nn.dynamic_rnn(cell,
+ observ,
+ length,
+ state,
+ tf.float32,
+ swap_memory=True)
mean = tf.check_numerics(mean, 'mean')
logstd = tf.check_numerics(logstd, 'logstd')
value = tf.check_numerics(value, 'value')
- policy = tf.contrib.distributions.MultivariateNormalDiag(
- mean, tf.exp(logstd))
+ policy = tf.contrib.distributions.MultivariateNormalDiag(mean, tf.exp(logstd))
return _NetworkOutput(policy, mean, logstd, value, state)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/memory.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/memory.py
index 81e0f73d7..37a7c7f53 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/memory.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/memory.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Memory that stores episodes."""
from __future__ import absolute_import
@@ -43,10 +42,9 @@ class EpisodeMemory(object):
self._scope = scope
self._length = tf.Variable(tf.zeros(capacity, tf.int32), False)
self._buffers = [
- tf.Variable(tf.zeros(
- [capacity, max_length] + elem.shape.as_list(),
- elem.dtype), False)
- for elem in template]
+ tf.Variable(tf.zeros([capacity, max_length] + elem.shape.as_list(), elem.dtype), False)
+ for elem in template
+ ]
def length(self, rows=None):
"""Tensor holding the current length of episodes.
@@ -72,13 +70,11 @@ class EpisodeMemory(object):
"""
rows = tf.range(self._capacity) if rows is None else rows
assert rows.shape.ndims == 1
- assert_capacity = tf.assert_less(
- rows, self._capacity,
- message='capacity exceeded')
+ assert_capacity = tf.assert_less(rows, self._capacity, message='capacity exceeded')
with tf.control_dependencies([assert_capacity]):
- assert_max_length = tf.assert_less(
- tf.gather(self._length, rows), self._max_length,
- message='max length exceeded')
+ assert_max_length = tf.assert_less(tf.gather(self._length, rows),
+ self._max_length,
+ message='max length exceeded')
append_ops = []
with tf.control_dependencies([assert_max_length]):
for buffer_, elements in zip(self._buffers, transitions):
@@ -86,8 +82,7 @@ class EpisodeMemory(object):
indices = tf.stack([rows, timestep], 1)
append_ops.append(tf.scatter_nd_update(buffer_, indices, elements))
with tf.control_dependencies(append_ops):
- episode_mask = tf.reduce_sum(tf.one_hot(
- rows, self._capacity, dtype=tf.int32), 0)
+ episode_mask = tf.reduce_sum(tf.one_hot(rows, self._capacity, dtype=tf.int32), 0)
return self._length.assign_add(episode_mask)
def replace(self, episodes, length, rows=None):
@@ -103,11 +98,11 @@ class EpisodeMemory(object):
"""
rows = tf.range(self._capacity) if rows is None else rows
assert rows.shape.ndims == 1
- assert_capacity = tf.assert_less(
- rows, self._capacity, message='capacity exceeded')
+ assert_capacity = tf.assert_less(rows, self._capacity, message='capacity exceeded')
with tf.control_dependencies([assert_capacity]):
- assert_max_length = tf.assert_less_equal(
- length, self._max_length, message='max length exceeded')
+ assert_max_length = tf.assert_less_equal(length,
+ self._max_length,
+ message='max length exceeded')
replace_ops = []
with tf.control_dependencies([assert_max_length]):
for buffer_, elements in zip(self._buffers, episodes):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/normalize.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/normalize.py
index 6c4170519..4de38fd25 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/normalize.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/normalize.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Normalize tensors based on streaming estimates of mean and variance."""
from __future__ import absolute_import
@@ -24,8 +23,7 @@ import tensorflow as tf
class StreamingNormalize(object):
"""Normalize tensors based on streaming estimates of mean and variance."""
- def __init__(
- self, template, center=True, scale=True, clip=10, name='normalize'):
+ def __init__(self, template, center=True, scale=True, clip=10, name='normalize'):
"""Normalize tensors based on streaming estimates of mean and variance.
Centering the value, scaling it by the standard deviation, and clipping
@@ -69,8 +67,7 @@ class StreamingNormalize(object):
if self._scale:
# We cannot scale before seeing at least two samples.
value /= tf.cond(
- self._count > 1, lambda: self._std() + 1e-8,
- lambda: tf.ones_like(self._var_sum))[None]
+ self._count > 1, lambda: self._std() + 1e-8, lambda: tf.ones_like(self._var_sum))[None]
if self._clip:
value = tf.clip_by_value(value, -self._clip, self._clip)
# Remove batch dimension if necessary.
@@ -97,8 +94,7 @@ class StreamingNormalize(object):
mean_delta = tf.reduce_sum(value - self._mean[None, ...], 0)
new_mean = self._mean + mean_delta / step
new_mean = tf.cond(self._count > 1, lambda: new_mean, lambda: value[0])
- var_delta = (
- value - self._mean[None, ...]) * (value - new_mean[None, ...])
+ var_delta = (value - self._mean[None, ...]) * (value - new_mean[None, ...])
new_var_sum = self._var_sum + tf.reduce_sum(var_delta, 0)
with tf.control_dependencies([new_mean, new_var_sum]):
update = self._mean.assign(new_mean), self._var_sum.assign(new_var_sum)
@@ -116,10 +112,8 @@ class StreamingNormalize(object):
Operation.
"""
with tf.name_scope(self._name + '/reset'):
- return tf.group(
- self._count.assign(0),
- self._mean.assign(tf.zeros_like(self._mean)),
- self._var_sum.assign(tf.zeros_like(self._var_sum)))
+ return tf.group(self._count.assign(0), self._mean.assign(tf.zeros_like(self._mean)),
+ self._var_sum.assign(tf.zeros_like(self._var_sum)))
def summary(self):
"""Summary string of mean and standard deviation.
@@ -128,10 +122,8 @@ class StreamingNormalize(object):
Summary tensor.
"""
with tf.name_scope(self._name + '/summary'):
- mean_summary = tf.cond(
- self._count > 0, lambda: self._summary('mean', self._mean), str)
- std_summary = tf.cond(
- self._count > 1, lambda: self._summary('stddev', self._std()), str)
+ mean_summary = tf.cond(self._count > 0, lambda: self._summary('mean', self._mean), str)
+ std_summary = tf.cond(self._count > 1, lambda: self._summary('stddev', self._std()), str)
return tf.summary.merge([mean_summary, std_summary])
def _std(self):
@@ -143,10 +135,8 @@ class StreamingNormalize(object):
Returns:
Tensor of current variance.
"""
- variance = tf.cond(
- self._count > 1,
- lambda: self._var_sum / tf.cast(self._count - 1, tf.float32),
- lambda: tf.ones_like(self._var_sum) * float('nan'))
+ variance = tf.cond(self._count > 1, lambda: self._var_sum / tf.cast(
+ self._count - 1, tf.float32), lambda: tf.ones_like(self._var_sum) * float('nan'))
# The epsilon corrects for small negative variance values caused by
# the algorithm. It was empirically chosen to work with all environments
# tested.
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/utility.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/utility.py
index 79645b16b..9f6360404 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/utility.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/ppo/utility.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Utilities for the PPO algorithm."""
from __future__ import absolute_import
@@ -51,8 +50,7 @@ def reinit_nested_vars(variables, indices=None):
Operation.
"""
if isinstance(variables, (tuple, list)):
- return tf.group(*[
- reinit_nested_vars(variable, indices) for variable in variables])
+ return tf.group(*[reinit_nested_vars(variable, indices) for variable in variables])
if indices is None:
return variables.assign(tf.zeros_like(variables))
else:
@@ -71,9 +69,8 @@ def assign_nested_vars(variables, tensors):
Operation.
"""
if isinstance(variables, (tuple, list)):
- return tf.group(*[
- assign_nested_vars(variable, tensor)
- for variable, tensor in zip(variables, tensors)])
+ return tf.group(
+ *[assign_nested_vars(variable, tensor) for variable, tensor in zip(variables, tensors)])
return variables.assign(tensors)
@@ -81,10 +78,11 @@ def discounted_return(reward, length, discount):
"""Discounted Monte-Carlo returns."""
timestep = tf.range(reward.shape[1].value)
mask = tf.cast(timestep[None, :] < length[:, None], tf.float32)
- return_ = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur + discount * agg,
- tf.transpose(tf.reverse(mask * reward, [1]), [1, 0]),
- tf.zeros_like(reward[:, -1]), 1, False), [1, 0]), [1])
+ return_ = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur + discount * agg,
+ tf.transpose(tf.reverse(mask * reward, [1]), [1, 0]),
+ tf.zeros_like(reward[:, -1]), 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(return_), 'return')
@@ -95,9 +93,8 @@ def fixed_step_return(reward, value, length, discount, window):
return_ = tf.zeros_like(reward)
for _ in range(window):
return_ += reward
- reward = discount * tf.concat(
- [reward[:, 1:], tf.zeros_like(reward[:, -1:])], 1)
- return_ += discount ** window * tf.concat(
+ reward = discount * tf.concat([reward[:, 1:], tf.zeros_like(reward[:, -1:])], 1)
+ return_ += discount**window * tf.concat(
[value[:, window:], tf.zeros_like(value[:, -window:]), 1])
return tf.check_numerics(tf.stop_gradient(mask * return_), 'return')
@@ -109,10 +106,11 @@ def lambda_return(reward, value, length, discount, lambda_):
sequence = mask * reward + discount * value * (1 - lambda_)
discount = mask * discount * lambda_
sequence = tf.stack([sequence, discount], 2)
- return_ = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur[0] + cur[1] * agg,
- tf.transpose(tf.reverse(sequence, [1]), [1, 2, 0]),
- tf.zeros_like(value[:, -1]), 1, False), [1, 0]), [1])
+ return_ = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur[0] + cur[1] * agg,
+ tf.transpose(tf.reverse(sequence, [1]), [1, 2, 0]), tf.zeros_like(value[:, -1]),
+ 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(return_), 'return')
@@ -122,27 +120,26 @@ def lambda_advantage(reward, value, length, discount):
mask = tf.cast(timestep[None, :] < length[:, None], tf.float32)
next_value = tf.concat([value[:, 1:], tf.zeros_like(value[:, -1:])], 1)
delta = reward + discount * next_value - value
- advantage = tf.reverse(tf.transpose(tf.scan(
- lambda agg, cur: cur + discount * agg,
- tf.transpose(tf.reverse(mask * delta, [1]), [1, 0]),
- tf.zeros_like(delta[:, -1]), 1, False), [1, 0]), [1])
+ advantage = tf.reverse(
+ tf.transpose(
+ tf.scan(lambda agg, cur: cur + discount * agg,
+ tf.transpose(tf.reverse(mask * delta, [1]), [1, 0]), tf.zeros_like(delta[:, -1]),
+ 1, False), [1, 0]), [1])
return tf.check_numerics(tf.stop_gradient(advantage), 'advantage')
def diag_normal_kl(mean0, logstd0, mean1, logstd1):
"""Epirical KL divergence of two normals with diagonal covariance."""
logstd0_2, logstd1_2 = 2 * logstd0, 2 * logstd1
- return 0.5 * (
- tf.reduce_sum(tf.exp(logstd0_2 - logstd1_2), -1) +
- tf.reduce_sum((mean1 - mean0) ** 2 / tf.exp(logstd1_2), -1) +
- tf.reduce_sum(logstd1_2, -1) - tf.reduce_sum(logstd0_2, -1) -
- mean0.shape[-1].value)
+ return 0.5 * (tf.reduce_sum(tf.exp(logstd0_2 - logstd1_2), -1) + tf.reduce_sum(
+ (mean1 - mean0)**2 / tf.exp(logstd1_2), -1) + tf.reduce_sum(logstd1_2, -1) -
+ tf.reduce_sum(logstd0_2, -1) - mean0.shape[-1].value)
def diag_normal_logpdf(mean, logstd, loc):
"""Log density of a normal with diagonal covariance."""
constant = -0.5 * (math.log(2 * math.pi) + logstd)
- value = -0.5 * ((loc - mean) / tf.exp(logstd)) ** 2
+ value = -0.5 * ((loc - mean) / tf.exp(logstd))**2
return tf.reduce_sum(constant + value, -1)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/__init__.py
index 05ee82406..a3980d0f3 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Executable scripts for reinforcement learning."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/configs.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/configs.py
index 669f61827..1ea65948b 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/configs.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/configs.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Example configurations using the PPO algorithm."""
from __future__ import absolute_import
@@ -33,10 +32,7 @@ def default():
use_gpu = False
# Network
network = networks.ForwardGaussianPolicy
- weight_summaries = dict(
- all=r'.*',
- policy=r'.*/policy/.*',
- value=r'.*/value/.*')
+ weight_summaries = dict(all=r'.*', policy=r'.*/policy/.*', value=r'.*/value/.*')
policy_layers = 200, 100
value_layers = 200, 100
init_mean_factor = 0.05
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/networks.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/networks.py
index fe46e6b8f..d2c22bd0f 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/networks.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/networks.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Networks for the PPO algorithm defined as recurrent cells."""
from __future__ import absolute_import
@@ -20,11 +19,10 @@ from __future__ import print_function
import tensorflow as tf
-
-_MEAN_WEIGHTS_INITIALIZER = tf.contrib.layers.variance_scaling_initializer(
- factor=0.1)
+_MEAN_WEIGHTS_INITIALIZER = tf.contrib.layers.variance_scaling_initializer(factor=0.1)
_LOGSTD_INITIALIZER = tf.random_normal_initializer(-1, 1e-10)
+
class LinearGaussianPolicy(tf.contrib.rnn.RNNCell):
"""Indepent linear network with a tanh at the end for policy and feedforward network for the value.
@@ -56,15 +54,12 @@ class LinearGaussianPolicy(tf.contrib.rnn.RNNCell):
def __call__(self, observation, state):
with tf.variable_scope('policy'):
x = tf.contrib.layers.flatten(observation)
- mean = tf.contrib.layers.fully_connected(
- x,
- self._action_size,
- tf.tanh,
- weights_initializer=self._mean_weights_initializer)
- logstd = tf.get_variable('logstd', mean.shape[1:], tf.float32,
- self._logstd_initializer)
- logstd = tf.tile(logstd[None, ...],
- [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
+ mean = tf.contrib.layers.fully_connected(x,
+ self._action_size,
+ tf.tanh,
+ weights_initializer=self._mean_weights_initializer)
+ logstd = tf.get_variable('logstd', mean.shape[1:], tf.float32, self._logstd_initializer)
+ logstd = tf.tile(logstd[None, ...], [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
with tf.variable_scope('value'):
x = tf.contrib.layers.flatten(observation)
for size in self._value_layers:
@@ -80,10 +75,12 @@ class ForwardGaussianPolicy(tf.contrib.rnn.RNNCell):
is learned as independent parameter vector.
"""
- def __init__(
- self, policy_layers, value_layers, action_size,
- mean_weights_initializer=_MEAN_WEIGHTS_INITIALIZER,
- logstd_initializer=_LOGSTD_INITIALIZER):
+ def __init__(self,
+ policy_layers,
+ value_layers,
+ action_size,
+ mean_weights_initializer=_MEAN_WEIGHTS_INITIALIZER,
+ logstd_initializer=_LOGSTD_INITIALIZER):
self._policy_layers = policy_layers
self._value_layers = value_layers
self._action_size = action_size
@@ -104,13 +101,12 @@ class ForwardGaussianPolicy(tf.contrib.rnn.RNNCell):
x = tf.contrib.layers.flatten(observation)
for size in self._policy_layers:
x = tf.contrib.layers.fully_connected(x, size, tf.nn.relu)
- mean = tf.contrib.layers.fully_connected(
- x, self._action_size, tf.tanh,
- weights_initializer=self._mean_weights_initializer)
- logstd = tf.get_variable(
- 'logstd', mean.shape[1:], tf.float32, self._logstd_initializer)
- logstd = tf.tile(
- logstd[None, ...], [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
+ mean = tf.contrib.layers.fully_connected(x,
+ self._action_size,
+ tf.tanh,
+ weights_initializer=self._mean_weights_initializer)
+ logstd = tf.get_variable('logstd', mean.shape[1:], tf.float32, self._logstd_initializer)
+ logstd = tf.tile(logstd[None, ...], [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
with tf.variable_scope('value'):
x = tf.contrib.layers.flatten(observation)
for size in self._value_layers:
@@ -127,10 +123,12 @@ class RecurrentGaussianPolicy(tf.contrib.rnn.RNNCell):
and uses a GRU cell.
"""
- def __init__(
- self, policy_layers, value_layers, action_size,
- mean_weights_initializer=_MEAN_WEIGHTS_INITIALIZER,
- logstd_initializer=_LOGSTD_INITIALIZER):
+ def __init__(self,
+ policy_layers,
+ value_layers,
+ action_size,
+ mean_weights_initializer=_MEAN_WEIGHTS_INITIALIZER,
+ logstd_initializer=_LOGSTD_INITIALIZER):
self._policy_layers = policy_layers
self._value_layers = value_layers
self._action_size = action_size
@@ -152,13 +150,12 @@ class RecurrentGaussianPolicy(tf.contrib.rnn.RNNCell):
for size in self._policy_layers[:-1]:
x = tf.contrib.layers.fully_connected(x, size, tf.nn.relu)
x, state = self._cell(x, state)
- mean = tf.contrib.layers.fully_connected(
- x, self._action_size, tf.tanh,
- weights_initializer=self._mean_weights_initializer)
- logstd = tf.get_variable(
- 'logstd', mean.shape[1:], tf.float32, self._logstd_initializer)
- logstd = tf.tile(
- logstd[None, ...], [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
+ mean = tf.contrib.layers.fully_connected(x,
+ self._action_size,
+ tf.tanh,
+ weights_initializer=self._mean_weights_initializer)
+ logstd = tf.get_variable('logstd', mean.shape[1:], tf.float32, self._logstd_initializer)
+ logstd = tf.tile(logstd[None, ...], [tf.shape(mean)[0]] + [1] * logstd.shape.ndims)
with tf.variable_scope('value'):
x = tf.contrib.layers.flatten(observation)
for size in self._value_layers:
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train.py
index e7048c2d9..99495b362 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
r"""Script to train a batch reinforcement learning algorithm.
Command line:
@@ -68,21 +67,25 @@ def _define_loop(graph, logdir, train_steps, eval_steps):
Returns:
Loop object.
"""
- loop = tools.Loop(
- logdir, graph.step, graph.should_log, graph.do_report,
- graph.force_reset)
- loop.add_phase(
- 'train', graph.done, graph.score, graph.summary, train_steps,
- report_every=None,
- log_every=train_steps // 2,
- checkpoint_every=None,
- feed={graph.is_training: True})
- loop.add_phase(
- 'eval', graph.done, graph.score, graph.summary, eval_steps,
- report_every=eval_steps,
- log_every=eval_steps // 2,
- checkpoint_every=10 * eval_steps,
- feed={graph.is_training: False})
+ loop = tools.Loop(logdir, graph.step, graph.should_log, graph.do_report, graph.force_reset)
+ loop.add_phase('train',
+ graph.done,
+ graph.score,
+ graph.summary,
+ train_steps,
+ report_every=None,
+ log_every=train_steps // 2,
+ checkpoint_every=None,
+ feed={graph.is_training: True})
+ loop.add_phase('eval',
+ graph.done,
+ graph.score,
+ graph.summary,
+ eval_steps,
+ report_every=eval_steps,
+ log_every=eval_steps // 2,
+ checkpoint_every=10 * eval_steps,
+ feed={graph.is_training: False})
return loop
@@ -101,25 +104,19 @@ def train(config, env_processes):
"""
tf.reset_default_graph()
with config.unlocked:
- config.network = functools.partial(
- utility.define_network, config.network, config)
+ config.network = functools.partial(utility.define_network, config.network, config)
config.policy_optimizer = getattr(tf.train, config.policy_optimizer)
config.value_optimizer = getattr(tf.train, config.value_optimizer)
if config.update_every % config.num_agents:
tf.logging.warn('Number of agents should divide episodes per update.')
with tf.device('/cpu:0'):
- batch_env = utility.define_batch_env(
- lambda: _create_environment(config),
- config.num_agents, env_processes)
- graph = utility.define_simulation_graph(
- batch_env, config.algorithm, config)
- loop = _define_loop(
- graph, config.logdir,
- config.update_every * config.max_length,
- config.eval_episodes * config.max_length)
- total_steps = int(
- config.steps / config.update_every *
- (config.update_every + config.eval_episodes))
+ batch_env = utility.define_batch_env(lambda: _create_environment(config), config.num_agents,
+ env_processes)
+ graph = utility.define_simulation_graph(batch_env, config.algorithm, config)
+ loop = _define_loop(graph, config.logdir, config.update_every * config.max_length,
+ config.eval_episodes * config.max_length)
+ total_steps = int(config.steps / config.update_every *
+ (config.update_every + config.eval_episodes))
# Exclude episode related variables since the Python state of environments is
# not checkpointed and thus new episodes start after resuming.
saver = utility.define_saver(exclude=(r'.*_temporary/.*',))
@@ -137,8 +134,8 @@ def main(_):
utility.set_up_logging()
if not FLAGS.config:
raise KeyError('You must specify a configuration.')
- logdir = FLAGS.logdir and os.path.expanduser(os.path.join(
- FLAGS.logdir, '{}-{}'.format(FLAGS.timestamp, FLAGS.config)))
+ logdir = FLAGS.logdir and os.path.expanduser(
+ os.path.join(FLAGS.logdir, '{}-{}'.format(FLAGS.timestamp, FLAGS.config)))
try:
config = utility.load_config(logdir)
except IOError:
@@ -150,16 +147,11 @@ def main(_):
if __name__ == '__main__':
FLAGS = tf.app.flags.FLAGS
- tf.app.flags.DEFINE_string(
- 'logdir', None,
- 'Base directory to store logs.')
- tf.app.flags.DEFINE_string(
- 'timestamp', datetime.datetime.now().strftime('%Y%m%dT%H%M%S'),
- 'Sub directory to store logs.')
- tf.app.flags.DEFINE_string(
- 'config', None,
- 'Configuration to execute.')
- tf.app.flags.DEFINE_boolean(
- 'env_processes', True,
- 'Step environments in separate processes to circumvent the GIL.')
+ tf.app.flags.DEFINE_string('logdir', None, 'Base directory to store logs.')
+ tf.app.flags.DEFINE_string('timestamp',
+ datetime.datetime.now().strftime('%Y%m%dT%H%M%S'),
+ 'Sub directory to store logs.')
+ tf.app.flags.DEFINE_string('config', None, 'Configuration to execute.')
+ tf.app.flags.DEFINE_boolean('env_processes', True,
+ 'Step environments in separate processes to circumvent the GIL.')
tf.app.run()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train_ppo_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train_ppo_test.py
index df5095825..930143c39 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train_ppo_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/train_ppo_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for the PPO algorithm usage example."""
from __future__ import absolute_import
@@ -29,7 +28,6 @@ from google3.robotics.reinforcement_learning.agents.scripts import configs
from google3.robotics.reinforcement_learning.agents.scripts import networks
from google3.robotics.reinforcement_learning.agents.scripts import train
-
FLAGS = tf.app.flags.FLAGS
@@ -65,9 +63,11 @@ class PPOTest(tf.test.TestCase):
for network, observ_shape in itertools.product(nets, observ_shapes):
config = self._define_config()
with config.unlocked:
- config.env = functools.partial(
- tools.MockEnvironment, observ_shape, action_shape=(3,),
- min_duration=15, max_duration=15)
+ config.env = functools.partial(tools.MockEnvironment,
+ observ_shape,
+ action_shape=(3,),
+ min_duration=15,
+ max_duration=15)
config.max_length = 20
config.steps = 100
config.network = network
@@ -77,9 +77,11 @@ class PPOTest(tf.test.TestCase):
def test_no_crash_variable_duration(self):
config = self._define_config()
with config.unlocked:
- config.env = functools.partial(
- tools.MockEnvironment, observ_shape=(2, 3), action_shape=(3,),
- min_duration=5, max_duration=25)
+ config.env = functools.partial(tools.MockEnvironment,
+ observ_shape=(2, 3),
+ action_shape=(3,),
+ min_duration=5,
+ max_duration=25)
config.max_length = 25
config.steps = 200
config.network = networks.RecurrentGaussianPolicy
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/utility.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/utility.py
index 1342977c7..22bc50126 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/utility.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/utility.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Utilities for using reinforcement learning algorithms."""
from __future__ import absolute_import
@@ -46,8 +45,7 @@ def define_simulation_graph(batch_env, algo_cls, config):
do_report = tf.placeholder(tf.bool, name='do_report')
force_reset = tf.placeholder(tf.bool, name='force_reset')
algo = algo_cls(batch_env, step, is_training, should_log, config)
- done, score, summary = tools.simulate(
- batch_env, algo, should_log, force_reset)
+ done, score, summary = tools.simulate(batch_env, algo, should_log, force_reset)
message = 'Graph contains {} trainable variables.'
tf.logging.info(message.format(tools.count_weights()))
# pylint: enable=unused-variable
@@ -67,9 +65,7 @@ def define_batch_env(constructor, num_agents, env_processes):
"""
with tf.variable_scope('environments'):
if env_processes:
- envs = [
- tools.wrappers.ExternalProcess(constructor)
- for _ in range(num_agents)]
+ envs = [tools.wrappers.ExternalProcess(constructor) for _ in range(num_agents)]
else:
envs = [constructor() for _ in range(num_agents)]
batch_env = tools.BatchEnv(envs, blocking=not env_processes)
@@ -108,15 +104,14 @@ def define_network(constructor, config, action_size):
Returns:
Created recurrent cell object.
"""
- mean_weights_initializer = (
- tf.contrib.layers.variance_scaling_initializer(
- factor=config.init_mean_factor))
- logstd_initializer = tf.random_normal_initializer(
- config.init_logstd, 1e-10)
- network = constructor(
- config.policy_layers, config.value_layers, action_size,
- mean_weights_initializer=mean_weights_initializer,
- logstd_initializer=logstd_initializer)
+ mean_weights_initializer = (tf.contrib.layers.variance_scaling_initializer(
+ factor=config.init_mean_factor))
+ logstd_initializer = tf.random_normal_initializer(config.init_logstd, 1e-10)
+ network = constructor(config.policy_layers,
+ config.value_layers,
+ action_size,
+ mean_weights_initializer=mean_weights_initializer,
+ logstd_initializer=logstd_initializer)
return network
@@ -134,9 +129,7 @@ def initialize_variables(sess, saver, logdir, checkpoint=None, resume=None):
ValueError: If resume expected but no log directory specified.
RuntimeError: If no resume expected but a checkpoint was found.
"""
- sess.run(tf.group(
- tf.local_variables_initializer(),
- tf.global_variables_initializer()))
+ sess.run(tf.group(tf.local_variables_initializer(), tf.global_variables_initializer()))
if resume and not (logdir or checkpoint):
raise ValueError('Need to specify logdir to resume a checkpoint.')
if logdir:
@@ -175,9 +168,8 @@ def save_config(config, logdir=None):
with tf.gfile.GFile(config_path, 'w') as file_:
yaml.dump(config, file_, default_flow_style=False)
else:
- message = (
- 'Start a new run without storing summaries and checkpoints since no '
- 'logging directory was specified.')
+ message = ('Start a new run without storing summaries and checkpoints since no '
+ 'logging directory was specified.')
tf.logging.info(message)
return config
@@ -196,9 +188,8 @@ def load_config(logdir):
"""
config_path = logdir and os.path.join(logdir, 'config.yaml')
if not config_path or not tf.gfile.Exists(config_path):
- message = (
- 'Cannot resume an existing run since the logging directory does not '
- 'contain a configuration file.')
+ message = ('Cannot resume an existing run since the logging directory does not '
+ 'contain a configuration file.')
raise IOError(message)
with tf.gfile.FastGFile(config_path, 'r') as file_:
config = yaml.load(file_)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/visualize.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/visualize.py
index 3a5f62e4b..cc68c0d42 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/visualize.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/scripts/visualize.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
r"""Script to render videos of the Proximal Policy Gradient algorithm.
Command line:
@@ -54,6 +53,8 @@ def _create_environment(config, outdir):
setattr(env, 'spec', getattr(env, 'spec', None))
if config.max_length:
env = tools.wrappers.LimitDuration(env, config.max_length)
+
+
# env = gym.wrappers.Monitor(
# env, outdir, lambda unused_episode_number: True)
env = tools.wrappers.RangeNormalize(env)
@@ -72,20 +73,20 @@ def _define_loop(graph, eval_steps):
Returns:
Loop object.
"""
- loop = tools.Loop(
- None, graph.step, graph.should_log, graph.do_report, graph.force_reset)
- loop.add_phase(
- 'eval', graph.done, graph.score, graph.summary, eval_steps,
- report_every=eval_steps,
- log_every=None,
- checkpoint_every=None,
- feed={graph.is_training: False})
+ loop = tools.Loop(None, graph.step, graph.should_log, graph.do_report, graph.force_reset)
+ loop.add_phase('eval',
+ graph.done,
+ graph.score,
+ graph.summary,
+ eval_steps,
+ report_every=eval_steps,
+ log_every=None,
+ checkpoint_every=None,
+ feed={graph.is_training: False})
return loop
-def visualize(
- logdir, outdir, num_agents, num_episodes, checkpoint=None,
- env_processes=True):
+def visualize(logdir, outdir, num_agents, num_episodes, checkpoint=None, env_processes=True):
"""Recover checkpoint and render videos from it.
Args:
@@ -98,25 +99,20 @@ def visualize(
"""
config = utility.load_config(logdir)
with config.unlocked:
- config.network = functools.partial(
- utility.define_network, config.network, config)
+ config.network = functools.partial(utility.define_network, config.network, config)
config.policy_optimizer = getattr(tf.train, config.policy_optimizer)
config.value_optimizer = getattr(tf.train, config.value_optimizer)
with tf.device('/cpu:0'):
- batch_env = utility.define_batch_env(
- lambda: _create_environment(config, outdir),
- num_agents, env_processes)
- graph = utility.define_simulation_graph(
- batch_env, config.algorithm, config)
+ batch_env = utility.define_batch_env(lambda: _create_environment(config, outdir), num_agents,
+ env_processes)
+ graph = utility.define_simulation_graph(batch_env, config.algorithm, config)
total_steps = num_episodes * config.max_length
loop = _define_loop(graph, total_steps)
- saver = utility.define_saver(
- exclude=(r'.*_temporary/.*', r'global_step'))
+ saver = utility.define_saver(exclude=(r'.*_temporary/.*', r'global_step'))
sess_config = tf.ConfigProto(allow_soft_placement=True)
sess_config.gpu_options.allow_growth = True
with tf.Session(config=sess_config) as sess:
- utility.initialize_variables(
- sess, saver, config.logdir, checkpoint, resume=True)
+ utility.initialize_variables(sess, saver, config.logdir, checkpoint, resume=True)
for unused_score in loop.run(sess, saver, total_steps):
pass
batch_env.close()
@@ -129,29 +125,18 @@ def main(_):
raise KeyError('You must specify logging and outdirs directories.')
FLAGS.logdir = os.path.expanduser(FLAGS.logdir)
FLAGS.outdir = os.path.expanduser(FLAGS.outdir)
- visualize(
- FLAGS.logdir, FLAGS.outdir, FLAGS.num_agents, FLAGS.num_episodes,
- FLAGS.checkpoint, FLAGS.env_processes)
+ visualize(FLAGS.logdir, FLAGS.outdir, FLAGS.num_agents, FLAGS.num_episodes, FLAGS.checkpoint,
+ FLAGS.env_processes)
if __name__ == '__main__':
FLAGS = tf.app.flags.FLAGS
- tf.app.flags.DEFINE_string(
- 'logdir', None,
- 'Directory to the checkpoint of a training run.')
- tf.app.flags.DEFINE_string(
- 'outdir', None,
- 'Local directory for storing the monitoring outdir.')
- tf.app.flags.DEFINE_string(
- 'checkpoint', None,
- 'Checkpoint name to load; defaults to most recent.')
- tf.app.flags.DEFINE_integer(
- 'num_agents', 1,
- 'How many environments to step in parallel.')
- tf.app.flags.DEFINE_integer(
- 'num_episodes', 5,
- 'Minimum number of episodes to render.')
- tf.app.flags.DEFINE_boolean(
- 'env_processes', True,
- 'Step environments in separate processes to circumvent the GIL.')
+ tf.app.flags.DEFINE_string('logdir', None, 'Directory to the checkpoint of a training run.')
+ tf.app.flags.DEFINE_string('outdir', None, 'Local directory for storing the monitoring outdir.')
+ tf.app.flags.DEFINE_string('checkpoint', None,
+ 'Checkpoint name to load; defaults to most recent.')
+ tf.app.flags.DEFINE_integer('num_agents', 1, 'How many environments to step in parallel.')
+ tf.app.flags.DEFINE_integer('num_episodes', 5, 'Minimum number of episodes to render.')
+ tf.app.flags.DEFINE_boolean('env_processes', True,
+ 'Step environments in separate processes to circumvent the GIL.')
tf.app.run()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/__init__.py
index d624c8243..f2f435c3e 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/__init__.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tools for reinforcement learning."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict.py
index 1707486d8..fbb08290f 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Wrap a dictionary to access keys as attributes."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict_test.py
index f5b2e3ce4..7ab1f415f 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/attr_dict_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for the attribute dictionary."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/batch_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/batch_env.py
index d103d0133..a2971bc4d 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/batch_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/batch_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Combine multiple environments to step them in batch."""
from __future__ import absolute_import
@@ -84,13 +83,9 @@ class BatchEnv(object):
message = 'Invalid action at index {}: {}'
raise ValueError(message.format(index, action))
if self._blocking:
- transitions = [
- env.step(action)
- for env, action in zip(self._envs, actions)]
+ transitions = [env.step(action) for env, action in zip(self._envs, actions)]
else:
- transitions = [
- env.step(action, blocking=False)
- for env, action in zip(self._envs, actions)]
+ transitions = [env.step(action, blocking=False) for env, action in zip(self._envs, actions)]
transitions = [transition() for transition in transitions]
observs, rewards, dones, infos = zip(*transitions)
observ = np.stack(observs)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights.py
index dd0d870f6..279df82a0 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Count learnable parameters."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights_test.py
index 930aa8623..a42c60f57 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/count_weights_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for the weight counting utility."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_batch_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_batch_env.py
index 2765d4821..6cd0a2fdf 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_batch_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_batch_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Batch of environments inside the TensorFlow graph."""
from __future__ import absolute_import
@@ -42,18 +41,18 @@ class InGraphBatchEnv(object):
action_shape = self._parse_shape(self._batch_env.action_space)
action_dtype = self._parse_dtype(self._batch_env.action_space)
with tf.variable_scope('env_temporary'):
- self._observ = tf.Variable(
- tf.zeros((len(self._batch_env),) + observ_shape, observ_dtype),
- name='observ', trainable=False)
- self._action = tf.Variable(
- tf.zeros((len(self._batch_env),) + action_shape, action_dtype),
- name='action', trainable=False)
- self._reward = tf.Variable(
- tf.zeros((len(self._batch_env),), tf.float32),
- name='reward', trainable=False)
- self._done = tf.Variable(
- tf.cast(tf.ones((len(self._batch_env),)), tf.bool),
- name='done', trainable=False)
+ self._observ = tf.Variable(tf.zeros((len(self._batch_env),) + observ_shape, observ_dtype),
+ name='observ',
+ trainable=False)
+ self._action = tf.Variable(tf.zeros((len(self._batch_env),) + action_shape, action_dtype),
+ name='action',
+ trainable=False)
+ self._reward = tf.Variable(tf.zeros((len(self._batch_env),), tf.float32),
+ name='reward',
+ trainable=False)
+ self._done = tf.Variable(tf.cast(tf.ones((len(self._batch_env),)), tf.bool),
+ name='done',
+ trainable=False)
def __getattr__(self, name):
"""Forward unimplemented attributes to one of the original environments.
@@ -89,16 +88,13 @@ class InGraphBatchEnv(object):
if action.dtype in (tf.float16, tf.float32, tf.float64):
action = tf.check_numerics(action, 'action')
observ_dtype = self._parse_dtype(self._batch_env.observation_space)
- observ, reward, done = tf.py_func(
- lambda a: self._batch_env.step(a)[:3], [action],
- [observ_dtype, tf.float32, tf.bool], name='step')
+ observ, reward, done = tf.py_func(lambda a: self._batch_env.step(a)[:3], [action],
+ [observ_dtype, tf.float32, tf.bool],
+ name='step')
observ = tf.check_numerics(observ, 'observ')
reward = tf.check_numerics(reward, 'reward')
- return tf.group(
- self._observ.assign(observ),
- self._action.assign(action),
- self._reward.assign(reward),
- self._done.assign(done))
+ return tf.group(self._observ.assign(observ), self._action.assign(action),
+ self._reward.assign(reward), self._done.assign(done))
def reset(self, indices=None):
"""Reset the batch of environments.
@@ -112,15 +108,15 @@ class InGraphBatchEnv(object):
if indices is None:
indices = tf.range(len(self._batch_env))
observ_dtype = self._parse_dtype(self._batch_env.observation_space)
- observ = tf.py_func(
- self._batch_env.reset, [indices], observ_dtype, name='reset')
+ observ = tf.py_func(self._batch_env.reset, [indices], observ_dtype, name='reset')
observ = tf.check_numerics(observ, 'observ')
reward = tf.zeros_like(indices, tf.float32)
done = tf.zeros_like(indices, tf.bool)
with tf.control_dependencies([
tf.scatter_update(self._observ, indices, observ),
tf.scatter_update(self._reward, indices, reward),
- tf.scatter_update(self._done, indices, done)]):
+ tf.scatter_update(self._done, indices, done)
+ ]):
return tf.identity(observ)
@property
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_env.py
index 33ff31d07..6a71f4516 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/in_graph_env.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Put an OpenAI Gym environment into the TensorFlow graph."""
from __future__ import absolute_import
@@ -42,16 +41,15 @@ class InGraphEnv(object):
action_shape = self._parse_shape(self._env.action_space)
action_dtype = self._parse_dtype(self._env.action_space)
with tf.name_scope('environment'):
- self._observ = tf.Variable(
- tf.zeros(observ_shape, observ_dtype), name='observ', trainable=False)
- self._action = tf.Variable(
- tf.zeros(action_shape, action_dtype), name='action', trainable=False)
- self._reward = tf.Variable(
- 0.0, dtype=tf.float32, name='reward', trainable=False)
- self._done = tf.Variable(
- True, dtype=tf.bool, name='done', trainable=False)
- self._step = tf.Variable(
- 0, dtype=tf.int32, name='step', trainable=False)
+ self._observ = tf.Variable(tf.zeros(observ_shape, observ_dtype),
+ name='observ',
+ trainable=False)
+ self._action = tf.Variable(tf.zeros(action_shape, action_dtype),
+ name='action',
+ trainable=False)
+ self._reward = tf.Variable(0.0, dtype=tf.float32, name='reward', trainable=False)
+ self._done = tf.Variable(True, dtype=tf.bool, name='done', trainable=False)
+ self._step = tf.Variable(0, dtype=tf.int32, name='step', trainable=False)
def __getattr__(self, name):
"""Forward unimplemented attributes to the original environment.
@@ -79,17 +77,14 @@ class InGraphEnv(object):
if action.dtype in (tf.float16, tf.float32, tf.float64):
action = tf.check_numerics(action, 'action')
observ_dtype = self._parse_dtype(self._env.observation_space)
- observ, reward, done = tf.py_func(
- lambda a: self._env.step(a)[:3], [action],
- [observ_dtype, tf.float32, tf.bool], name='step')
+ observ, reward, done = tf.py_func(lambda a: self._env.step(a)[:3], [action],
+ [observ_dtype, tf.float32, tf.bool],
+ name='step')
observ = tf.check_numerics(observ, 'observ')
reward = tf.check_numerics(reward, 'reward')
- return tf.group(
- self._observ.assign(observ),
- self._action.assign(action),
- self._reward.assign(reward),
- self._done.assign(done),
- self._step.assign_add(1))
+ return tf.group(self._observ.assign(observ), self._action.assign(action),
+ self._reward.assign(reward), self._done.assign(done),
+ self._step.assign_add(1))
def reset(self):
"""Reset the environment.
@@ -100,10 +95,10 @@ class InGraphEnv(object):
observ_dtype = self._parse_dtype(self._env.observation_space)
observ = tf.py_func(self._env.reset, [], observ_dtype, name='reset')
observ = tf.check_numerics(observ, 'observ')
- with tf.control_dependencies([
- self._observ.assign(observ),
- self._reward.assign(0),
- self._done.assign(False)]):
+ with tf.control_dependencies(
+ [self._observ.assign(observ),
+ self._reward.assign(0),
+ self._done.assign(False)]):
return tf.identity(observ)
@property
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop.py
index 36f1e7faa..78a3cfd29 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Execute operations in a loop and coordinate logging and checkpoints."""
from __future__ import absolute_import
@@ -25,10 +24,8 @@ import tensorflow as tf
from pybullet_envs.minitaur.agents.tools import streaming_mean
-
_Phase = collections.namedtuple(
- 'Phase',
- 'name, writer, op, batch, steps, feed, report_every, log_every,'
+ 'Phase', 'name, writer, op, batch, steps, feed, report_every, log_every,'
'checkpoint_every')
@@ -56,16 +53,22 @@ class Loop(object):
reset: Tensor indicating to the model to start a new computation.
"""
self._logdir = logdir
- self._step = (
- tf.Variable(0, False, name='global_step') if step is None else step)
+ self._step = (tf.Variable(0, False, name='global_step') if step is None else step)
self._log = tf.placeholder(tf.bool) if log is None else log
self._report = tf.placeholder(tf.bool) if report is None else report
self._reset = tf.placeholder(tf.bool) if reset is None else reset
self._phases = []
- def add_phase(
- self, name, done, score, summary, steps,
- report_every=None, log_every=None, checkpoint_every=None, feed=None):
+ def add_phase(self,
+ name,
+ done,
+ score,
+ summary,
+ steps,
+ report_every=None,
+ log_every=None,
+ checkpoint_every=None,
+ feed=None):
"""Add a phase to the loop protocol.
If the model breaks long computation into multiple steps, the done tensor
@@ -97,13 +100,12 @@ class Loop(object):
if done.shape.ndims is None or score.shape.ndims is None:
raise ValueError("Rank of 'done' and 'score' tensors must be known.")
writer = self._logdir and tf.summary.FileWriter(
- os.path.join(self._logdir, name), tf.get_default_graph(),
- flush_secs=60)
+ os.path.join(self._logdir, name), tf.get_default_graph(), flush_secs=60)
op = self._define_step(done, score, summary)
batch = 1 if score.shape.ndims == 0 else score.shape[0].value
- self._phases.append(_Phase(
- name, writer, op, batch, int(steps), feed, report_every,
- log_every, checkpoint_every))
+ self._phases.append(
+ _Phase(name, writer, op, batch, int(steps), feed, report_every, log_every,
+ checkpoint_every))
def run(self, sess, saver, max_step=None):
"""Run the loop schedule for a specified number of steps.
@@ -133,13 +135,11 @@ class Loop(object):
tf.logging.info(message.format(phase.name, phase_step, global_step))
# Populate book keeping tensors.
phase.feed[self._reset] = (steps_in < steps_made)
- phase.feed[self._log] = (
- phase.writer and
- self._is_every_steps(phase_step, phase.batch, phase.log_every))
- phase.feed[self._report] = (
- self._is_every_steps(phase_step, phase.batch, phase.report_every))
- summary, mean_score, global_step, steps_made = sess.run(
- phase.op, phase.feed)
+ phase.feed[self._log] = (phase.writer and
+ self._is_every_steps(phase_step, phase.batch, phase.log_every))
+ phase.feed[self._report] = (self._is_every_steps(phase_step, phase.batch,
+ phase.report_every))
+ summary, mean_score, global_step, steps_made = sess.run(phase.op, phase.feed)
if self._is_every_steps(phase_step, phase.batch, phase.checkpoint_every):
self._store_checkpoint(sess, saver, global_step)
if self._is_every_steps(phase_step, phase.batch, phase.report_every):
@@ -207,8 +207,7 @@ class Loop(object):
score_mean = streaming_mean.StreamingMean((), tf.float32)
with tf.control_dependencies([done, score, summary]):
done_score = tf.gather(score, tf.where(done)[:, 0])
- submit_score = tf.cond(
- tf.reduce_any(done), lambda: score_mean.submit(done_score), tf.no_op)
+ submit_score = tf.cond(tf.reduce_any(done), lambda: score_mean.submit(done_score), tf.no_op)
with tf.control_dependencies([submit_score]):
mean_score = tf.cond(self._report, score_mean.clear, float)
steps_made = tf.shape(score)[0]
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop_test.py
index d4d03c513..3245d26b7 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/loop_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for the training loop."""
from __future__ import absolute_import
@@ -28,8 +27,7 @@ class LoopTest(tf.test.TestCase):
def test_report_every_step(self):
step = tf.Variable(0, False, dtype=tf.int32, name='step')
loop = tools.Loop(None, step)
- loop.add_phase(
- 'phase_1', done=True, score=0, summary='', steps=1, report_every=3)
+ loop.add_phase('phase_1', done=True, score=0, summary='', steps=1, report_every=3)
# Step: 0 1 2 3 4 5 6 7 8
# Report: x x x
with self.test_session() as sess:
@@ -45,15 +43,33 @@ class LoopTest(tf.test.TestCase):
def test_phases_feed(self):
score = tf.placeholder(tf.float32, [])
loop = tools.Loop(None)
- loop.add_phase(
- 'phase_1', done=True, score=score, summary='', steps=1, report_every=1,
- log_every=None, checkpoint_every=None, feed={score: 1})
- loop.add_phase(
- 'phase_2', done=True, score=score, summary='', steps=3, report_every=1,
- log_every=None, checkpoint_every=None, feed={score: 2})
- loop.add_phase(
- 'phase_3', done=True, score=score, summary='', steps=2, report_every=1,
- log_every=None, checkpoint_every=None, feed={score: 3})
+ loop.add_phase('phase_1',
+ done=True,
+ score=score,
+ summary='',
+ steps=1,
+ report_every=1,
+ log_every=None,
+ checkpoint_every=None,
+ feed={score: 1})
+ loop.add_phase('phase_2',
+ done=True,
+ score=score,
+ summary='',
+ steps=3,
+ report_every=1,
+ log_every=None,
+ checkpoint_every=None,
+ feed={score: 2})
+ loop.add_phase('phase_3',
+ done=True,
+ score=score,
+ summary='',
+ steps=2,
+ report_every=1,
+ log_every=None,
+ checkpoint_every=None,
+ feed={score: 3})
with self.test_session() as sess:
sess.run(tf.global_variables_initializer())
scores = list(loop.run(sess, saver=None, max_step=15))
@@ -61,10 +77,8 @@ class LoopTest(tf.test.TestCase):
def test_average_score_over_phases(self):
loop = tools.Loop(None)
- loop.add_phase(
- 'phase_1', done=True, score=1, summary='', steps=1, report_every=2)
- loop.add_phase(
- 'phase_2', done=True, score=2, summary='', steps=2, report_every=5)
+ loop.add_phase('phase_1', done=True, score=1, summary='', steps=1, report_every=2)
+ loop.add_phase('phase_2', done=True, score=2, summary='', steps=2, report_every=5)
# Score: 1 2 2 1 2 2 1 2 2 1 2 2 1 2 2 1 2
# Report 1: x x x
# Report 2: x x
@@ -78,8 +92,7 @@ class LoopTest(tf.test.TestCase):
done = tf.equal((step + 1) % 2, 0)
score = tf.cast(step, tf.float32)
loop = tools.Loop(None, step)
- loop.add_phase(
- 'phase_1', done, score, summary='', steps=1, report_every=3)
+ loop.add_phase('phase_1', done, score, summary='', steps=1, report_every=3)
# Score: 0 1 2 3 4 5 6 7 8
# Done: x x x x
# Report: x x x
@@ -91,10 +104,9 @@ class LoopTest(tf.test.TestCase):
def test_not_done_batch(self):
step = tf.Variable(0, False, dtype=tf.int32, name='step')
done = tf.equal([step % 3, step % 4], 0)
- score = tf.cast([step, step ** 2], tf.float32)
+ score = tf.cast([step, step**2], tf.float32)
loop = tools.Loop(None, step)
- loop.add_phase(
- 'phase_1', done, score, summary='', steps=1, report_every=8)
+ loop.add_phase('phase_1', done, score, summary='', steps=1, report_every=8)
# Step: 0 2 4 6
# Score 1: 0 2 4 6
# Done 1: x x
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_algorithm.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_algorithm.py
index 1bc58a906..e321afae3 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_algorithm.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_algorithm.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Mock algorithm for testing reinforcement learning code."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_environment.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_environment.py
index 248f515b1..9db14d56c 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_environment.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/mock_environment.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Mock environment for testing reinforcement learning code."""
from __future__ import absolute_import
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate.py
index 45b36d6b0..e794f6a9d 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""In-graph simulation step of a vecrotized algorithm with environments."""
from __future__ import absolute_import
@@ -55,7 +54,8 @@ def simulate(batch_env, algo, log=True, reset=False):
reset_ops = [
batch_env.reset(agent_indices),
tf.scatter_update(score, agent_indices, zero_scores),
- tf.scatter_update(length, agent_indices, zero_durations)]
+ tf.scatter_update(length, agent_indices, zero_durations)
+ ]
with tf.control_dependencies(reset_ops):
return algo.begin_episode(agent_indices)
@@ -76,9 +76,8 @@ def simulate(batch_env, algo, log=True, reset=False):
add_score = score.assign_add(batch_env.reward)
inc_length = length.assign_add(tf.ones(len(batch_env), tf.int32))
with tf.control_dependencies([add_score, inc_length]):
- experience_summary = algo.experience(
- prevob, batch_env.action, batch_env.reward, batch_env.done,
- batch_env.observ)
+ experience_summary = algo.experience(prevob, batch_env.action, batch_env.reward,
+ batch_env.done, batch_env.observ)
return tf.summary.merge([step_summary, experience_summary])
def _define_end_episode(agent_indices):
@@ -94,8 +93,7 @@ def simulate(batch_env, algo, log=True, reset=False):
"""
assert agent_indices.shape.ndims == 1
submit_score = mean_score.submit(tf.gather(score, agent_indices))
- submit_length = mean_length.submit(
- tf.cast(tf.gather(length, agent_indices), tf.float32))
+ submit_length = mean_length.submit(tf.cast(tf.gather(length, agent_indices), tf.float32))
with tf.control_dependencies([submit_score, submit_length]):
return algo.end_episode(agent_indices)
@@ -105,41 +103,34 @@ def simulate(batch_env, algo, log=True, reset=False):
Returns:
Summary string.
"""
- score_summary = tf.cond(
- tf.logical_and(log, tf.cast(mean_score.count, tf.bool)),
- lambda: tf.summary.scalar('mean_score', mean_score.clear()), str)
- length_summary = tf.cond(
- tf.logical_and(log, tf.cast(mean_length.count, tf.bool)),
- lambda: tf.summary.scalar('mean_length', mean_length.clear()), str)
+ score_summary = tf.cond(tf.logical_and(log, tf.cast(
+ mean_score.count, tf.bool)), lambda: tf.summary.scalar('mean_score', mean_score.clear()),
+ str)
+ length_summary = tf.cond(tf.logical_and(
+ log, tf.cast(mean_length.count,
+ tf.bool)), lambda: tf.summary.scalar('mean_length', mean_length.clear()), str)
return tf.summary.merge([score_summary, length_summary])
with tf.name_scope('simulate'):
log = tf.convert_to_tensor(log)
reset = tf.convert_to_tensor(reset)
with tf.variable_scope('simulate_temporary'):
- score = tf.Variable(
- tf.zeros(len(batch_env), dtype=tf.float32), False, name='score')
- length = tf.Variable(
- tf.zeros(len(batch_env), dtype=tf.int32), False, name='length')
+ score = tf.Variable(tf.zeros(len(batch_env), dtype=tf.float32), False, name='score')
+ length = tf.Variable(tf.zeros(len(batch_env), dtype=tf.int32), False, name='length')
mean_score = streaming_mean.StreamingMean((), tf.float32)
mean_length = streaming_mean.StreamingMean((), tf.float32)
- agent_indices = tf.cond(
- reset,
- lambda: tf.range(len(batch_env)),
- lambda: tf.cast(tf.where(batch_env.done)[:, 0], tf.int32))
- begin_episode = tf.cond(
- tf.cast(tf.shape(agent_indices)[0], tf.bool),
- lambda: _define_begin_episode(agent_indices), str)
+ agent_indices = tf.cond(reset, lambda: tf.range(len(batch_env)), lambda: tf.cast(
+ tf.where(batch_env.done)[:, 0], tf.int32))
+ begin_episode = tf.cond(tf.cast(tf.shape(agent_indices)[0],
+ tf.bool), lambda: _define_begin_episode(agent_indices), str)
with tf.control_dependencies([begin_episode]):
step = _define_step()
with tf.control_dependencies([step]):
agent_indices = tf.cast(tf.where(batch_env.done)[:, 0], tf.int32)
- end_episode = tf.cond(
- tf.cast(tf.shape(agent_indices)[0], tf.bool),
- lambda: _define_end_episode(agent_indices), str)
+ end_episode = tf.cond(tf.cast(tf.shape(agent_indices)[0],
+ tf.bool), lambda: _define_end_episode(agent_indices), str)
with tf.control_dependencies([end_episode]):
- summary = tf.summary.merge([
- _define_summaries(), begin_episode, step, end_episode])
+ summary = tf.summary.merge([_define_summaries(), begin_episode, step, end_episode])
with tf.control_dependencies([summary]):
done, score = tf.identity(batch_env.done), tf.identity(score)
return done, score, summary
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate_test.py
index 590010fec..42b45bc7f 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/simulate_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for the simulation operation."""
from __future__ import absolute_import
@@ -84,9 +83,10 @@ class SimulateTest(tf.test.TestCase):
def _create_test_batch_env(self, durations):
envs = []
for duration in durations:
- env = tools.MockEnvironment(
- observ_shape=(2, 3), action_shape=(3,),
- min_duration=duration, max_duration=duration)
+ env = tools.MockEnvironment(observ_shape=(2, 3),
+ action_shape=(3,),
+ min_duration=duration,
+ max_duration=duration)
env = tools.wrappers.ConvertTo32Bit(env)
envs.append(env)
batch_env = tools.BatchEnv(envs, blocking=True)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/streaming_mean.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/streaming_mean.py
index 3f620fe37..5992eaa6b 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/streaming_mean.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/streaming_mean.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Compute a streaming estimation of the mean of submitted tensors."""
from __future__ import absolute_import
@@ -53,9 +52,8 @@ class StreamingMean(object):
# Add a batch dimension if necessary.
if value.shape.ndims == self._sum.shape.ndims:
value = value[None, ...]
- return tf.group(
- self._sum.assign_add(tf.reduce_sum(value, 0)),
- self._count.assign_add(tf.shape(value)[0]))
+ return tf.group(self._sum.assign_add(tf.reduce_sum(value, 0)),
+ self._count.assign_add(tf.shape(value)[0]))
def clear(self):
"""Return the mean estimate and reset the streaming statistics."""
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers.py
index 5cac88fdf..2e33f3942 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Wrappers for OpenAI Gym environments."""
from __future__ import absolute_import
@@ -150,8 +149,7 @@ class FrameHistory(object):
return self._select_frames()
def _select_frames(self):
- indices = [
- (self._step - index) % self._capacity for index in self._past_indices]
+ indices = [(self._step - index) % self._capacity for index in self._past_indices]
observ = self._buffer[indices]
if self._flatten:
observ = np.reshape(observ, (-1,) + observ.shape[2:])
@@ -192,14 +190,14 @@ class RangeNormalize(object):
def __init__(self, env, observ=None, action=None):
self._env = env
- self._should_normalize_observ = (
- observ is not False and self._is_finite(self._env.observation_space))
+ self._should_normalize_observ = (observ is not False and
+ self._is_finite(self._env.observation_space))
if observ is True and not self._should_normalize_observ:
raise ValueError('Cannot normalize infinite observation range.')
if observ is None and not self._should_normalize_observ:
tf.logging.info('Not normalizing infinite observation range.')
- self._should_normalize_action = (
- action is not False and self._is_finite(self._env.action_space))
+ self._should_normalize_action = (action is not False and
+ self._is_finite(self._env.action_space))
if action is True and not self._should_normalize_action:
raise ValueError('Cannot normalize infinite action range.')
if action is None and not self._should_normalize_action:
@@ -327,8 +325,7 @@ class ExternalProcess(object):
action_space: The cached action space of the environment.
"""
self._conn, conn = multiprocessing.Pipe()
- self._process = multiprocessing.Process(
- target=self._worker, args=(constructor, conn))
+ self._process = multiprocessing.Process(target=self._worker, args=(constructor, conn))
atexit.register(self.close)
self._process.start()
self._observ_space = None
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers_test.py b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers_test.py
index dfc6fb263..fac8dd0d4 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers_test.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/agents/tools/wrappers_test.py
@@ -11,7 +11,6 @@
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
-
"""Tests for environment wrappers."""
from __future__ import absolute_import
@@ -28,18 +27,20 @@ from agents import tools
class ExternalProcessTest(tf.test.TestCase):
def test_close_no_hang_after_init(self):
- constructor = functools.partial(
- tools.MockEnvironment,
- observ_shape=(2, 3), action_shape=(2,),
- min_duration=2, max_duration=2)
+ constructor = functools.partial(tools.MockEnvironment,
+ observ_shape=(2, 3),
+ action_shape=(2,),
+ min_duration=2,
+ max_duration=2)
env = tools.wrappers.ExternalProcess(constructor)
env.close()
def test_close_no_hang_after_step(self):
- constructor = functools.partial(
- tools.MockEnvironment,
- observ_shape=(2, 3), action_shape=(2,),
- min_duration=5, max_duration=5)
+ constructor = functools.partial(tools.MockEnvironment,
+ observ_shape=(2, 3),
+ action_shape=(2,),
+ min_duration=5,
+ max_duration=5)
env = tools.wrappers.ExternalProcess(constructor)
env.reset()
env.step(env.action_space.sample())
@@ -53,8 +54,7 @@ class ExternalProcessTest(tf.test.TestCase):
env.step(env.action_space.sample())
def test_reraise_exception_in_step(self):
- constructor = functools.partial(
- MockEnvironmentCrashInStep, crash_at_step=3)
+ constructor = functools.partial(MockEnvironmentCrashInStep, crash_at_step=3)
env = tools.wrappers.ExternalProcess(constructor)
env.reset()
env.step(env.action_space.sample())
@@ -74,9 +74,10 @@ class MockEnvironmentCrashInStep(tools.MockEnvironment):
"""Raise an error after specified number of steps in an episode."""
def __init__(self, crash_at_step):
- super(MockEnvironmentCrashInStep, self).__init__(
- observ_shape=(2, 3), action_shape=(2,),
- min_duration=crash_at_step + 1, max_duration=crash_at_step + 1)
+ super(MockEnvironmentCrashInStep, self).__init__(observ_shape=(2, 3),
+ action_shape=(2,),
+ min_duration=crash_at_step + 1,
+ max_duration=crash_at_step + 1)
self._crash_at_step = crash_at_step
def step(self, *args, **kwargs):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/__init__.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/__init__.py
index 37def777d..72c619547 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/__init__.py
@@ -5,6 +5,3 @@ from pybullet_envs.minitaur.envs.minitaur_reactive_env import MinitaurReactiveEn
from pybullet_envs.minitaur.envs.minitaur_stand_gym_env import MinitaurStandGymEnv
from pybullet_envs.minitaur.envs.minitaur_trotting_env import MinitaurTrottingEnv
from pybullet_envs.minitaur.envs.minitaur_four_leg_stand_env import MinitaurFourLegStandEnv
-
-
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/bullet_client.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/bullet_client.py
index 8fc1fcd5c..54e0bd09e 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/bullet_client.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/bullet_client.py
@@ -42,9 +42,13 @@ class BulletClient(object):
attribute = getattr(pybullet, name)
if inspect.isbuiltin(attribute):
if name not in [
- "invertTransform", "multiplyTransforms", "getMatrixFromQuaternion",
- "getEulerFromQuaternion", "computeViewMatrixFromYawPitchRoll",
- "computeProjectionMatrixFOV", "getQuaternionFromEuler",
+ "invertTransform",
+ "multiplyTransforms",
+ "getMatrixFromQuaternion",
+ "getEulerFromQuaternion",
+ "computeViewMatrixFromYawPitchRoll",
+ "computeProjectionMatrixFOV",
+ "getQuaternionFromEuler",
]: # A temporary hack for now.
attribute = functools.partial(attribute, physicsClientId=self._client)
return attribute
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_alternating_legs_env_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_alternating_legs_env_randomizer.py
index a2d1645f4..9f868ba60 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_alternating_legs_env_randomizer.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_alternating_legs_env_randomizer.py
@@ -4,11 +4,11 @@ The randomization include swing_offset, extension_offset of all legs that mimics
bent legs, desired_pitch from user input, battery voltage and motor damping.
"""
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
parentdir = os.path.dirname(os.path.dirname(parentdir))
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import numpy as np
import tensorflow as tf
@@ -20,8 +20,7 @@ BATTERY_VOLTAGE_RANGE = (14.8, 16.8)
MOTOR_VISCOUS_DAMPING_RANGE = (0, 0.01)
-class MinitaurAlternatingLegsEnvRandomizer(
- env_randomizer_base.EnvRandomizerBase):
+class MinitaurAlternatingLegsEnvRandomizer(env_randomizer_base.EnvRandomizerBase):
"""A randomizer that changes the minitaur_gym_alternating_leg_env."""
def __init__(self,
@@ -34,23 +33,20 @@ class MinitaurAlternatingLegsEnvRandomizer(
self.perturb_desired_pitch_bound = perturb_desired_pitch_bound
def randomize_env(self, env):
- perturb_magnitude = np.random.uniform(
- low=-self.perturb_swing_bound,
- high=self.perturb_swing_bound,
- size=NUM_LEGS)
+ perturb_magnitude = np.random.uniform(low=-self.perturb_swing_bound,
+ high=self.perturb_swing_bound,
+ size=NUM_LEGS)
env.set_swing_offset(perturb_magnitude)
tf.logging.info("swing_offset: {}".format(perturb_magnitude))
- perturb_magnitude = np.random.uniform(
- low=-self.perturb_extension_bound,
- high=self.perturb_extension_bound,
- size=NUM_LEGS)
+ perturb_magnitude = np.random.uniform(low=-self.perturb_extension_bound,
+ high=self.perturb_extension_bound,
+ size=NUM_LEGS)
env.set_extension_offset(perturb_magnitude)
tf.logging.info("extension_offset: {}".format(perturb_magnitude))
- perturb_magnitude = np.random.uniform(
- low=-self.perturb_desired_pitch_bound,
- high=self.perturb_desired_pitch_bound)
+ perturb_magnitude = np.random.uniform(low=-self.perturb_desired_pitch_bound,
+ high=self.perturb_desired_pitch_bound)
env.set_desired_pitch(perturb_magnitude)
tf.logging.info("desired_pitch: {}".format(perturb_magnitude))
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py
index befdf7ea1..0fbfef36d 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer.py
@@ -1,11 +1,11 @@
"""Randomize the minitaur_gym_env when reset() is called."""
import random
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
parentdir = os.path.dirname(os.path.dirname(parentdir))
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import numpy as np
from pybullet_envs.minitaur.envs import env_randomizer_base
@@ -52,24 +52,20 @@ class MinitaurEnvRandomizer(env_randomizer_base.EnvRandomizerBase):
minitaur.SetBaseMasses(randomized_base_mass)
leg_masses = minitaur.GetLegMassesFromURDF()
- leg_masses_lower_bound = np.array(leg_masses) * (
- 1.0 + self._minitaur_leg_mass_err_range[0])
- leg_masses_upper_bound = np.array(leg_masses) * (
- 1.0 + self._minitaur_leg_mass_err_range[1])
+ leg_masses_lower_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[0])
+ leg_masses_upper_bound = np.array(leg_masses) * (1.0 + self._minitaur_leg_mass_err_range[1])
randomized_leg_masses = [
np.random.uniform(leg_masses_lower_bound[i], leg_masses_upper_bound[i])
for i in xrange(len(leg_masses))
]
minitaur.SetLegMasses(randomized_leg_masses)
- randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0],
- BATTERY_VOLTAGE_RANGE[1])
+ randomized_battery_voltage = random.uniform(BATTERY_VOLTAGE_RANGE[0], BATTERY_VOLTAGE_RANGE[1])
minitaur.SetBatteryVoltage(randomized_battery_voltage)
randomized_motor_damping = random.uniform(MOTOR_VISCOUS_DAMPING_RANGE[0],
MOTOR_VISCOUS_DAMPING_RANGE[1])
minitaur.SetMotorViscousDamping(randomized_motor_damping)
- randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0],
- MINITAUR_LEG_FRICTION[1])
+ randomized_foot_friction = random.uniform(MINITAUR_LEG_FRICTION[0], MINITAUR_LEG_FRICTION[1])
minitaur.SetFootFriction(randomized_foot_friction)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_config.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_config.py
index 53d5ad122..85a97bab7 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_config.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_config.py
@@ -4,7 +4,6 @@ from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
-
PARAM_RANGE = {
# The following ranges are in percentage. e.g. 0.8 means 80%.
"mass": [0.8, 1.2],
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_from_config.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_from_config.py
index 97b91609b..a550f35a0 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_from_config.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_env_randomizer_from_config.py
@@ -7,11 +7,11 @@ from __future__ import print_function
import functools
import random
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
parentdir = os.path.dirname(os.path.dirname(parentdir))
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import numpy as np
import tensorflow as tf
@@ -32,8 +32,7 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
except AttributeError:
raise ValueError("Config {} is not found.".format(config))
self._randomization_param_dict = config()
- tf.logging.info("Randomization config is: {}".format(
- self._randomization_param_dict))
+ tf.logging.info("Randomization config is: {}".format(self._randomization_param_dict))
def randomize_env(self, env):
"""Randomize various physical properties of the environment.
@@ -43,35 +42,29 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
Args:
env: A minitaur gym environment.
"""
- self._randomization_function_dict = self._build_randomization_function_dict(
- env)
+ self._randomization_function_dict = self._build_randomization_function_dict(env)
for param_name, random_range in self._randomization_param_dict.iteritems():
- self._randomization_function_dict[param_name](
- lower_bound=random_range[0], upper_bound=random_range[1])
+ self._randomization_function_dict[param_name](lower_bound=random_range[0],
+ upper_bound=random_range[1])
def _build_randomization_function_dict(self, env):
func_dict = {}
- func_dict["mass"] = functools.partial(
- self._randomize_masses, minitaur=env.minitaur)
- func_dict["inertia"] = functools.partial(
- self._randomize_inertia, minitaur=env.minitaur)
- func_dict["latency"] = functools.partial(
- self._randomize_latency, minitaur=env.minitaur)
- func_dict["joint friction"] = functools.partial(
- self._randomize_joint_friction, minitaur=env.minitaur)
- func_dict["motor friction"] = functools.partial(
- self._randomize_motor_friction, minitaur=env.minitaur)
- func_dict["restitution"] = functools.partial(
- self._randomize_contact_restitution, minitaur=env.minitaur)
- func_dict["lateral friction"] = functools.partial(
- self._randomize_contact_friction, minitaur=env.minitaur)
- func_dict["battery"] = functools.partial(
- self._randomize_battery_level, minitaur=env.minitaur)
- func_dict["motor strength"] = functools.partial(
- self._randomize_motor_strength, minitaur=env.minitaur)
+ func_dict["mass"] = functools.partial(self._randomize_masses, minitaur=env.minitaur)
+ func_dict["inertia"] = functools.partial(self._randomize_inertia, minitaur=env.minitaur)
+ func_dict["latency"] = functools.partial(self._randomize_latency, minitaur=env.minitaur)
+ func_dict["joint friction"] = functools.partial(self._randomize_joint_friction,
+ minitaur=env.minitaur)
+ func_dict["motor friction"] = functools.partial(self._randomize_motor_friction,
+ minitaur=env.minitaur)
+ func_dict["restitution"] = functools.partial(self._randomize_contact_restitution,
+ minitaur=env.minitaur)
+ func_dict["lateral friction"] = functools.partial(self._randomize_contact_friction,
+ minitaur=env.minitaur)
+ func_dict["battery"] = functools.partial(self._randomize_battery_level, minitaur=env.minitaur)
+ func_dict["motor strength"] = functools.partial(self._randomize_motor_strength,
+ minitaur=env.minitaur)
# Settinmg control step needs access to the environment.
- func_dict["control step"] = functools.partial(
- self._randomize_control_step, env=env)
+ func_dict["control step"] = functools.partial(self._randomize_control_step, env=env)
return func_dict
def _randomize_control_step(self, env, lower_bound, upper_bound):
@@ -111,8 +104,8 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
def _randomize_joint_friction(self, minitaur, lower_bound, upper_bound):
num_knee_joints = minitaur.GetNumKneeJoints()
- randomized_joint_frictions = np.random.uniform(
- [lower_bound] * num_knee_joints, [upper_bound] * num_knee_joints)
+ randomized_joint_frictions = np.random.uniform([lower_bound] * num_knee_joints,
+ [upper_bound] * num_knee_joints)
minitaur.SetJointFriction(randomized_joint_frictions)
tf.logging.info("joint friction is: {}".format(randomized_joint_frictions))
@@ -137,9 +130,7 @@ class MinitaurEnvRandomizerFromConfig(env_randomizer_base.EnvRandomizerBase):
tf.logging.info("battery voltage is: {}".format(randomized_battery_voltage))
def _randomize_motor_strength(self, minitaur, lower_bound, upper_bound):
- randomized_motor_strength_ratios = np.random.uniform(
- [lower_bound] * minitaur.num_motors,
- [upper_bound] * minitaur.num_motors)
+ randomized_motor_strength_ratios = np.random.uniform([lower_bound] * minitaur.num_motors,
+ [upper_bound] * minitaur.num_motors)
minitaur.SetMotorStrengthRatios(randomized_motor_strength_ratios)
- tf.logging.info(
- "motor strength is: {}".format(randomized_motor_strength_ratios))
+ tf.logging.info("motor strength is: {}".format(randomized_motor_strength_ratios))
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py
index e030c6ae4..8d9aa8e64 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_push_randomizer.py
@@ -4,11 +4,11 @@ from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
parentdir = os.path.dirname(os.path.dirname(parentdir))
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import math
import numpy as np
@@ -50,12 +50,10 @@ class MinitaurPushRandomizer(env_randomizer_base.EnvRandomizerBase):
self._perturbation_start_step = perturbation_start_step
self._perturbation_interval_steps = perturbation_interval_steps
self._perturbation_duration_steps = perturbation_duration_steps
- self._horizontal_force_bound = (
- horizontal_force_bound if horizontal_force_bound else
- [_HORIZONTAL_FORCE_LOWER_BOUND, _HORIZONTAL_FORCE_UPPER_BOUND])
- self._vertical_force_bound = (
- vertical_force_bound if vertical_force_bound else
- [_VERTICAL_FORCE_LOWER_BOUND, _VERTICAL_FORCE_UPPER_BOUND])
+ self._horizontal_force_bound = (horizontal_force_bound if horizontal_force_bound else
+ [_HORIZONTAL_FORCE_LOWER_BOUND, _HORIZONTAL_FORCE_UPPER_BOUND])
+ self._vertical_force_bound = (vertical_force_bound if vertical_force_bound else
+ [_VERTICAL_FORCE_LOWER_BOUND, _VERTICAL_FORCE_UPPER_BOUND])
def randomize_env(self, env):
"""Randomizes the simulation environment.
@@ -75,23 +73,20 @@ class MinitaurPushRandomizer(env_randomizer_base.EnvRandomizerBase):
"""
base_link_ids = env.minitaur.chassis_link_ids
if env.env_step_counter % self._perturbation_interval_steps == 0:
- self._applied_link_id = base_link_ids[np.random.randint(
- 0, len(base_link_ids))]
- horizontal_force_magnitude = np.random.uniform(
- self._horizontal_force_bound[0], self._horizontal_force_bound[1])
+ self._applied_link_id = base_link_ids[np.random.randint(0, len(base_link_ids))]
+ horizontal_force_magnitude = np.random.uniform(self._horizontal_force_bound[0],
+ self._horizontal_force_bound[1])
theta = np.random.uniform(0, 2 * math.pi)
- vertical_force_magnitude = np.random.uniform(
- self._vertical_force_bound[0], self._vertical_force_bound[1])
+ vertical_force_magnitude = np.random.uniform(self._vertical_force_bound[0],
+ self._vertical_force_bound[1])
self._applied_force = horizontal_force_magnitude * np.array(
- [math.cos(theta), math.sin(theta), 0]) + np.array(
- [0, 0, -vertical_force_magnitude])
+ [math.cos(theta), math.sin(theta), 0]) + np.array([0, 0, -vertical_force_magnitude])
if (env.env_step_counter % self._perturbation_interval_steps <
self._perturbation_duration_steps) and (env.env_step_counter >=
self._perturbation_start_step):
- env.pybullet_client.applyExternalForce(
- objectUniqueId=env.minitaur.quadruped,
- linkIndex=self._applied_link_id,
- forceObj=self._applied_force,
- posObj=[0.0, 0.0, 0.0],
- flags=env.pybullet_client.LINK_FRAME)
+ env.pybullet_client.applyExternalForce(objectUniqueId=env.minitaur.quadruped,
+ linkIndex=self._applied_link_id,
+ forceObj=self._applied_force,
+ posObj=[0.0, 0.0, 0.0],
+ flags=env.pybullet_client.LINK_FRAME)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_terrain_randomizer.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_terrain_randomizer.py
index b7e5706b8..d5f33371e 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_terrain_randomizer.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/env_randomizers/minitaur_terrain_randomizer.py
@@ -4,11 +4,11 @@ from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(currentdir))
parentdir = os.path.dirname(os.path.dirname(parentdir))
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import itertools
import math
@@ -62,8 +62,7 @@ class PoissonDisc2D(object):
self._grid = [None] * self._grid_size_x * self._grid_size_y
# Generate the first sample point and set it as an active site.
- first_sample = np.array(
- np.random.random_sample(2)) * [grid_length, grid_width]
+ first_sample = np.array(np.random.random_sample(2)) * [grid_length, grid_width]
self._active_list = [first_sample]
# Also store the sample point in the grid.
@@ -114,8 +113,7 @@ class PoissonDisc2D(object):
Returns:
Whether the point is inside the grid.
"""
- return (0 <= point[0] < self._grid_length) and (0 <= point[1] <
- self._grid_width)
+ return (0 <= point[0] < self._grid_length) and (0 <= point[1] < self._grid_width)
def _is_in_range(self, index2d):
"""Checks if the cell ID is within the grid.
@@ -127,8 +125,7 @@ class PoissonDisc2D(object):
Whether the cell (2D index) is inside the grid.
"""
- return (0 <= index2d[0] < self._grid_size_x) and (0 <= index2d[1] <
- self._grid_size_y)
+ return (0 <= index2d[0] < self._grid_size_x) and (0 <= index2d[1] < self._grid_size_y)
def _is_close_to_existing_points(self, point):
"""Checks if the point is close to any already sampled (and stored) points.
@@ -142,15 +139,13 @@ class PoissonDisc2D(object):
"""
px, py = self._point_to_index_2d(point)
# Now we can check nearby cells for existing points
- for neighbor_cell in itertools.product(
- xrange(px - 1, px + 2), xrange(py - 1, py + 2)):
+ for neighbor_cell in itertools.product(xrange(px - 1, px + 2), xrange(py - 1, py + 2)):
if not self._is_in_range(neighbor_cell):
continue
maybe_a_point = self._grid[self._index_2d_to_1d(neighbor_cell)]
- if maybe_a_point is not None and np.linalg.norm(
- maybe_a_point - point) < self._min_radius:
+ if maybe_a_point is not None and np.linalg.norm(maybe_a_point - point) < self._min_radius:
return True
return False
@@ -168,8 +163,8 @@ class PoissonDisc2D(object):
random_angle = np.random.uniform(0, 2 * math.pi)
# The sampled 2D points near the active point
- sample = random_radius * np.array(
- [np.cos(random_angle), np.sin(random_angle)]) + active_point
+ sample = random_radius * np.array([np.cos(random_angle),
+ np.sin(random_angle)]) + active_point
if not self._is_in_grid(sample):
continue
@@ -214,12 +209,11 @@ class TerrainType(enum.Enum):
class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
"""Generates an uneven terrain in the gym env."""
- def __init__(
- self,
- terrain_type=TerrainType.TRIANGLE_MESH,
- mesh_filename="robotics/reinforcement_learning/minitaur/envs/testdata/"
- "triangle_mesh_terrain/terrain9735.obj",
- mesh_scale=None):
+ def __init__(self,
+ terrain_type=TerrainType.TRIANGLE_MESH,
+ mesh_filename="robotics/reinforcement_learning/minitaur/envs/testdata/"
+ "triangle_mesh_terrain/terrain9735.obj",
+ mesh_scale=None):
"""Initializes the randomizer.
Args:
@@ -261,9 +255,7 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
flags=1,
meshScale=self._mesh_scale)
env.ground_id = env.pybullet_client.createMultiBody(
- baseMass=0,
- baseCollisionShapeIndex=terrain_collision_shape_id,
- basePosition=[0, 0, 0])
+ baseMass=0, baseCollisionShapeIndex=terrain_collision_shape_id, basePosition=[0, 0, 0])
def _generate_convex_blocks(self, env):
"""Adds random convex blocks to the flat ground.
@@ -277,8 +269,7 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
"""
- poisson_disc = PoissonDisc2D(_GRID_LENGTH, _GRID_WIDTH, _MIN_BLOCK_DISTANCE,
- _MAX_SAMPLE_SIZE)
+ poisson_disc = PoissonDisc2D(_GRID_LENGTH, _GRID_WIDTH, _MIN_BLOCK_DISTANCE, _MAX_SAMPLE_SIZE)
block_centers = poisson_disc.generate()
@@ -289,12 +280,10 @@ class MinitaurTerrainRandomizer(env_randomizer_base.EnvRandomizerBase):
# Do not place blocks near the point [0, 0], where the robot will start.
if abs(shifted_center[0]) < 1.0 and abs(shifted_center[1]) < 1.0:
continue
- half_length = np.random.uniform(_MIN_BLOCK_LENGTH, _MAX_BLOCK_LENGTH) / (
- 2 * math.sqrt(2))
+ half_length = np.random.uniform(_MIN_BLOCK_LENGTH, _MAX_BLOCK_LENGTH) / (2 * math.sqrt(2))
half_height = np.random.uniform(_MIN_BLOCK_HEIGHT, _MAX_BLOCK_HEIGHT) / 2
box_id = env.pybullet_client.createCollisionShape(
- env.pybullet_client.GEOM_BOX,
- halfExtents=[half_length, half_length, half_height])
+ env.pybullet_client.GEOM_BOX, halfExtents=[half_length, half_length, half_height])
env.pybullet_client.createMultiBody(
baseMass=0,
baseCollisionShapeIndex=box_id,
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur.py
index efe32837c..fc403c0d5 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur.py
@@ -2,10 +2,10 @@
"""
-import os, inspect
+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 collections
import copy
@@ -24,9 +24,8 @@ OVERHEAT_SHUTDOWN_TORQUE = 2.45
OVERHEAT_SHUTDOWN_TIME = 1.0
LEG_POSITION = ["front_left", "back_left", "front_right", "back_right"]
MOTOR_NAMES = [
- "motor_front_leftL_joint", "motor_front_leftR_joint",
- "motor_back_leftL_joint", "motor_back_leftR_joint",
- "motor_front_rightL_joint", "motor_front_rightR_joint",
+ "motor_front_leftL_joint", "motor_front_leftR_joint", "motor_back_leftL_joint",
+ "motor_back_leftR_joint", "motor_front_rightL_joint", "motor_front_rightR_joint",
"motor_back_rightL_joint", "motor_back_rightR_joint"
]
_CHASSIS_NAME_PATTERN = re.compile(r"chassis\D*center")
@@ -141,10 +140,9 @@ class Minitaur(object):
if self._accurate_motor_model_enabled:
self._kp = motor_kp
self._kd = motor_kd
- self._motor_model = motor.MotorModel(
- torque_control_enabled=self._torque_control_enabled,
- kp=self._kp,
- kd=self._kd)
+ self._motor_model = motor.MotorModel(torque_control_enabled=self._torque_control_enabled,
+ kp=self._kp,
+ kd=self._kd)
elif self._pd_control_enabled:
self._kp = 8
self._kd = 0.3
@@ -188,17 +186,14 @@ class Minitaur(object):
self._link_urdf = []
num_bodies = self._pybullet_client.getNumJoints(self.quadruped)
for body_id in range(-1, num_bodies): # -1 is for the base link.
- inertia = self._pybullet_client.getDynamicsInfo(self.quadruped,
- body_id)[2]
+ inertia = self._pybullet_client.getDynamicsInfo(self.quadruped, body_id)[2]
self._link_urdf.append(inertia)
# We need to use id+1 to index self._link_urdf because it has the base
# (index = -1) at the first element.
self._base_inertia_urdf = [
self._link_urdf[chassis_id + 1] for chassis_id in self._chassis_link_ids
]
- self._leg_inertia_urdf = [
- self._link_urdf[leg_id + 1] for leg_id in self._leg_link_ids
- ]
+ self._leg_inertia_urdf = [self._link_urdf[leg_id + 1] for leg_id in self._leg_link_ids]
self._leg_inertia_urdf.extend(
[self._link_urdf[motor_id + 1] for motor_id in self._motor_link_ids])
@@ -239,13 +234,10 @@ class Minitaur(object):
num_joints = self._pybullet_client.getNumJoints(self.quadruped)
for i in range(num_joints):
joint_info = self._pybullet_client.getJointInfo(self.quadruped, i)
- self._pybullet_client.changeDynamics(
- joint_info[0], -1, linearDamping=0, angularDamping=0)
+ self._pybullet_client.changeDynamics(joint_info[0], -1, linearDamping=0, angularDamping=0)
def _BuildMotorIdList(self):
- self._motor_id_list = [
- self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES
- ]
+ self._motor_id_list = [self._joint_name_to_id[motor_name] for motor_name in MOTOR_NAMES]
def IsObservationValid(self):
"""Whether the observation is valid for the current time step.
@@ -284,10 +276,10 @@ class Minitaur(object):
useFixedBase=self._on_rack,
flags=self._pybullet_client.URDF_USE_SELF_COLLISION)
else:
- self.quadruped = self._pybullet_client.loadURDF(
- "%s/quadruped/minitaur.urdf" % self._urdf_root,
- init_position,
- useFixedBase=self._on_rack)
+ self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur.urdf" %
+ self._urdf_root,
+ init_position,
+ useFixedBase=self._on_rack)
self._BuildJointNameToIdDict()
self._BuildUrdfIds()
if self._remove_default_joint_damping:
@@ -297,10 +289,9 @@ class Minitaur(object):
self._RecordInertiaInfoFromURDF()
self.ResetPose(add_constraint=True)
else:
- self._pybullet_client.resetBasePositionAndOrientation(
- self.quadruped, init_position, INIT_ORIENTATION)
- self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
- [0, 0, 0])
+ self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
+ INIT_ORIENTATION)
+ self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
self.ResetPose(add_constraint=False)
self._overheat_counter = np.zeros(self.num_motors)
self._motor_enabled_list = [True] * self.num_motors
@@ -325,25 +316,22 @@ class Minitaur(object):
self.ReceiveObservation()
def _SetMotorTorqueById(self, motor_id, torque):
- self._pybullet_client.setJointMotorControl2(
- bodyIndex=self.quadruped,
- jointIndex=motor_id,
- controlMode=self._pybullet_client.TORQUE_CONTROL,
- force=torque)
+ self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
+ jointIndex=motor_id,
+ controlMode=self._pybullet_client.TORQUE_CONTROL,
+ force=torque)
def _SetDesiredMotorAngleById(self, motor_id, desired_angle):
- self._pybullet_client.setJointMotorControl2(
- bodyIndex=self.quadruped,
- jointIndex=motor_id,
- controlMode=self._pybullet_client.POSITION_CONTROL,
- targetPosition=desired_angle,
- positionGain=self._kp,
- velocityGain=self._kd,
- force=self._max_force)
+ self._pybullet_client.setJointMotorControl2(bodyIndex=self.quadruped,
+ jointIndex=motor_id,
+ controlMode=self._pybullet_client.POSITION_CONTROL,
+ targetPosition=desired_angle,
+ positionGain=self._kp,
+ velocityGain=self._kd,
+ force=self._max_force)
def _SetDesiredMotorAngleByName(self, motor_name, desired_angle):
- self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name],
- desired_angle)
+ self._SetDesiredMotorAngleById(self._joint_name_to_id[motor_name], desired_angle)
def ResetPose(self, add_constraint):
"""Reset the pose of the minitaur.
@@ -367,59 +355,53 @@ class Minitaur(object):
knee_angle = -2.1834
leg_position = LEG_POSITION[leg_id]
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_link"],
- self._motor_direction[2 * leg_id] * knee_angle,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_link"],
- self._motor_direction[2 * leg_id + 1] * knee_angle,
- targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "L_link"],
+ self._motor_direction[2 * leg_id] * knee_angle,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "R_link"],
+ self._motor_direction[2 * leg_id + 1] * knee_angle,
+ targetVelocity=0)
if add_constraint:
self._pybullet_client.createConstraint(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_link"],
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_link"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_RIGHT, KNEE_CONSTRAINT_POINT_LEFT)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_link"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_link"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_RIGHT,
+ KNEE_CONSTRAINT_POINT_LEFT)
if self._accurate_motor_model_enabled or self._pd_control_enabled:
# Disable the default motor in pybullet.
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
else:
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "L_joint",
- self._motor_direction[2 * leg_id] * half_pi)
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "R_joint",
- self._motor_direction[2 * leg_id + 1] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
+ self._motor_direction[2 * leg_id] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
+ self._motor_direction[2 * leg_id + 1] * half_pi)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
@@ -440,8 +422,7 @@ class Minitaur(object):
Returns:
The position of minitaur's base.
"""
- position, _ = (
- self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
+ position, _ = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
return position
def GetTrueBaseRollPitchYaw(self):
@@ -464,10 +445,9 @@ class Minitaur(object):
"""
delayed_orientation = np.array(
self._control_observation[3 * self.num_motors:3 * self.num_motors + 4])
- delayed_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion(
- delayed_orientation)
- roll_pitch_yaw = self._AddSensorNoise(
- np.array(delayed_roll_pitch_yaw), self._observation_noise_stdev[3])
+ delayed_roll_pitch_yaw = self._pybullet_client.getEulerFromQuaternion(delayed_orientation)
+ roll_pitch_yaw = self._AddSensorNoise(np.array(delayed_roll_pitch_yaw),
+ self._observation_noise_stdev[3])
return roll_pitch_yaw
def GetTrueMotorAngles(self):
@@ -492,9 +472,8 @@ class Minitaur(object):
Returns:
Motor angles polluted by noise and latency, mapped to [-pi, pi].
"""
- motor_angles = self._AddSensorNoise(
- np.array(self._control_observation[0:self.num_motors]),
- self._observation_noise_stdev[0])
+ motor_angles = self._AddSensorNoise(np.array(self._control_observation[0:self.num_motors]),
+ self._observation_noise_stdev[0])
return MapToMinusPiToPi(motor_angles)
def GetTrueMotorVelocities(self):
@@ -518,8 +497,7 @@ class Minitaur(object):
Velocities of all eight motors polluted by noise and latency.
"""
return self._AddSensorNoise(
- np.array(
- self._control_observation[self.num_motors:2 * self.num_motors]),
+ np.array(self._control_observation[self.num_motors:2 * self.num_motors]),
self._observation_noise_stdev[1])
def GetTrueMotorTorques(self):
@@ -546,8 +524,7 @@ class Minitaur(object):
Motor torques of all eight motors polluted by noise and latency.
"""
return self._AddSensorNoise(
- np.array(
- self._control_observation[2 * self.num_motors:3 * self.num_motors]),
+ np.array(self._control_observation[2 * self.num_motors:3 * self.num_motors]),
self._observation_noise_stdev[2])
def GetTrueBaseOrientation(self):
@@ -556,8 +533,7 @@ class Minitaur(object):
Returns:
The orientation of minitaur's base.
"""
- _, orientation = (
- self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
+ _, orientation = (self._pybullet_client.getBasePositionAndOrientation(self.quadruped))
return orientation
def GetBaseOrientation(self):
@@ -567,8 +543,7 @@ class Minitaur(object):
Returns:
The orientation of minitaur's base polluted by noise and latency.
"""
- return self._pybullet_client.getQuaternionFromEuler(
- self.GetBaseRollPitchYaw())
+ return self._pybullet_client.getQuaternionFromEuler(self.GetBaseRollPitchYaw())
def GetTrueBaseRollPitchYawRate(self):
"""Get the rate of orientation change of the minitaur's base in euler angle.
@@ -588,8 +563,7 @@ class Minitaur(object):
and latency.
"""
return self._AddSensorNoise(
- np.array(self._control_observation[3 * self.num_motors + 4:
- 3 * self.num_motors + 7]),
+ np.array(self._control_observation[3 * self.num_motors + 4:3 * self.num_motors + 7]),
self._observation_noise_stdev[4])
def GetActionDimension(self):
@@ -618,12 +592,9 @@ class Minitaur(object):
"""
if self._motor_velocity_limit < np.inf:
current_motor_angle = self.GetTrueMotorAngles()
- motor_commands_max = (
- current_motor_angle + self.time_step * self._motor_velocity_limit)
- motor_commands_min = (
- current_motor_angle - self.time_step * self._motor_velocity_limit)
- motor_commands = np.clip(motor_commands, motor_commands_min,
- motor_commands_max)
+ motor_commands_max = (current_motor_angle + self.time_step * self._motor_velocity_limit)
+ motor_commands_min = (current_motor_angle - self.time_step * self._motor_velocity_limit)
+ motor_commands = np.clip(motor_commands, motor_commands_min, motor_commands_max)
# Set the kp and kd for all the motors if not provided as an argument.
if motor_kps is None:
motor_kps = np.full(8, self._kp)
@@ -642,8 +613,7 @@ class Minitaur(object):
self._overheat_counter[i] += 1
else:
self._overheat_counter[i] = 0
- if (self._overheat_counter[i] >
- OVERHEAT_SHUTDOWN_TIME / self.time_step):
+ if (self._overheat_counter[i] > OVERHEAT_SHUTDOWN_TIME / self.time_step):
self._motor_enabled_list[i] = False
# The torque is already in the observation space because we use
@@ -651,19 +621,17 @@ class Minitaur(object):
self._observed_motor_torques = observed_torque
# Transform into the motor space when applying the torque.
- self._applied_motor_torque = np.multiply(actual_torque,
- self._motor_direction)
+ self._applied_motor_torque = np.multiply(actual_torque, self._motor_direction)
- for motor_id, motor_torque, motor_enabled in zip(
- self._motor_id_list, self._applied_motor_torque,
- self._motor_enabled_list):
+ for motor_id, motor_torque, motor_enabled in zip(self._motor_id_list,
+ self._applied_motor_torque,
+ self._motor_enabled_list):
if motor_enabled:
self._SetMotorTorqueById(motor_id, motor_torque)
else:
self._SetMotorTorqueById(motor_id, 0)
else:
- torque_commands = -1 * motor_kps * (
- q - motor_commands) - motor_kds * qdot
+ torque_commands = -1 * motor_kps * (q - motor_commands) - motor_kds * qdot
# The torque is already in the observation space because we use
# GetMotorAngles and GetMotorVelocities.
@@ -673,14 +641,12 @@ class Minitaur(object):
self._applied_motor_torques = np.multiply(self._observed_motor_torques,
self._motor_direction)
- for motor_id, motor_torque in zip(self._motor_id_list,
- self._applied_motor_torques):
+ for motor_id, motor_torque in zip(self._motor_id_list, self._applied_motor_torques):
self._SetMotorTorqueById(motor_id, motor_torque)
else:
- motor_commands_with_direction = np.multiply(motor_commands,
- self._motor_direction)
- for motor_id, motor_command_with_direction in zip(
- self._motor_id_list, motor_commands_with_direction):
+ motor_commands_with_direction = np.multiply(motor_commands, self._motor_direction)
+ for motor_id, motor_command_with_direction in zip(self._motor_id_list,
+ motor_commands_with_direction):
self._SetDesiredMotorAngleById(motor_id, motor_command_with_direction)
def ConvertFromLegModel(self, actions):
@@ -698,13 +664,13 @@ class Minitaur(object):
quater_pi = math.pi / 4
for i in range(self.num_motors):
action_idx = int(i // 2)
- forward_backward_component = (-scale_for_singularity * quater_pi * (
- actions[action_idx + half_num_motors] + offset_for_singularity))
+ forward_backward_component = (
+ -scale_for_singularity * quater_pi *
+ (actions[action_idx + half_num_motors] + offset_for_singularity))
extension_component = (-1)**i * quater_pi * actions[action_idx]
if i >= half_num_motors:
extension_component = -extension_component
- motor_angle[i] = (
- math.pi + forward_backward_component + extension_component)
+ motor_angle[i] = (math.pi + forward_backward_component + extension_component)
return motor_angle
def GetBaseMassesFromURDF(self):
@@ -734,12 +700,10 @@ class Minitaur(object):
the length of self._chassis_link_ids.
"""
if len(base_mass) != len(self._chassis_link_ids):
- raise ValueError(
- "The length of base_mass {} and self._chassis_link_ids {} are not "
- "the same.".format(len(base_mass), len(self._chassis_link_ids)))
+ raise ValueError("The length of base_mass {} and self._chassis_link_ids {} are not "
+ "the same.".format(len(base_mass), len(self._chassis_link_ids)))
for chassis_id, chassis_mass in zip(self._chassis_link_ids, base_mass):
- self._pybullet_client.changeDynamics(
- self.quadruped, chassis_id, mass=chassis_mass)
+ self._pybullet_client.changeDynamics(self.quadruped, chassis_id, mass=chassis_mass)
def SetLegMasses(self, leg_masses):
"""Set the mass of the legs.
@@ -759,12 +723,10 @@ class Minitaur(object):
raise ValueError("The number of values passed to SetLegMasses are "
"different than number of leg links and motors.")
for leg_id, leg_mass in zip(self._leg_link_ids, leg_masses):
- self._pybullet_client.changeDynamics(
- self.quadruped, leg_id, mass=leg_mass)
+ self._pybullet_client.changeDynamics(self.quadruped, leg_id, mass=leg_mass)
motor_masses = leg_masses[len(self._leg_link_ids):]
for link_id, motor_mass in zip(self._motor_link_ids, motor_masses):
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, mass=motor_mass)
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, mass=motor_mass)
def SetBaseInertias(self, base_inertias):
"""Set the inertias of minitaur's base.
@@ -779,17 +741,15 @@ class Minitaur(object):
negative values.
"""
if len(base_inertias) != len(self._chassis_link_ids):
- raise ValueError(
- "The length of base_inertias {} and self._chassis_link_ids {} are "
- "not the same.".format(
- len(base_inertias), len(self._chassis_link_ids)))
- for chassis_id, chassis_inertia in zip(self._chassis_link_ids,
- base_inertias):
+ raise ValueError("The length of base_inertias {} and self._chassis_link_ids {} are "
+ "not the same.".format(len(base_inertias), len(self._chassis_link_ids)))
+ for chassis_id, chassis_inertia in zip(self._chassis_link_ids, base_inertias):
for inertia_value in chassis_inertia:
if (np.asarray(inertia_value) < 0).any():
raise ValueError("Values in inertia matrix should be non-negative.")
- self._pybullet_client.changeDynamics(
- self.quadruped, chassis_id, localInertiaDiagonal=chassis_inertia)
+ self._pybullet_client.changeDynamics(self.quadruped,
+ chassis_id,
+ localInertiaDiagonal=chassis_inertia)
def SetLegInertias(self, leg_inertias):
"""Set the inertias of the legs.
@@ -813,16 +773,18 @@ class Minitaur(object):
for inertia_value in leg_inertias:
if (np.asarray(inertia_value) < 0).any():
raise ValueError("Values in inertia matrix should be non-negative.")
- self._pybullet_client.changeDynamics(
- self.quadruped, leg_id, localInertiaDiagonal=leg_inertia)
+ self._pybullet_client.changeDynamics(self.quadruped,
+ leg_id,
+ localInertiaDiagonal=leg_inertia)
motor_inertias = leg_inertias[len(self._leg_link_ids):]
for link_id, motor_inertia in zip(self._motor_link_ids, motor_inertias):
for inertia_value in motor_inertias:
if (np.asarray(inertia_value) < 0).any():
raise ValueError("Values in inertia matrix should be non-negative.")
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, localInertiaDiagonal=motor_inertia)
+ self._pybullet_client.changeDynamics(self.quadruped,
+ link_id,
+ localInertiaDiagonal=motor_inertia)
def SetFootFriction(self, foot_friction):
"""Set the lateral friction of the feet.
@@ -832,8 +794,7 @@ class Minitaur(object):
shared by all four feet.
"""
for link_id in self._foot_link_ids:
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, lateralFriction=foot_friction)
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, lateralFriction=foot_friction)
# TODO(b/73748980): Add more API's to set other contact parameters.
def SetFootRestitution(self, foot_restitution):
@@ -844,8 +805,7 @@ class Minitaur(object):
This value is shared by all four feet.
"""
for link_id in self._foot_link_ids:
- self._pybullet_client.changeDynamics(
- self.quadruped, link_id, restitution=foot_restitution)
+ self._pybullet_client.changeDynamics(self.quadruped, link_id, restitution=foot_restitution)
def SetJointFriction(self, joint_frictions):
for knee_joint_id, friction in zip(self._foot_link_ids, joint_frictions):
@@ -901,9 +861,8 @@ class Minitaur(object):
return self._observation_history[-1]
remaining_latency = latency - n_steps_ago * self.time_step
blend_alpha = remaining_latency / self.time_step
- observation = (
- (1.0 - blend_alpha) * np.array(self._observation_history[n_steps_ago])
- + blend_alpha * np.array(self._observation_history[n_steps_ago + 1]))
+ observation = ((1.0 - blend_alpha) * np.array(self._observation_history[n_steps_ago]) +
+ blend_alpha * np.array(self._observation_history[n_steps_ago + 1]))
return observation
def _GetPDObservation(self):
@@ -913,15 +872,13 @@ class Minitaur(object):
return (np.array(q), np.array(qdot))
def _GetControlObservation(self):
- control_delayed_observation = self._GetDelayedObservation(
- self._control_latency)
+ control_delayed_observation = self._GetDelayedObservation(self._control_latency)
return control_delayed_observation
def _AddSensorNoise(self, sensor_values, noise_stdev):
if noise_stdev <= 0:
return sensor_values
- observation = sensor_values + np.random.normal(
- scale=noise_stdev, size=sensor_values.shape)
+ observation = sensor_values + np.random.normal(scale=noise_stdev, size=sensor_values.shape)
return observation
def SetControlLatency(self, latency):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env.py
index 9529062fa..fa177b7b5 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env.py
@@ -3,10 +3,10 @@
"""
import math
-import os, inspect
+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 gym import spaces
import numpy as np
@@ -31,10 +31,7 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
expenditure.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 66
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 66}
def __init__(self,
urdf_version=None,
@@ -81,23 +78,23 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
# _swing_offset and _extension_offset is to mimick the bent legs.
self._swing_offset = np.zeros(NUM_LEGS)
self._extension_offset = np.zeros(NUM_LEGS)
- super(MinitaurAlternatingLegsEnv, self).__init__(
- urdf_version=urdf_version,
- accurate_motor_model_enabled=True,
- motor_overheat_protection=True,
- hard_reset=False,
- motor_kp=motor_kp,
- motor_kd=motor_kd,
- remove_default_joint_damping=remove_default_joint_damping,
- control_latency=control_latency,
- pd_latency=pd_latency,
- on_rack=on_rack,
- render=render,
- num_steps_to_log=num_steps_to_log,
- env_randomizer=env_randomizer,
- log_path=log_path,
- control_time_step=control_time_step,
- action_repeat=action_repeat)
+ super(MinitaurAlternatingLegsEnv,
+ self).__init__(urdf_version=urdf_version,
+ accurate_motor_model_enabled=True,
+ motor_overheat_protection=True,
+ hard_reset=False,
+ motor_kp=motor_kp,
+ motor_kd=motor_kd,
+ remove_default_joint_damping=remove_default_joint_damping,
+ control_latency=control_latency,
+ pd_latency=pd_latency,
+ on_rack=on_rack,
+ render=render,
+ num_steps_to_log=num_steps_to_log,
+ env_randomizer=env_randomizer,
+ log_path=log_path,
+ control_time_step=control_time_step,
+ action_repeat=action_repeat)
action_dim = 8
action_high = np.array([0.1] * action_dim)
@@ -113,33 +110,29 @@ class MinitaurAlternatingLegsEnv(minitaur_gym_env.MinitaurGymEnv):
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
init_pose = [
- INIT_SWING_POS + self._swing_offset[0],
- INIT_SWING_POS + self._swing_offset[1],
- INIT_SWING_POS + self._swing_offset[2],
- INIT_SWING_POS + self._swing_offset[3],
+ INIT_SWING_POS + self._swing_offset[0], INIT_SWING_POS + self._swing_offset[1],
+ INIT_SWING_POS + self._swing_offset[2], INIT_SWING_POS + self._swing_offset[3],
INIT_EXTENSION_POS + self._extension_offset[0],
INIT_EXTENSION_POS + self._extension_offset[1],
INIT_EXTENSION_POS + self._extension_offset[2],
INIT_EXTENSION_POS + self._extension_offset[3]
]
initial_motor_angles = self._convert_from_leg_model(init_pose)
- super(MinitaurAlternatingLegsEnv, self).reset(
- initial_motor_angles=initial_motor_angles, reset_duration=0.5)
+ super(MinitaurAlternatingLegsEnv, self).reset(initial_motor_angles=initial_motor_angles,
+ reset_duration=0.5)
return self._get_observation()
def _convert_from_leg_model(self, leg_pose):
motor_pose = np.zeros(NUM_MOTORS)
for i in range(NUM_LEGS):
motor_pose[2 * i] = leg_pose[NUM_LEGS + i] - (-1)**(i / 2) * leg_pose[i]
- motor_pose[2 * i
- + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
+ motor_pose[2 * i + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
return motor_pose
def _signal(self, t):
initial_pose = np.array([
- INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
- INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
- INIT_EXTENSION_POS
+ INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
+ INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
])
amplitude = STEP_AMPLITUDE
period = STEP_PERIOD
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env_example.py
index f1266d354..226edf3c5 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_alternating_legs_env_example.py
@@ -3,10 +3,10 @@
"""
import time
-import os, inspect
+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 os
import numpy as np
@@ -50,13 +50,11 @@ def hand_tuned_agent(observation, timestamp):
pitch_compensation = pitch_gain * pitch + pitch_dot_gain * pitch_dot
first_leg = [
- 0, -pitch_compensation, -pitch_compensation, 0, 0,
- -pitch_compensation - roll_compensation,
+ 0, -pitch_compensation, -pitch_compensation, 0, 0, -pitch_compensation - roll_compensation,
pitch_compensation + roll_compensation, 0
]
second_leg = [
- -pitch_compensation, 0, 0, -pitch_compensation,
- pitch_compensation - roll_compensation, 0, 0,
+ -pitch_compensation, 0, 0, -pitch_compensation, pitch_compensation - roll_compensation, 0, 0,
-pitch_compensation + roll_compensation
]
if (timestamp // minitaur_alternating_legs_env.STEP_PERIOD) % 2:
@@ -94,8 +92,7 @@ def hand_tuned_balance_example(log_path=None):
for _ in range(steps):
# Sleep to prevent serial buffer overflow on microcontroller.
time.sleep(0.002)
- action = hand_tuned_agent(observation,
- environment.minitaur.GetTimeSinceReset())
+ action = hand_tuned_agent(observation, environment.minitaur.GetTimeSinceReset())
observation, reward, done, _ = environment.step(action)
sum_reward += reward
if done:
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env.py
index c2ec7ded4..b40d6f0d4 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env.py
@@ -4,10 +4,10 @@
import math
import random
-import os, inspect
+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 gym import spaces
import numpy as np
@@ -52,61 +52,52 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
that its walking gait is clearer to visualize.
render: Whether to render the simulation.
"""
- super(MinitaurBallGymEnv, self).__init__(
- urdf_root=urdf_root,
- self_collision_enabled=self_collision_enabled,
- pd_control_enabled=pd_control_enabled,
- leg_model_enabled=leg_model_enabled,
- on_rack=on_rack,
- render=render)
+ super(MinitaurBallGymEnv, self).__init__(urdf_root=urdf_root,
+ self_collision_enabled=self_collision_enabled,
+ pd_control_enabled=pd_control_enabled,
+ leg_model_enabled=leg_model_enabled,
+ on_rack=on_rack,
+ render=render)
self._cam_dist = 2.0
self._cam_yaw = -70
self._cam_pitch = -30
self.action_space = spaces.Box(np.array([-1]), np.array([1]))
- self.observation_space = spaces.Box(np.array([-math.pi, 0]),
- np.array([math.pi, 100]))
+ self.observation_space = spaces.Box(np.array([-math.pi, 0]), np.array([math.pi, 100]))
def reset(self):
self._ball_id = 0
super(MinitaurBallGymEnv, self).reset()
self._init_ball_theta = random.uniform(-INIT_BALL_ANGLE, INIT_BALL_ANGLE)
self._init_ball_distance = INIT_BALL_DISTANCE
- self._ball_pos = [self._init_ball_distance *
- math.cos(self._init_ball_theta),
- self._init_ball_distance *
- math.sin(self._init_ball_theta), 1]
+ self._ball_pos = [
+ self._init_ball_distance * math.cos(self._init_ball_theta),
+ self._init_ball_distance * math.sin(self._init_ball_theta), 1
+ ]
self._ball_id = self._pybullet_client.loadURDF(
"%s/sphere_with_restitution.urdf" % self._urdf_root, self._ball_pos)
return self._get_observation()
def _get_observation(self):
world_translation_minitaur, world_rotation_minitaur = (
- self._pybullet_client.getBasePositionAndOrientation(
- self.minitaur.quadruped))
+ self._pybullet_client.getBasePositionAndOrientation(self.minitaur.quadruped))
world_translation_ball, world_rotation_ball = (
self._pybullet_client.getBasePositionAndOrientation(self._ball_id))
- minitaur_translation_world, minitaur_rotation_world = (
- self._pybullet_client.invertTransform(world_translation_minitaur,
- world_rotation_minitaur))
- minitaur_translation_ball, _ = (
- self._pybullet_client.multiplyTransforms(minitaur_translation_world,
- minitaur_rotation_world,
- world_translation_ball,
- world_rotation_ball))
- distance = math.sqrt(minitaur_translation_ball[0]**2 +
- minitaur_translation_ball[1]**2)
- angle = math.atan2(minitaur_translation_ball[0],
- minitaur_translation_ball[1])
+ minitaur_translation_world, minitaur_rotation_world = (self._pybullet_client.invertTransform(
+ world_translation_minitaur, world_rotation_minitaur))
+ minitaur_translation_ball, _ = (self._pybullet_client.multiplyTransforms(
+ minitaur_translation_world, minitaur_rotation_world, world_translation_ball,
+ world_rotation_ball))
+ distance = math.sqrt(minitaur_translation_ball[0]**2 + minitaur_translation_ball[1]**2)
+ angle = math.atan2(minitaur_translation_ball[0], minitaur_translation_ball[1])
self._observation = [angle - math.pi / 2, distance]
return self._observation
def _transform_action_to_motor_command(self, action):
if self._leg_model_enabled:
for i, action_component in enumerate(action):
- if not (-self._action_bound - ACTION_EPS <=
- action_component <= self._action_bound + ACTION_EPS):
- raise ValueError("{}th action {} out of bounds.".format
- (i, action_component))
+ if not (-self._action_bound - ACTION_EPS <= action_component <=
+ self._action_bound + ACTION_EPS):
+ raise ValueError("{}th action {} out of bounds.".format(i, action_component))
action = self._apply_steering_to_locomotion(action)
action = self.minitaur.ConvertFromLegModel(action)
return action
@@ -126,15 +117,12 @@ class MinitaurBallGymEnv(minitaur_gym_env.MinitaurGymEnv):
return action
def _distance_to_ball(self):
- world_translation_minitaur, _ = (
- self._pybullet_client.getBasePositionAndOrientation(
- self.minitaur.quadruped))
- world_translation_ball, _ = (
- self._pybullet_client.getBasePositionAndOrientation(
- self._ball_id))
- distance = math.sqrt(
- (world_translation_ball[0] - world_translation_minitaur[0])**2 +
- (world_translation_ball[1] - world_translation_minitaur[1])**2)
+ world_translation_minitaur, _ = (self._pybullet_client.getBasePositionAndOrientation(
+ self.minitaur.quadruped))
+ world_translation_ball, _ = (self._pybullet_client.getBasePositionAndOrientation(
+ self._ball_id))
+ distance = math.sqrt((world_translation_ball[0] - world_translation_minitaur[0])**2 +
+ (world_translation_ball[1] - world_translation_minitaur[1])**2)
return distance
def _goal_state(self):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env_example.py
index b52b945ad..404dc26ac 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_ball_gym_env_example.py
@@ -31,4 +31,4 @@ def main():
if __name__ == '__main__':
- main() \ No newline at end of file
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_derpy.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_derpy.py
index 2b5eb2698..7946955d4 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_derpy.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_derpy.py
@@ -6,13 +6,13 @@ It is the result of first pass system identification for the derpy robot. The
"""
import math
-import os, inspect
+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 numpy as np
-from pybullet_envs.minitaur.envs import minitaur
+from pybullet_envs.minitaur.envs import minitaur
KNEE_CONSTRAINT_POINT_LONG = [0, 0.0055, 0.088]
KNEE_CONSTRAINT_POINT_SHORT = [0, 0.0055, 0.100]
@@ -46,13 +46,12 @@ class MinitaurDerpy(minitaur.Minitaur):
"%s/quadruped/minitaur_derpy.urdf" % self._urdf_root,
init_position,
useFixedBase=self._on_rack,
- flags=(
- self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
+ flags=(self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
else:
- self.quadruped = self._pybullet_client.loadURDF(
- "%s/quadruped/minitaur_derpy.urdf" % self._urdf_root,
- init_position,
- useFixedBase=self._on_rack)
+ self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur_derpy.urdf" %
+ self._urdf_root,
+ init_position,
+ useFixedBase=self._on_rack)
self._BuildJointNameToIdDict()
self._BuildUrdfIds()
if self._remove_default_joint_damping:
@@ -62,10 +61,9 @@ class MinitaurDerpy(minitaur.Minitaur):
self._RecordInertiaInfoFromURDF()
self.ResetPose(add_constraint=True)
else:
- self._pybullet_client.resetBasePositionAndOrientation(
- self.quadruped, init_position, minitaur.INIT_ORIENTATION)
- self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
- [0, 0, 0])
+ self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
+ minitaur.INIT_ORIENTATION)
+ self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
self.ResetPose(add_constraint=False)
self._overheat_counter = np.zeros(self.num_motors)
@@ -103,68 +101,60 @@ class MinitaurDerpy(minitaur.Minitaur):
knee_angle = -2.1834
leg_position = minitaur.LEG_POSITION[leg_id]
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * knee_angle,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * knee_angle,
- targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * knee_angle,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * knee_angle,
+ targetVelocity=0)
if add_constraint:
if leg_id < 2:
self._pybullet_client.createConstraint(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_SHORT, KNEE_CONSTRAINT_POINT_LONG)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_SHORT,
+ KNEE_CONSTRAINT_POINT_LONG)
else:
self._pybullet_client.createConstraint(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_LONG, KNEE_CONSTRAINT_POINT_SHORT)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_LONG,
+ KNEE_CONSTRAINT_POINT_SHORT)
if self._accurate_motor_model_enabled or self._pd_control_enabled:
# Disable the default motor in pybullet.
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
else:
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "L_joint",
- self._motor_direction[2 * leg_id] * half_pi)
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "R_joint",
- self._motor_direction[2 * leg_id + 1] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
+ self._motor_direction[2 * leg_id] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
+ self._motor_direction[2 * leg_id + 1] * half_pi)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env.py
index 0774f1710..1008f8062 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env.py
@@ -32,10 +32,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
action to zero and the height of the robot base. It prefers a similar pose to
the signal while keeping balance.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 166
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
def __init__(self,
urdf_version=None,
@@ -101,23 +98,23 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
self._extension_offset = np.zeros(NUM_LEGS)
self._use_angular_velocity_in_observation = use_motor_angle_in_observation
self._use_motor_angle_in_observation = use_motor_angle_in_observation
- super(MinitaurFourLegStandEnv, self).__init__(
- urdf_version=urdf_version,
- control_time_step=control_time_step,
- action_repeat=action_repeat,
- remove_default_joint_damping=remove_default_joint_damping,
- accurate_motor_model_enabled=True,
- motor_overheat_protection=True,
- hard_reset=hard_reset,
- motor_kp=motor_kp,
- motor_kd=motor_kd,
- control_latency=control_latency,
- pd_latency=pd_latency,
- on_rack=on_rack,
- render=render,
- env_randomizer=env_randomizer,
- reflection = False,
- log_path=log_path)
+ super(MinitaurFourLegStandEnv,
+ self).__init__(urdf_version=urdf_version,
+ control_time_step=control_time_step,
+ action_repeat=action_repeat,
+ remove_default_joint_damping=remove_default_joint_damping,
+ accurate_motor_model_enabled=True,
+ motor_overheat_protection=True,
+ hard_reset=hard_reset,
+ motor_kp=motor_kp,
+ motor_kd=motor_kd,
+ control_latency=control_latency,
+ pd_latency=pd_latency,
+ on_rack=on_rack,
+ render=render,
+ env_randomizer=env_randomizer,
+ reflection=False,
+ log_path=log_path)
action_dim = 4
action_low = np.array([-1.0] * action_dim)
@@ -138,20 +135,17 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
init_pose = [
- INIT_SWING_POS + self._swing_offset[0],
- INIT_SWING_POS + self._swing_offset[1],
- INIT_SWING_POS + self._swing_offset[2],
- INIT_SWING_POS + self._swing_offset[3],
+ INIT_SWING_POS + self._swing_offset[0], INIT_SWING_POS + self._swing_offset[1],
+ INIT_SWING_POS + self._swing_offset[2], INIT_SWING_POS + self._swing_offset[3],
INIT_EXTENSION_POS + self._extension_offset[0],
INIT_EXTENSION_POS + self._extension_offset[1],
INIT_EXTENSION_POS + self._extension_offset[2],
INIT_EXTENSION_POS + self._extension_offset[3]
]
initial_motor_angles = self._convert_from_leg_model(init_pose)
- self._pybullet_client.resetBasePositionAndOrientation(
- 0, [0, 0, 0], [0, 0, 0, 1])
- super(MinitaurFourLegStandEnv, self).reset(
- initial_motor_angles=initial_motor_angles, reset_duration=0.5)
+ self._pybullet_client.resetBasePositionAndOrientation(0, [0, 0, 0], [0, 0, 0, 1])
+ super(MinitaurFourLegStandEnv, self).reset(initial_motor_angles=initial_motor_angles,
+ reset_duration=0.5)
return self._get_observation()
def step(self, action):
@@ -180,10 +174,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
time.sleep(time_to_sleep)
base_pos = self.minitaur.GetBasePosition()
# Keep the previous orientation of the camera set by the user.
- [yaw, pitch,
- dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
- self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch,
- base_pos)
+ [yaw, pitch, dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
+ self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, base_pos)
action = self._transform_action_to_motor_command(action)
t = self._env_step_counter % MOVING_FLOOR_TOTAL_STEP
if t == 0:
@@ -197,8 +189,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
t = float(float(t) / float(MOVING_FLOOR_TOTAL_STEP))
ori = map(operator.add, [x * (1.0 - t) for x in self._cur_ori],
[x * t for x in self._goal_ori])
- ori=list(ori)
- print("ori=",ori)
+ ori = list(ori)
+ print("ori=", ori)
self._pybullet_client.resetBasePositionAndOrientation(0, [0, 0, 0], ori)
if self._env_step_counter % PERTURBATION_TOTAL_STEP == 0:
self._perturbation_magnitude = random.uniform(0.0, 0.0)
@@ -218,8 +210,8 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
obs = self._get_true_observation()
reward = self._reward()
if self._log_path is not None:
- minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur,
- action, self._env_step_counter)
+ minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur, action,
+ self._env_step_counter)
if done:
self.minitaur.Terminate()
return np.array(self._get_observation()), reward, done, {}
@@ -228,15 +220,13 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
motor_pose = np.zeros(NUM_MOTORS)
for i in range(NUM_LEGS):
motor_pose[2 * i] = leg_pose[NUM_LEGS + i] - (-1)**(i / 2) * leg_pose[i]
- motor_pose[2 * i
- + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
+ motor_pose[2 * i + 1] = leg_pose[NUM_LEGS + i] + (-1)**(i / 2) * leg_pose[i]
return motor_pose
def _signal(self, t):
initial_pose = np.array([
- INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
- INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
- INIT_EXTENSION_POS
+ INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
+ INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
])
signal = initial_pose
return signal
@@ -268,8 +258,7 @@ class MinitaurFourLegStandEnv(minitaur_gym_env.MinitaurGymEnv):
rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation)
local_up = rot_mat[6:]
_, _, height = self.minitaur.GetBasePosition()
- local_global_up_dot_product = np.dot(
- np.asarray([0, 0, 1]), np.asarray(local_up))
+ local_global_up_dot_product = np.dot(np.asarray([0, 0, 1]), np.asarray(local_up))
return local_global_up_dot_product < 0.85 or height < 0.15
def _reward(self):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env_example.py
index c154e879a..183213fce 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_four_leg_stand_env_example.py
@@ -5,7 +5,6 @@ import numpy as np
import tensorflow as tf
from pybullet_envs.minitaur.envs import minitaur_four_leg_stand_env
-
FLAGS = tf.flags.FLAGS
tf.flags.DEFINE_string("log_path", None, "The directory to write the log file.")
NUM_LEGS = 4
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py
index 7553c33fa..44297d11b 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env.py
@@ -4,10 +4,10 @@
import math
import time
-import os, inspect
+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
from gym import spaces
@@ -64,10 +64,7 @@ class MinitaurGymEnv(gym.Env):
expenditure.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 100
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 100}
def __init__(self,
urdf_root=pybullet_data.getDataPath(),
@@ -184,17 +181,14 @@ class MinitaurGymEnv(gym.Env):
self._action_repeat = 1
self.control_time_step = self._time_step * self._action_repeat
# TODO(b/73829334): Fix the value of self._num_bullet_solver_iterations.
- self._num_bullet_solver_iterations = int(
- NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
+ self._num_bullet_solver_iterations = int(NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
self._urdf_root = urdf_root
self._self_collision_enabled = self_collision_enabled
self._motor_velocity_limit = motor_velocity_limit
self._observation = []
self._true_observation = []
self._objectives = []
- self._objective_weights = [
- distance_weight, energy_weight, drift_weight, shake_weight
- ]
+ self._objective_weights = [distance_weight, energy_weight, drift_weight, shake_weight]
self._env_step_counter = 0
self._num_steps_to_log = num_steps_to_log
self._is_render = render
@@ -226,12 +220,10 @@ class MinitaurGymEnv(gym.Env):
self._urdf_version = urdf_version
self._ground_id = None
self._reflection = reflection
- self._env_randomizers = convert_to_list(
- env_randomizer) if env_randomizer else []
+ self._env_randomizers = convert_to_list(env_randomizer) if env_randomizer else []
self._episode_proto = minitaur_logging_pb2.MinitaurEpisode()
if self._is_render:
- self._pybullet_client = bullet_client.BulletClient(
- connection_mode=pybullet.GUI)
+ self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
else:
self._pybullet_client = bullet_client.BulletClient()
if self._urdf_version is None:
@@ -249,7 +241,7 @@ class MinitaurGymEnv(gym.Env):
self._hard_reset = hard_reset # This assignment need to be after reset()
def close(self):
- if self._env_step_counter>0:
+ if self._env_step_counter > 0:
self.logging.save_episode(self._episode_proto)
self.minitaur.Terminate()
@@ -257,53 +249,48 @@ class MinitaurGymEnv(gym.Env):
self._env_randomizers.append(env_randomizer)
def reset(self, initial_motor_angles=None, reset_duration=1.0):
- self._pybullet_client.configureDebugVisualizer(
- self._pybullet_client.COV_ENABLE_RENDERING, 0)
- if self._env_step_counter>0:
+ self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_RENDERING, 0)
+ if self._env_step_counter > 0:
self.logging.save_episode(self._episode_proto)
self._episode_proto = minitaur_logging_pb2.MinitaurEpisode()
- minitaur_logging.preallocate_episode_proto(self._episode_proto,
- self._num_steps_to_log)
+ minitaur_logging.preallocate_episode_proto(self._episode_proto, self._num_steps_to_log)
if self._hard_reset:
self._pybullet_client.resetSimulation()
self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=int(self._num_bullet_solver_iterations))
self._pybullet_client.setTimeStep(self._time_step)
- self._ground_id = self._pybullet_client.loadURDF(
- "%s/plane.urdf" % self._urdf_root)
+ self._ground_id = self._pybullet_client.loadURDF("%s/plane.urdf" % self._urdf_root)
if (self._reflection):
- self._pybullet_client.changeVisualShape(self._ground_id,-1,rgbaColor=[1,1,1,0.8])
- self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION,self._ground_id)
+ self._pybullet_client.changeVisualShape(self._ground_id, -1, rgbaColor=[1, 1, 1, 0.8])
+ self._pybullet_client.configureDebugVisualizer(
+ self._pybullet_client.COV_ENABLE_PLANAR_REFLECTION, self._ground_id)
self._pybullet_client.setGravity(0, 0, -10)
acc_motor = self._accurate_motor_model_enabled
motor_protect = self._motor_overheat_protection
if self._urdf_version not in MINIATUR_URDF_VERSION_MAP:
- raise ValueError(
- "%s is not a supported urdf_version." % self._urdf_version)
+ raise ValueError("%s is not a supported urdf_version." % self._urdf_version)
else:
- self.minitaur = (
- MINIATUR_URDF_VERSION_MAP[self._urdf_version](
- pybullet_client=self._pybullet_client,
- action_repeat=self._action_repeat,
- urdf_root=self._urdf_root,
- time_step=self._time_step,
- self_collision_enabled=self._self_collision_enabled,
- motor_velocity_limit=self._motor_velocity_limit,
- pd_control_enabled=self._pd_control_enabled,
- accurate_motor_model_enabled=acc_motor,
- remove_default_joint_damping=self._remove_default_joint_damping,
- motor_kp=self._motor_kp,
- motor_kd=self._motor_kd,
- control_latency=self._control_latency,
- pd_latency=self._pd_latency,
- observation_noise_stdev=self._observation_noise_stdev,
- torque_control_enabled=self._torque_control_enabled,
- motor_overheat_protection=motor_protect,
- on_rack=self._on_rack))
- self.minitaur.Reset(
- reload_urdf=False,
- default_motor_angles=initial_motor_angles,
- reset_time=reset_duration)
+ self.minitaur = (MINIATUR_URDF_VERSION_MAP[self._urdf_version](
+ pybullet_client=self._pybullet_client,
+ action_repeat=self._action_repeat,
+ urdf_root=self._urdf_root,
+ time_step=self._time_step,
+ self_collision_enabled=self._self_collision_enabled,
+ motor_velocity_limit=self._motor_velocity_limit,
+ pd_control_enabled=self._pd_control_enabled,
+ accurate_motor_model_enabled=acc_motor,
+ remove_default_joint_damping=self._remove_default_joint_damping,
+ motor_kp=self._motor_kp,
+ motor_kd=self._motor_kd,
+ control_latency=self._control_latency,
+ pd_latency=self._pd_latency,
+ observation_noise_stdev=self._observation_noise_stdev,
+ torque_control_enabled=self._torque_control_enabled,
+ motor_overheat_protection=motor_protect,
+ on_rack=self._on_rack))
+ self.minitaur.Reset(reload_urdf=False,
+ default_motor_angles=initial_motor_angles,
+ reset_time=reset_duration)
# Loop over all env randomizers.
for env_randomizer in self._env_randomizers:
@@ -313,10 +300,9 @@ class MinitaurGymEnv(gym.Env):
self._env_step_counter = 0
self._last_base_position = [0, 0, 0]
self._objectives = []
- self._pybullet_client.resetDebugVisualizerCamera(
- self._cam_dist, self._cam_yaw, self._cam_pitch, [0, 0, 0])
- self._pybullet_client.configureDebugVisualizer(
- self._pybullet_client.COV_ENABLE_RENDERING, 1)
+ self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
+ self._cam_pitch, [0, 0, 0])
+ self._pybullet_client.configureDebugVisualizer(self._pybullet_client.COV_ENABLE_RENDERING, 1)
return self._get_observation()
def seed(self, seed=None):
@@ -328,8 +314,7 @@ class MinitaurGymEnv(gym.Env):
for i, action_component in enumerate(action):
if not (-self._action_bound - ACTION_EPS <= action_component <=
self._action_bound + ACTION_EPS):
- raise ValueError("{}th action {} out of bounds.".format(
- i, action_component))
+ raise ValueError("{}th action {} out of bounds.".format(i, action_component))
action = self.minitaur.ConvertFromLegModel(action)
return action
@@ -361,10 +346,8 @@ class MinitaurGymEnv(gym.Env):
time.sleep(time_to_sleep)
base_pos = self.minitaur.GetBasePosition()
# Keep the previous orientation of the camera set by the user.
- [yaw, pitch,
- dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
- self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch,
- base_pos)
+ [yaw, pitch, dist] = self._pybullet_client.getDebugVisualizerCamera()[8:11]
+ self._pybullet_client.resetDebugVisualizerCamera(dist, yaw, pitch, base_pos)
for env_randomizer in self._env_randomizers:
env_randomizer.randomize_step(self)
@@ -374,8 +357,8 @@ class MinitaurGymEnv(gym.Env):
reward = self._reward()
done = self._termination()
if self._log_path is not None:
- minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur,
- action, self._env_step_counter)
+ minitaur_logging.update_episode_proto(self._episode_proto, self.minitaur, action,
+ self._env_step_counter)
self._env_step_counter += 1
if done:
self.minitaur.Terminate()
@@ -392,11 +375,11 @@ class MinitaurGymEnv(gym.Env):
pitch=self._cam_pitch,
roll=0,
upAxisIndex=2)
- proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(
- fov=60,
- aspect=float(RENDER_WIDTH) / RENDER_HEIGHT,
- nearVal=0.1,
- farVal=100.0)
+ proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(fov=60,
+ aspect=float(RENDER_WIDTH) /
+ RENDER_HEIGHT,
+ nearVal=0.1,
+ farVal=100.0)
(_, _, px, _, _) = self._pybullet_client.getCameraImage(
width=RENDER_WIDTH,
height=RENDER_HEIGHT,
@@ -413,9 +396,8 @@ class MinitaurGymEnv(gym.Env):
Returns:
A numpy array of motor angles.
"""
- return np.array(
- self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:
- MOTOR_ANGLE_OBSERVATION_INDEX + NUM_MOTORS])
+ return np.array(self._observation[MOTOR_ANGLE_OBSERVATION_INDEX:MOTOR_ANGLE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_velocities(self):
"""Get the minitaur's motor velocities.
@@ -424,8 +406,8 @@ class MinitaurGymEnv(gym.Env):
A numpy array of motor velocities.
"""
return np.array(
- self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:
- MOTOR_VELOCITY_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_VELOCITY_OBSERVATION_INDEX:MOTOR_VELOCITY_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_motor_torques(self):
"""Get the minitaur's motor torques.
@@ -434,8 +416,8 @@ class MinitaurGymEnv(gym.Env):
A numpy array of motor torques.
"""
return np.array(
- self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:
- MOTOR_TORQUE_OBSERVATION_INDEX + NUM_MOTORS])
+ self._observation[MOTOR_TORQUE_OBSERVATION_INDEX:MOTOR_TORQUE_OBSERVATION_INDEX +
+ NUM_MOTORS])
def get_minitaur_base_orientation(self):
"""Get the minitaur's base orientation, represented by a quaternion.
@@ -459,8 +441,7 @@ class MinitaurGymEnv(gym.Env):
rot_mat = self._pybullet_client.getMatrixFromQuaternion(orientation)
local_up = rot_mat[6:]
pos = self.minitaur.GetBasePosition()
- return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or
- pos[2] < 0.13)
+ return (np.dot(np.asarray([0, 0, 1]), np.asarray(local_up)) < 0.85 or pos[2] < 0.13)
def _termination(self):
position = self.minitaur.GetBasePosition()
@@ -483,9 +464,7 @@ class MinitaurGymEnv(gym.Env):
np.dot(self.minitaur.GetMotorTorques(),
self.minitaur.GetMotorVelocities())) * self._time_step
objectives = [forward_reward, energy_reward, drift_reward, shake_reward]
- weighted_objectives = [
- o * w for o, w in zip(objectives, self._objective_weights)
- ]
+ weighted_objectives = [o * w for o, w in zip(objectives, self._objective_weights)]
reward = sum(weighted_objectives)
self._objectives.append(objectives)
return reward
@@ -552,10 +531,8 @@ class MinitaurGymEnv(gym.Env):
upper_bound = np.zeros(self._get_observation_dimension())
num_motors = self.minitaur.num_motors
upper_bound[0:num_motors] = math.pi # Joint angle.
- upper_bound[num_motors:2 * num_motors] = (
- motor.MOTOR_SPEED_LIMIT) # Joint velocity.
- upper_bound[2 * num_motors:3 * num_motors] = (
- motor.OBSERVED_TORQUE_LIMIT) # Joint torque.
+ upper_bound[num_motors:2 * num_motors] = (motor.MOTOR_SPEED_LIMIT) # Joint velocity.
+ upper_bound[2 * num_motors:3 * num_motors] = (motor.OBSERVED_TORQUE_LIMIT) # Joint torque.
upper_bound[3 * num_motors:] = 1.0 # Quaternion of base orientation.
return upper_bound
@@ -577,7 +554,6 @@ class MinitaurGymEnv(gym.Env):
_seed = seed
_step = step
-
def set_time_step(self, control_step, simulation_step=0.001):
"""Sets the time step of the environment.
@@ -591,18 +567,15 @@ class MinitaurGymEnv(gym.Env):
ValueError: If the control step is smaller than the simulation step.
"""
if control_step < simulation_step:
- raise ValueError(
- "Control step should be larger than or equal to simulation step.")
+ raise ValueError("Control step should be larger than or equal to simulation step.")
self.control_time_step = control_step
self._time_step = simulation_step
self._action_repeat = int(round(control_step / simulation_step))
- self._num_bullet_solver_iterations = (
- NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
+ self._num_bullet_solver_iterations = (NUM_SIMULATION_ITERATION_STEPS / self._action_repeat)
self._pybullet_client.setPhysicsEngineParameter(
numSolverIterations=self._num_bullet_solver_iterations)
self._pybullet_client.setTimeStep(self._time_step)
- self.minitaur.SetTimeSteps(
- action_repeat=self._action_repeat, simulation_step=self._time_step)
+ self.minitaur.SetTimeSteps(action_repeat=self._action_repeat, simulation_step=self._time_step)
@property
def pybullet_client(self):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env_example.py
index c05022648..8441879ad 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_gym_env_example.py
@@ -8,8 +8,8 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
-print("parentdir=",parentdir)
-os.sys.path.insert(0,parentdir)
+print("parentdir=", parentdir)
+os.sys.path.insert(0, parentdir)
import argparse
import numpy as np
@@ -17,7 +17,6 @@ import tensorflow as tf
from pybullet_envs.minitaur.envs import minitaur_gym_env
import time
-
#FLAGS = flags.FLAGS
#flags.DEFINE_enum(
# "example_name", "sine", ["sine", "reset", "stand", "overheat"],
@@ -60,7 +59,7 @@ def ResetPoseExample(log_path=None):
action = [math.pi / 2] * 8
for _ in range(steps):
_, _, done, _ = environment.step(action)
- time.sleep(1./100.)
+ time.sleep(1. / 100.)
if done:
break
@@ -104,7 +103,7 @@ def MotorOverheatExample(log_path=None):
observation, _, _, _ = environment.step(action)
current_row.extend(observation.tolist())
actions_and_observations.append(current_row)
- time.sleep(1./100.)
+ time.sleep(1. / 100.)
if FLAGS.output_filename is not None:
WriteToCSV(FLAGS.output_filename, actions_and_observations)
@@ -151,7 +150,7 @@ def SineStandExample(log_path=None):
observation, _, _, _ = environment.step(action)
current_row.extend(observation.tolist())
actions_and_observations.append(current_row)
- time.sleep(1./100.)
+ time.sleep(1. / 100.)
if FLAGS.output_filename is not None:
WriteToCSV(FLAGS.output_filename, actions_and_observations)
@@ -199,7 +198,7 @@ def SinePolicyExample(log_path=None):
a4 = math.sin(t * speed + math.pi) * amplitude2
action = [a1, a2, a2, a1, a3, a4, a4, a3]
_, reward, done, _ = environment.step(action)
- time.sleep(1./100.)
+ time.sleep(1. / 100.)
sum_reward += reward
if done:
@@ -207,14 +206,15 @@ def SinePolicyExample(log_path=None):
environment.reset()
-
-
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)
+ 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):
@@ -224,6 +224,6 @@ def main():
if (args.env == 3):
MotorOverheatExample()
-if __name__ == '__main__':
- main()
+if __name__ == '__main__':
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py
index c40594042..e8467a5ae 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging.py
@@ -10,10 +10,10 @@ from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
-import os, inspect
+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 datetime
import os
@@ -74,9 +74,8 @@ def update_episode_proto(episode_proto, minitaur, action, step):
"""
max_num_steps = len(episode_proto.state_action)
if step >= max_num_steps:
- tf.logging.warning(
- "{}th step is not recorded in the logging since only {} steps were "
- "pre-allocated.".format(step, max_num_steps))
+ tf.logging.warning("{}th step is not recorded in the logging since only {} steps were "
+ "pre-allocated.".format(step, max_num_steps))
return
step_log = episode_proto.state_action[step]
step_log.info_valid = minitaur.IsObservationValid()
@@ -95,8 +94,7 @@ def update_episode_proto(episode_proto, minitaur, action, step):
_update_base_state(step_log.base_position, minitaur.GetBasePosition())
_update_base_state(step_log.base_orientation, minitaur.GetBaseRollPitchYaw())
- _update_base_state(step_log.base_angular_vel,
- minitaur.GetBaseRollPitchYawRate())
+ _update_base_state(step_log.base_angular_vel, minitaur.GetBaseRollPitchYawRate())
class MinitaurLogging(object):
@@ -124,10 +122,8 @@ class MinitaurLogging(object):
if not tf.gfile.Exists(self._log_path):
tf.gfile.MakeDirs(self._log_path)
ts = time.time()
- time_stamp = datetime.datetime.fromtimestamp(ts).strftime(
- "%Y-%m-%d-%H%M%S")
- log_path = os.path.join(self._log_path,
- "minitaur_log_{}".format(time_stamp))
+ time_stamp = datetime.datetime.fromtimestamp(ts).strftime("%Y-%m-%d-%H%M%S")
+ log_path = os.path.join(self._log_path, "minitaur_log_{}".format(time_stamp))
with tf.gfile.Open(log_path, "w") as f:
f.write(episode_proto.SerializeToString())
return log_path
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging_pb2.py
index ff564386a..9650c4b24 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging_pb2.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_logging_pb2.py
@@ -3,12 +3,12 @@
import sys
-import os, inspect
+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)
-_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
+_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
from google.protobuf import descriptor as _descriptor
from google.protobuf import message as _message
from google.protobuf import reflection as _reflection
@@ -18,168 +18,271 @@ from google.protobuf import descriptor_pb2
_sym_db = _symbol_database.Default()
-
from pybullet_envs.minitaur.envs import timestamp_pb2 as timestamp__pb2
from pybullet_envs.minitaur.envs import vector_pb2 as vector__pb2
-
DESCRIPTOR = _descriptor.FileDescriptor(
- name='minitaur_logging.proto',
- package='robotics.reinforcement_learning.minitaur.envs',
- syntax='proto3',
- serialized_pb=_b('\n\x16minitaur_logging.proto\x12-robotics.reinforcement_learning.minitaur.envs\x1a\x0ftimestamp.proto\x1a\x0cvector.proto\"k\n\x0fMinitaurEpisode\x12X\n\x0cstate_action\x18\x01 \x03(\x0b\x32\x42.robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction\"U\n\x12MinitaurMotorState\x12\r\n\x05\x61ngle\x18\x01 \x01(\x01\x12\x10\n\x08velocity\x18\x02 \x01(\x01\x12\x0e\n\x06torque\x18\x03 \x01(\x01\x12\x0e\n\x06\x61\x63tion\x18\x04 \x01(\x01\"\xce\x02\n\x13MinitaurStateAction\x12\x12\n\ninfo_valid\x18\x06 \x01(\x08\x12(\n\x04time\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x32\n\rbase_position\x18\x02 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_orientation\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_angular_vel\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12W\n\x0cmotor_states\x18\x05 \x03(\x0b\x32\x41.robotics.reinforcement_learning.minitaur.envs.MinitaurMotorStateb\x06proto3')
- ,
- dependencies=[timestamp__pb2.DESCRIPTOR,vector__pb2.DESCRIPTOR,])
-
-
-
+ name='minitaur_logging.proto',
+ package='robotics.reinforcement_learning.minitaur.envs',
+ syntax='proto3',
+ serialized_pb=_b(
+ '\n\x16minitaur_logging.proto\x12-robotics.reinforcement_learning.minitaur.envs\x1a\x0ftimestamp.proto\x1a\x0cvector.proto\"k\n\x0fMinitaurEpisode\x12X\n\x0cstate_action\x18\x01 \x03(\x0b\x32\x42.robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction\"U\n\x12MinitaurMotorState\x12\r\n\x05\x61ngle\x18\x01 \x01(\x01\x12\x10\n\x08velocity\x18\x02 \x01(\x01\x12\x0e\n\x06torque\x18\x03 \x01(\x01\x12\x0e\n\x06\x61\x63tion\x18\x04 \x01(\x01\"\xce\x02\n\x13MinitaurStateAction\x12\x12\n\ninfo_valid\x18\x06 \x01(\x08\x12(\n\x04time\x18\x01 \x01(\x0b\x32\x1a.google.protobuf.Timestamp\x12\x32\n\rbase_position\x18\x02 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_orientation\x18\x03 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12\x35\n\x10\x62\x61se_angular_vel\x18\x04 \x01(\x0b\x32\x1b.robotics.messages.Vector3d\x12W\n\x0cmotor_states\x18\x05 \x03(\x0b\x32\x41.robotics.reinforcement_learning.minitaur.envs.MinitaurMotorStateb\x06proto3'
+ ),
+ dependencies=[
+ timestamp__pb2.DESCRIPTOR,
+ vector__pb2.DESCRIPTOR,
+ ])
_MINITAUREPISODE = _descriptor.Descriptor(
- name='MinitaurEpisode',
- full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='state_action', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode.state_action', index=0,
- number=1, type=11, cpp_type=10, label=3,
- has_default_value=False, default_value=[],
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=104,
- serialized_end=211,
+ name='MinitaurEpisode',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(
+ name='state_action',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode.state_action',
+ index=0,
+ number=1,
+ type=11,
+ cpp_type=10,
+ label=3,
+ has_default_value=False,
+ default_value=[],
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=104,
+ serialized_end=211,
)
-
_MINITAURMOTORSTATE = _descriptor.Descriptor(
- name='MinitaurMotorState',
- full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='angle', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.angle', index=0,
- number=1, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='velocity', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.velocity', index=1,
- number=2, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='torque', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.torque', index=2,
- number=3, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='action', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.action', index=3,
- number=4, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=213,
- serialized_end=298,
+ name='MinitaurMotorState',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(
+ name='angle',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.angle',
+ index=0,
+ number=1,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='velocity',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.velocity',
+ index=1,
+ number=2,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='torque',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.torque',
+ index=2,
+ number=3,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='action',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState.action',
+ index=3,
+ number=4,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=213,
+ serialized_end=298,
)
-
_MINITAURSTATEACTION = _descriptor.Descriptor(
- name='MinitaurStateAction',
- full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='info_valid', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.info_valid', index=0,
- number=6, type=8, cpp_type=7, label=1,
- has_default_value=False, default_value=False,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='time', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.time', index=1,
- number=1, type=11, cpp_type=10, label=1,
- has_default_value=False, default_value=None,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='base_position', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_position', index=2,
- number=2, type=11, cpp_type=10, label=1,
- has_default_value=False, default_value=None,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='base_orientation', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_orientation', index=3,
- number=3, type=11, cpp_type=10, label=1,
- has_default_value=False, default_value=None,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='base_angular_vel', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_angular_vel', index=4,
- number=4, type=11, cpp_type=10, label=1,
- has_default_value=False, default_value=None,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='motor_states', full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.motor_states', index=5,
- number=5, type=11, cpp_type=10, label=3,
- has_default_value=False, default_value=[],
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=301,
- serialized_end=635,
+ name='MinitaurStateAction',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(
+ name='info_valid',
+ full_name=
+ 'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.info_valid',
+ index=0,
+ number=6,
+ type=8,
+ cpp_type=7,
+ label=1,
+ has_default_value=False,
+ default_value=False,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='time',
+ full_name='robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.time',
+ index=1,
+ number=1,
+ type=11,
+ cpp_type=10,
+ label=1,
+ has_default_value=False,
+ default_value=None,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='base_position',
+ full_name=
+ 'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_position',
+ index=2,
+ number=2,
+ type=11,
+ cpp_type=10,
+ label=1,
+ has_default_value=False,
+ default_value=None,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='base_orientation',
+ full_name=
+ 'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_orientation',
+ index=3,
+ number=3,
+ type=11,
+ cpp_type=10,
+ label=1,
+ has_default_value=False,
+ default_value=None,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='base_angular_vel',
+ full_name=
+ 'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.base_angular_vel',
+ index=4,
+ number=4,
+ type=11,
+ cpp_type=10,
+ label=1,
+ has_default_value=False,
+ default_value=None,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(
+ name='motor_states',
+ full_name=
+ 'robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction.motor_states',
+ index=5,
+ number=5,
+ type=11,
+ cpp_type=10,
+ label=3,
+ has_default_value=False,
+ default_value=[],
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=301,
+ serialized_end=635,
)
_MINITAUREPISODE.fields_by_name['state_action'].message_type = _MINITAURSTATEACTION
@@ -193,26 +296,34 @@ DESCRIPTOR.message_types_by_name['MinitaurMotorState'] = _MINITAURMOTORSTATE
DESCRIPTOR.message_types_by_name['MinitaurStateAction'] = _MINITAURSTATEACTION
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
-MinitaurEpisode = _reflection.GeneratedProtocolMessageType('MinitaurEpisode', (_message.Message,), dict(
- DESCRIPTOR = _MINITAUREPISODE,
- __module__ = 'minitaur_logging_pb2'
- # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode)
- ))
+MinitaurEpisode = _reflection.GeneratedProtocolMessageType(
+ 'MinitaurEpisode',
+ (_message.Message,),
+ dict(
+ DESCRIPTOR=_MINITAUREPISODE,
+ __module__='minitaur_logging_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurEpisode)
+ ))
_sym_db.RegisterMessage(MinitaurEpisode)
-MinitaurMotorState = _reflection.GeneratedProtocolMessageType('MinitaurMotorState', (_message.Message,), dict(
- DESCRIPTOR = _MINITAURMOTORSTATE,
- __module__ = 'minitaur_logging_pb2'
- # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState)
- ))
+MinitaurMotorState = _reflection.GeneratedProtocolMessageType(
+ 'MinitaurMotorState',
+ (_message.Message,),
+ dict(
+ DESCRIPTOR=_MINITAURMOTORSTATE,
+ __module__='minitaur_logging_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurMotorState)
+ ))
_sym_db.RegisterMessage(MinitaurMotorState)
-MinitaurStateAction = _reflection.GeneratedProtocolMessageType('MinitaurStateAction', (_message.Message,), dict(
- DESCRIPTOR = _MINITAURSTATEACTION,
- __module__ = 'minitaur_logging_pb2'
- # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction)
- ))
+MinitaurStateAction = _reflection.GeneratedProtocolMessageType(
+ 'MinitaurStateAction',
+ (_message.Message,),
+ dict(
+ DESCRIPTOR=_MINITAURSTATEACTION,
+ __module__='minitaur_logging_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.reinforcement_learning.minitaur.envs.MinitaurStateAction)
+ ))
_sym_db.RegisterMessage(MinitaurStateAction)
-
# @@protoc_insertion_point(module_scope)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_proto_dump_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_proto_dump_example.py
index ca0534ad5..f194eb268 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_proto_dump_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_proto_dump_example.py
@@ -15,13 +15,13 @@ fields = episode.ListFields()
recs = []
for rec in fields[0][1]:
- #print(rec.time)
- for motorState in rec.motor_states:
- #print("motorState.angle=",motorState.angle)
- #print("motorState.velocity=",motorState.velocity)
- #print("motorState.action=",motorState.action)
- #print("motorState.torque=",motorState.torque)
- recs.append([motorState.angle,motorState.velocity,motorState.action,motorState.torque])
-
+ #print(rec.time)
+ for motorState in rec.motor_states:
+ #print("motorState.angle=",motorState.angle)
+ #print("motorState.velocity=",motorState.velocity)
+ #print("motorState.action=",motorState.action)
+ #print("motorState.torque=",motorState.torque)
+ recs.append([motorState.angle, motorState.velocity, motorState.action, motorState.torque])
+
a = numpy.array(recs)
-numpy.savetxt("motorq_qdot_action_torque.csv", a, delimiter=",") \ No newline at end of file
+numpy.savetxt("motorq_qdot_action_torque.csv", a, delimiter=",")
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller.py
index dcecf26a6..7fb43cbca 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller.py
@@ -17,8 +17,8 @@ DIAGONAL_LEG_PAIR_2 = (1, 2)
class BehaviorParameters(
collections.namedtuple("BehaviorParameters", [
- "stance_duration", "desired_forward_speed", "turning_speed",
- "standing_height", "desired_incline_angle"
+ "stance_duration", "desired_forward_speed", "turning_speed", "standing_height",
+ "desired_incline_angle"
])):
__slots__ = ()
@@ -28,18 +28,16 @@ class BehaviorParameters(
turning_speed=0,
standing_height=0.21,
desired_incline_angle=0):
- return super(BehaviorParameters, cls).__new__(
- cls, stance_duration, desired_forward_speed, turning_speed,
- standing_height, desired_incline_angle)
+ return super(BehaviorParameters,
+ cls).__new__(cls, stance_duration, desired_forward_speed, turning_speed,
+ standing_height, desired_incline_angle)
def motor_angles_to_leg_pose(motor_angles):
leg_pose = np.zeros(_NUM_MOTORS)
for i in range(_NUM_LEGS):
- leg_pose[i] = 0.5 * (-1)**(i // 2) * (
- motor_angles[2 * i + 1] - motor_angles[2 * i])
- leg_pose[_NUM_LEGS + i] = 0.5 * (
- motor_angles[2 * i] + motor_angles[2 * i + 1])
+ leg_pose[i] = 0.5 * (-1)**(i // 2) * (motor_angles[2 * i + 1] - motor_angles[2 * i])
+ leg_pose[_NUM_LEGS + i] = 0.5 * (motor_angles[2 * i] + motor_angles[2 * i + 1])
return leg_pose
@@ -47,8 +45,7 @@ def leg_pose_to_motor_angles(leg_pose):
motor_pose = np.zeros(_NUM_MOTORS)
for i in range(_NUM_LEGS):
motor_pose[2 * i] = leg_pose[_NUM_LEGS + i] - (-1)**(i // 2) * leg_pose[i]
- motor_pose[2 * i + 1] = (
- leg_pose[_NUM_LEGS + i] + (-1)**(i // 2) * leg_pose[i])
+ motor_pose[2 * i + 1] = (leg_pose[_NUM_LEGS + i] + (-1)**(i // 2) * leg_pose[i])
return motor_pose
@@ -85,8 +82,7 @@ def foot_position_to_leg_pose(foot_position):
ext = math.acos(cos_ext)
hip_toe = math.sqrt(hip_toe_sqr)
- cos_theta = (hip_toe_sqr + hip_ankle_sqr -
- (l3 - l2)**2) / (2 * hip_ankle * hip_toe)
+ cos_theta = (hip_toe_sqr + hip_ankle_sqr - (l3 - l2)**2) / (2 * hip_ankle * hip_toe)
assert cos_theta > 0
theta = math.acos(cos_theta)
@@ -94,8 +90,7 @@ def foot_position_to_leg_pose(foot_position):
return (-sw, ext)
-def foot_horizontal_position_to_leg_swing(foot_horizontal_position,
- leg_extension):
+def foot_horizontal_position_to_leg_swing(foot_horizontal_position, leg_extension):
"""Computes the target leg swing.
Sometimes it is more convenient to plan in the hybrid space.
@@ -119,8 +114,7 @@ def foot_horizontal_position_to_leg_swing(foot_horizontal_position,
# Cap the foot horizontal (projected) position so the target leg pose is
# always feasible.
- foot_position = max(
- min(toe_hip_len * 0.8, foot_horizontal_position), -toe_hip_len * 0.5)
+ foot_position = max(min(toe_hip_len * 0.8, foot_horizontal_position), -toe_hip_len * 0.5)
sw_and_theta = math.asin(foot_position / toe_hip_len)
@@ -171,9 +165,7 @@ def generate_swing_trajectory(phase, init_pose, end_pose):
b = (phi * phi * delta_2 - delta_1) / delta_p
- delta = (
- a * normalized_phase * normalized_phase + b * normalized_phase +
- init_delta)
+ delta = (a * normalized_phase * normalized_phase + b * normalized_phase + init_delta)
l1 = _UPPER_LEG_LEN
l2 = _LOWER_SHORT_LEG_LEN
@@ -209,10 +201,9 @@ class RaibertSwingLegController(object):
leg_pose_set = []
for i in raibiert_controller.swing_set:
target_foot_horizontal_position = (
- raibiert_controller.behavior_parameters.stance_duration / 2 *
- current_speed + self._speed_gain *
- (current_speed -
- raibiert_controller.behavior_parameters.desired_forward_speed))
+ raibiert_controller.behavior_parameters.stance_duration / 2 * current_speed +
+ self._speed_gain *
+ (current_speed - raibiert_controller.behavior_parameters.desired_forward_speed))
# Use the swing phase [0, 1] to track the foot. The idea is
# straightforward:
@@ -221,19 +212,19 @@ class RaibertSwingLegController(object):
# 3) Find the next leg pose on the curve based on how much time left.
# 1) Convert the target foot
- target_leg_extension = (
- raibiert_controller.nominal_leg_extension -
- self._leg_extension_clearance)
- target_leg_swing = foot_horizontal_position_to_leg_swing(
- target_foot_horizontal_position, leg_extension=target_leg_extension)
+ target_leg_extension = (raibiert_controller.nominal_leg_extension -
+ self._leg_extension_clearance)
+ target_leg_swing = foot_horizontal_position_to_leg_swing(target_foot_horizontal_position,
+ leg_extension=target_leg_extension)
target_leg_pose = (target_leg_swing, target_leg_extension)
# 2) Generates the curve from the current leg pose to the target leg pose.
# and Find the next leg pose on the curve based on current swing phase.
- desired_leg_pose = self._leg_trajectory_generator(
- phase, raibiert_controller.swing_start_leg_pose, target_leg_pose)
+ desired_leg_pose = self._leg_trajectory_generator(phase,
+ raibiert_controller.swing_start_leg_pose,
+ target_leg_pose)
leg_pose_set.append(desired_leg_pose)
@@ -244,9 +235,7 @@ class RaibertSwingLegController(object):
class RaibertStanceLegController(object):
- def __init__(self,
- speed_gain=0.1,
- leg_trajectory_generator=generate_stance_trajectory):
+ def __init__(self, speed_gain=0.1, leg_trajectory_generator=generate_stance_trajectory):
self._speed_gain = speed_gain
self._leg_trajectory_generator = leg_trajectory_generator
@@ -255,20 +244,18 @@ class RaibertStanceLegController(object):
current_speed = raibiert_controller.estimate_base_velocity()
leg_pose_set = []
for i in raibiert_controller.stance_set:
- desired_forward_speed = (
- raibiert_controller.behavior_parameters.desired_forward_speed)
- target_foot_position = -(
- raibiert_controller.behavior_parameters.stance_duration / 2 *
- current_speed - self._speed_gain *
- (current_speed - desired_forward_speed))
+ desired_forward_speed = (raibiert_controller.behavior_parameters.desired_forward_speed)
+ target_foot_position = -(raibiert_controller.behavior_parameters.stance_duration / 2 *
+ current_speed - self._speed_gain *
+ (current_speed - desired_forward_speed))
target_leg_pose = (foot_horizontal_position_to_leg_swing(
- target_foot_position,
- leg_extension=raibiert_controller.nominal_leg_extension),
+ target_foot_position, leg_extension=raibiert_controller.nominal_leg_extension),
raibiert_controller.nominal_leg_extension)
- desired_leg_pose = self._leg_trajectory_generator(
- phase, raibiert_controller.stance_start_leg_pose, target_leg_pose)
+ desired_leg_pose = self._leg_trajectory_generator(phase,
+ raibiert_controller.stance_start_leg_pose,
+ target_leg_pose)
leg_pose_set.append(desired_leg_pose)
@@ -288,8 +275,7 @@ class MinitaurRaibertTrottingController(object):
self._robot = robot
self._behavior_parameters = behavior_parameters
- nominal_leg_pose = foot_position_to_leg_pose(
- (0, -self._behavior_parameters.standing_height))
+ nominal_leg_pose = foot_position_to_leg_pose((0, -self._behavior_parameters.standing_height))
self._nominal_leg_extension = nominal_leg_pose[1]
self._swing_leg_controller = swing_leg_controller
@@ -337,8 +323,7 @@ class MinitaurRaibertTrottingController(object):
# extract the swing leg pose from the current_leg_pose
leg_pose = []
for index in leg_indices:
- leg_pose.append(
- [current_leg_pose[index], current_leg_pose[index + _NUM_LEGS]])
+ leg_pose.append([current_leg_pose[index], current_leg_pose[index + _NUM_LEGS]])
leg_pose = np.array(leg_pose)
return np.mean(leg_pose, axis=0)
@@ -353,13 +338,13 @@ class MinitaurRaibertTrottingController(object):
def get_phase(self):
"""Compute the current stance/swing phase."""
- return math.fmod(self._time, self._behavior_parameters.stance_duration
- ) / self._behavior_parameters.stance_duration
+ return math.fmod(
+ self._time,
+ self._behavior_parameters.stance_duration) / self._behavior_parameters.stance_duration
def update_swing_stance_set(self):
"""Switch the set of swing/stance legs based on timing."""
- swing_stance_phase = math.fmod(
- self._time, 2 * self._behavior_parameters.stance_duration)
+ swing_stance_phase = math.fmod(self._time, 2 * self._behavior_parameters.stance_duration)
if swing_stance_phase < self._behavior_parameters.stance_duration:
return (DIAGONAL_LEG_PAIR_1, DIAGONAL_LEG_PAIR_2)
return (DIAGONAL_LEG_PAIR_2, DIAGONAL_LEG_PAIR_1)
@@ -387,8 +372,8 @@ class MinitaurRaibertTrottingController(object):
toe_hip_len = math.sqrt(x**2 + y**2)
horizontal_dist = toe_hip_len * delta_sw
phase = self.get_phase()
- speed = 0 if phase < 0.1 else horizontal_dist / (
- self._behavior_parameters.stance_duration * phase)
+ speed = 0 if phase < 0.1 else horizontal_dist / (self._behavior_parameters.stance_duration *
+ phase)
return speed
def get_swing_leg_action(self):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller_example.py
index 87958dde5..8adeee376 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_raibert_controller_example.py
@@ -1,6 +1,5 @@
#The example to run the raibert controller in a Minitaur gym env.
-
from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
@@ -9,8 +8,7 @@ import os
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
-os.sys.path.insert(0,parentdir)
-
+os.sys.path.insert(0, parentdir)
import tensorflow as tf
from pybullet_envs.minitaur.envs import minitaur_raibert_controller
@@ -21,9 +19,8 @@ FLAGS = tf.app.flags.FLAGS
flags.DEFINE_float("motor_kp", 1.0, "The position gain of the motor.")
flags.DEFINE_float("motor_kd", 0.015, "The speed gain of the motor.")
-flags.DEFINE_float(
- "control_latency", 0.02, "The latency between sensor measurement and action"
- " execution the robot.")
+flags.DEFINE_float("control_latency", 0.02, "The latency between sensor measurement and action"
+ " execution the robot.")
flags.DEFINE_string("log_path", None, "The directory to write the log file.")
@@ -55,20 +52,18 @@ def main(argv):
log_path=FLAGS.log_path)
env.reset()
- controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(
- env.minitaur)
+ controller = minitaur_raibert_controller.MinitaurRaibertTrottingController(env.minitaur)
tstart = env.minitaur.GetTimeSinceReset()
for _ in range(1000):
t = env.minitaur.GetTimeSinceReset() - tstart
- controller.behavior_parameters = (
- minitaur_raibert_controller.BehaviorParameters(
- desired_forward_speed=speed(t)))
+ controller.behavior_parameters = (minitaur_raibert_controller.BehaviorParameters(
+ desired_forward_speed=speed(t)))
controller.update(t)
env.step(controller.get_action())
finally:
env.close()
+
if __name__ == "__main__":
tf.app.run(main)
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_rainbow_dash.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_rainbow_dash.py
index c33b4af77..d1787ea35 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_rainbow_dash.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_rainbow_dash.py
@@ -4,10 +4,10 @@ It is the result of first pass system identification for the rainbow dash robot.
"""
-import os, inspect
+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 math
@@ -46,13 +46,12 @@ class MinitaurRainbowDash(minitaur.Minitaur):
"%s/quadruped/minitaur_rainbow_dash.urdf" % self._urdf_root,
init_position,
useFixedBase=self._on_rack,
- flags=(
- self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
+ flags=(self._pybullet_client.URDF_USE_SELF_COLLISION_EXCLUDE_PARENT))
else:
- self.quadruped = self._pybullet_client.loadURDF(
- "%s/quadruped/minitaur_rainbow_dash.urdf" % self._urdf_root,
- init_position,
- useFixedBase=self._on_rack)
+ self.quadruped = self._pybullet_client.loadURDF("%s/quadruped/minitaur_rainbow_dash.urdf" %
+ self._urdf_root,
+ init_position,
+ useFixedBase=self._on_rack)
self._BuildJointNameToIdDict()
self._BuildUrdfIds()
if self._remove_default_joint_damping:
@@ -62,10 +61,9 @@ class MinitaurRainbowDash(minitaur.Minitaur):
self._RecordInertiaInfoFromURDF()
self.ResetPose(add_constraint=True)
else:
- self._pybullet_client.resetBasePositionAndOrientation(
- self.quadruped, init_position, minitaur.INIT_ORIENTATION)
- self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0],
- [0, 0, 0])
+ self._pybullet_client.resetBasePositionAndOrientation(self.quadruped, init_position,
+ minitaur.INIT_ORIENTATION)
+ self._pybullet_client.resetBaseVelocity(self.quadruped, [0, 0, 0], [0, 0, 0])
self.ResetPose(add_constraint=False)
self._overheat_counter = np.zeros(self.num_motors)
@@ -103,68 +101,60 @@ class MinitaurRainbowDash(minitaur.Minitaur):
knee_angle = -2.1834
leg_position = minitaur.LEG_POSITION[leg_id]
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._motor_direction[2 * leg_id] * knee_angle,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["motor_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * half_pi,
- targetVelocity=0)
- self._pybullet_client.resetJointState(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self._motor_direction[2 * leg_id + 1] * knee_angle,
- targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "L_joint"],
+ self._motor_direction[2 * leg_id] * knee_angle,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["motor_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * half_pi,
+ targetVelocity=0)
+ self._pybullet_client.resetJointState(self.quadruped,
+ self._joint_name_to_id["knee_" + leg_position +
+ "R_joint"],
+ self._motor_direction[2 * leg_id + 1] * knee_angle,
+ targetVelocity=0)
if add_constraint:
if leg_id < 2:
self._pybullet_client.createConstraint(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_SHORT, KNEE_CONSTRAINT_POINT_LONG)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_SHORT,
+ KNEE_CONSTRAINT_POINT_LONG)
else:
self._pybullet_client.createConstraint(
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "R_joint"],
- self.quadruped,
- self._joint_name_to_id["knee_" + leg_position + "L_joint"],
- self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0],
- KNEE_CONSTRAINT_POINT_LONG, KNEE_CONSTRAINT_POINT_SHORT)
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "R_joint"],
+ self.quadruped, self._joint_name_to_id["knee_" + leg_position + "L_joint"],
+ self._pybullet_client.JOINT_POINT2POINT, [0, 0, 0], KNEE_CONSTRAINT_POINT_LONG,
+ KNEE_CONSTRAINT_POINT_SHORT)
if self._accurate_motor_model_enabled or self._pd_control_enabled:
# Disable the default motor in pybullet.
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "L_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
- jointIndex=(
- self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
+ jointIndex=(self._joint_name_to_id["motor_" + leg_position + "R_joint"]),
controlMode=self._pybullet_client.VELOCITY_CONTROL,
targetVelocity=0,
force=knee_friction_force)
else:
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "L_joint",
- self._motor_direction[2 * leg_id] * half_pi)
- self._SetDesiredMotorAngleByName(
- "motor_" + leg_position + "R_joint",
- self._motor_direction[2 * leg_id + 1] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "L_joint",
+ self._motor_direction[2 * leg_id] * half_pi)
+ self._SetDesiredMotorAngleByName("motor_" + leg_position + "R_joint",
+ self._motor_direction[2 * leg_id + 1] * half_pi)
self._pybullet_client.setJointMotorControl2(
bodyIndex=self.quadruped,
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env.py
index 540965a2f..a9492f309 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env.py
@@ -42,20 +42,17 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
fileName=terrain_file_name,
flags=1,
meshScale=[0.5, 0.5, 0.5])
- self._pybullet_client.createMultiBody(terrain_mass,
- terrain_collision_shape_id,
- terrain_visual_shape_id,
- terrain_position,
+ self._pybullet_client.createMultiBody(terrain_mass, terrain_collision_shape_id,
+ terrain_visual_shape_id, terrain_position,
terrain_orientation)
self._pybullet_client.setGravity(0, 0, -10)
- self.minitaur = (minitaur.Minitaur(
- pybullet_client=self._pybullet_client,
- urdf_root=self._urdf_root,
- time_step=self._time_step,
- self_collision_enabled=self._self_collision_enabled,
- motor_velocity_limit=self._motor_velocity_limit,
- pd_control_enabled=self._pd_control_enabled,
- on_rack=self._on_rack))
+ self.minitaur = (minitaur.Minitaur(pybullet_client=self._pybullet_client,
+ urdf_root=self._urdf_root,
+ time_step=self._time_step,
+ self_collision_enabled=self._self_collision_enabled,
+ motor_velocity_limit=self._motor_velocity_limit,
+ pd_control_enabled=self._pd_control_enabled,
+ on_rack=self._on_rack))
self._last_base_position = [0, 0, 0]
for _ in xrange(100):
if self._pd_control_enabled:
@@ -78,6 +75,5 @@ class MinitaurRandomizeTerrainGymEnv(minitaur_gym_env.MinitaurGymEnv):
asset_source = os.path.join(terrain_dir, terrain_file_name)
asset_destination = os.path.join(FLAGS.storage_dir, terrain_file_name)
gfile.Copy(asset_source, asset_destination, overwrite=True)
- terrain_file_name_complete = os.path.join(FLAGS.storage_dir,
- terrain_file_name)
+ terrain_file_name_complete = os.path.join(FLAGS.storage_dir, terrain_file_name)
return terrain_file_name_complete
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env_example.py
index 0e5638790..3ecf6dc9c 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_randomize_terrain_gym_env_example.py
@@ -21,10 +21,7 @@ def ResetTerrainExample():
num_reset = 10
steps = 100
env = minitaur_randomize_terrain_gym_env.MinitaurRandomizeTerrainGymEnv(
- render=True,
- leg_model_enabled=False,
- motor_velocity_limit=np.inf,
- pd_control_enabled=True)
+ render=True, leg_model_enabled=False, motor_velocity_limit=np.inf, pd_control_enabled=True)
action = [math.pi / 2] * 8
for _ in xrange(num_reset):
env.reset()
@@ -37,10 +34,7 @@ def ResetTerrainExample():
def SinePolicyExample():
"""An example of minitaur walking with a sine gait."""
env = minitaur_randomize_terrain_gym_env.MinitaurRandomizeTerrainGymEnv(
- render=True,
- motor_velocity_limit=np.inf,
- pd_control_enabled=True,
- on_rack=False)
+ render=True, motor_velocity_limit=np.inf, pd_control_enabled=True, on_rack=False)
sum_reward = 0
steps = 200
amplitude_1_bound = 0.5
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env.py
index 8ae8314f0..7f899cb4a 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env.py
@@ -2,10 +2,10 @@
"""
-import os, inspect
+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 collections
import math
@@ -19,8 +19,7 @@ NUM_LEGS = 4
NUM_MOTORS = 2 * NUM_LEGS
MinitaurPose = collections.namedtuple(
- "MinitaurPose",
- "swing_angle_1, swing_angle_2, swing_angle_3, swing_angle_4, "
+ "MinitaurPose", "swing_angle_1, swing_angle_2, swing_angle_3, swing_angle_4, "
"extension_angle_1, extension_angle_2, extension_angle_3, "
"extension_angle_4")
@@ -35,10 +34,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
expenditure.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 166
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
def __init__(self,
urdf_version=None,
@@ -96,24 +92,24 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
"""
self._use_angle_in_observation = use_angle_in_observation
- super(MinitaurReactiveEnv, self).__init__(
- urdf_version=urdf_version,
- energy_weight=energy_weight,
- accurate_motor_model_enabled=accurate_motor_model_enabled,
- motor_overheat_protection=True,
- motor_kp=motor_kp,
- motor_kd=motor_kd,
- remove_default_joint_damping=remove_default_joint_damping,
- control_latency=control_latency,
- pd_latency=pd_latency,
- on_rack=on_rack,
- render=render,
- hard_reset=hard_reset,
- num_steps_to_log=num_steps_to_log,
- env_randomizer=env_randomizer,
- log_path=log_path,
- control_time_step=control_time_step,
- action_repeat=action_repeat)
+ super(MinitaurReactiveEnv,
+ self).__init__(urdf_version=urdf_version,
+ energy_weight=energy_weight,
+ accurate_motor_model_enabled=accurate_motor_model_enabled,
+ motor_overheat_protection=True,
+ motor_kp=motor_kp,
+ motor_kd=motor_kd,
+ remove_default_joint_damping=remove_default_joint_damping,
+ control_latency=control_latency,
+ pd_latency=pd_latency,
+ on_rack=on_rack,
+ render=render,
+ hard_reset=hard_reset,
+ num_steps_to_log=num_steps_to_log,
+ env_randomizer=env_randomizer,
+ log_path=log_path,
+ control_time_step=control_time_step,
+ action_repeat=action_repeat)
action_dim = 8
action_low = np.array([-0.5] * action_dim)
@@ -126,34 +122,31 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
def reset(self):
# TODO(b/73666007): Use composition instead of inheritance.
# (http://go/design-for-testability-no-inheritance).
- init_pose = MinitaurPose(
- swing_angle_1=INIT_SWING_POS,
- swing_angle_2=INIT_SWING_POS,
- swing_angle_3=INIT_SWING_POS,
- swing_angle_4=INIT_SWING_POS,
- extension_angle_1=INIT_EXTENSION_POS,
- extension_angle_2=INIT_EXTENSION_POS,
- extension_angle_3=INIT_EXTENSION_POS,
- extension_angle_4=INIT_EXTENSION_POS)
+ init_pose = MinitaurPose(swing_angle_1=INIT_SWING_POS,
+ swing_angle_2=INIT_SWING_POS,
+ swing_angle_3=INIT_SWING_POS,
+ swing_angle_4=INIT_SWING_POS,
+ extension_angle_1=INIT_EXTENSION_POS,
+ extension_angle_2=INIT_EXTENSION_POS,
+ extension_angle_3=INIT_EXTENSION_POS,
+ extension_angle_4=INIT_EXTENSION_POS)
# TODO(b/73734502): Refactor input of _convert_from_leg_model to namedtuple.
initial_motor_angles = self._convert_from_leg_model(list(init_pose))
- super(MinitaurReactiveEnv, self).reset(
- initial_motor_angles=initial_motor_angles, reset_duration=0.5)
+ super(MinitaurReactiveEnv, self).reset(initial_motor_angles=initial_motor_angles,
+ reset_duration=0.5)
return self._get_observation()
def _convert_from_leg_model(self, leg_pose):
motor_pose = np.zeros(NUM_MOTORS)
for i in range(NUM_LEGS):
motor_pose[int(2 * i)] = leg_pose[NUM_LEGS + i] - (-1)**int(i / 2) * leg_pose[i]
- motor_pose[int(2 * i + 1)] = (
- leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i])
+ motor_pose[int(2 * i + 1)] = (leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i])
return motor_pose
def _signal(self, t):
initial_pose = np.array([
- INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS,
- INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS,
- INIT_EXTENSION_POS
+ INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_SWING_POS, INIT_EXTENSION_POS,
+ INIT_EXTENSION_POS, INIT_EXTENSION_POS, INIT_EXTENSION_POS
])
return initial_pose
@@ -214,8 +207,7 @@ class MinitaurReactiveEnv(minitaur_gym_env.MinitaurGymEnv):
upper_bound_pitch_dot = 2 * math.pi / self._time_step
upper_bound_motor_angle = 2 * math.pi
upper_bound = [
- upper_bound_roll, upper_bound_pitch, upper_bound_roll_dot,
- upper_bound_pitch_dot
+ upper_bound_roll, upper_bound_pitch, upper_bound_roll_dot, upper_bound_pitch_dot
]
if self._use_angle_in_observation:
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env_example.py
index 2c2be7106..e0d4000c1 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_reactive_env_example.py
@@ -10,17 +10,14 @@ import time
import inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(os.path.dirname(os.path.dirname(currentdir)))
-print("parentdir=",parentdir)
-os.sys.path.insert(0,parentdir)
-
-
+print("parentdir=", parentdir)
+os.sys.path.insert(0, parentdir)
import tensorflow as tf
from pybullet_envs.minitaur.agents.scripts import utility
import pybullet_data
from pybullet_envs.minitaur.envs import simple_ppo_agent
-
flags = tf.app.flags
FLAGS = tf.app.flags.FLAGS
LOG_DIR = os.path.join(pybullet_data.getDataPath(), "policies/ppo/minitaur_reactive_env")
@@ -36,13 +33,12 @@ def main(argv):
network = config.network
with tf.Session() as sess:
- agent = simple_ppo_agent.SimplePPOPolicy(
- sess,
- env,
- network,
- policy_layers=policy_layers,
- value_layers=value_layers,
- checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
+ agent = simple_ppo_agent.SimplePPOPolicy(sess,
+ env,
+ network,
+ policy_layers=policy_layers,
+ value_layers=value_layers,
+ checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
sum_reward = 0
observation = env.reset()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env.py
index 3ea1b2e09..8135b7265 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env.py
@@ -29,10 +29,7 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
function is based on how long the minitaur stays standing up.
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 50
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
def __init__(self,
urdf_root=pybullet_data.getDataPath(),
@@ -53,16 +50,15 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
pd_control_enabled: Whether to use PD controller for each motor.
render: Whether to render the simulation.
"""
- super(MinitaurStandGymEnv, self).__init__(
- urdf_root=urdf_root,
- action_repeat=action_repeat,
- observation_noise_stdev=observation_noise_stdev,
- self_collision_enabled=self_collision_enabled,
- motor_velocity_limit=motor_velocity_limit,
- pd_control_enabled=pd_control_enabled,
- accurate_motor_model_enabled=True,
- motor_overheat_protection=True,
- render=render)
+ super(MinitaurStandGymEnv, self).__init__(urdf_root=urdf_root,
+ action_repeat=action_repeat,
+ observation_noise_stdev=observation_noise_stdev,
+ self_collision_enabled=self_collision_enabled,
+ motor_velocity_limit=motor_velocity_limit,
+ pd_control_enabled=pd_control_enabled,
+ accurate_motor_model_enabled=True,
+ motor_overheat_protection=True,
+ render=render)
# Set the action dimension to 1, and reset the action space.
action_dim = 1
action_high = np.array([self._action_bound] * action_dim)
@@ -85,8 +81,8 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
for t in range(5000):
if self._is_render:
base_pos = self.minitaur.GetBasePosition()
- self._pybullet_client.resetDebugVisualizerCamera(
- self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
+ self._pybullet_client.resetDebugVisualizerCamera(self._cam_dist, self._cam_yaw,
+ self._cam_pitch, base_pos)
state = self._get_true_observation()
action = self._policy_flip(t, state[24:28])
self.minitaur.ApplyAction(action)
@@ -226,8 +222,7 @@ class MinitaurStandGymEnv(minitaur_gym_env.MinitaurGymEnv):
# Lower the signal a little, so that it becomes positive only for a short
# amount time.
lower_signal = -0.94
- signal_unit = math.copysign(intensity,
- math.sin(time_step * speed) + lower_signal)
+ signal_unit = math.copysign(intensity, math.sin(time_step * speed) + lower_signal)
# Only extend the leg, don't shorten.
if signal_unit < 0:
signal_unit = 0
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env_example.py
index 848c39d4a..aa07bd029 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_stand_gym_env_example.py
@@ -13,9 +13,8 @@ from pybullet_envs.minitaur.envs import minitaur_stand_gym_env
def StandUpExample():
"""An example that the minitaur stands up."""
steps = 1000
- environment = minitaur_stand_gym_env.MinitaurStandGymEnv(
- render=True,
- motor_velocity_limit=np.inf)
+ environment = minitaur_stand_gym_env.MinitaurStandGymEnv(render=True,
+ motor_velocity_limit=np.inf)
action = [0.5]
_, _, done, _ = environment.step(action)
for t in range(steps):
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env.py
index 97f820f54..e79e54926 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env.py
@@ -24,10 +24,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
controller (e.g. a neural network).
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 166
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 166}
def __init__(self,
urdf_version=None,
@@ -103,8 +100,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
# The reset position.
self._init_pose = [
- init_swing, init_swing, init_swing, init_swing, init_extension,
- init_extension, init_extension, init_extension
+ init_swing, init_swing, init_swing, init_swing, init_extension, init_extension,
+ init_extension, init_extension
]
self._step_frequency = step_frequency
@@ -112,23 +109,23 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
self._swing_amplitude = swing_amplitude
self._use_signal_in_observation = use_signal_in_observation
self._use_angle_in_observation = use_angle_in_observation
- super(MinitaurTrottingEnv, self).__init__(
- urdf_version=urdf_version,
- accurate_motor_model_enabled=accurate_motor_model_enabled,
- motor_overheat_protection=True,
- motor_kp=motor_kp,
- motor_kd=motor_kd,
- remove_default_joint_damping=remove_default_joint_damping,
- control_latency=control_latency,
- pd_latency=pd_latency,
- on_rack=on_rack,
- render=render,
- hard_reset=hard_reset,
- num_steps_to_log=num_steps_to_log,
- env_randomizer=env_randomizer,
- log_path=log_path,
- control_time_step=control_time_step,
- action_repeat=action_repeat)
+ super(MinitaurTrottingEnv,
+ self).__init__(urdf_version=urdf_version,
+ accurate_motor_model_enabled=accurate_motor_model_enabled,
+ motor_overheat_protection=True,
+ motor_kp=motor_kp,
+ motor_kd=motor_kd,
+ remove_default_joint_damping=remove_default_joint_damping,
+ control_latency=control_latency,
+ pd_latency=pd_latency,
+ on_rack=on_rack,
+ render=render,
+ hard_reset=hard_reset,
+ num_steps_to_log=num_steps_to_log,
+ env_randomizer=env_randomizer,
+ log_path=log_path,
+ control_time_step=control_time_step,
+ action_repeat=action_repeat)
action_dim = NUM_LEGS * 2
action_high = np.array([0.25] * action_dim)
@@ -144,8 +141,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
# [swing leg 1, swing leg 2, swing leg 3, swing leg 4,
# extension leg 1, extension leg 2, extension leg 3, extension leg 4]
initial_motor_angles = self._convert_from_leg_model(self._init_pose)
- super(MinitaurTrottingEnv, self).reset(
- initial_motor_angles=initial_motor_angles, reset_duration=0.5)
+ super(MinitaurTrottingEnv, self).reset(initial_motor_angles=initial_motor_angles,
+ reset_duration=0.5)
return self._get_observation()
def _convert_from_leg_model(self, leg_pose):
@@ -161,8 +158,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
motor_pose = np.zeros(NUM_MOTORS)
for i in range(NUM_LEGS):
motor_pose[int(2 * i)] = leg_pose[NUM_LEGS + i] - (-1)**int(i / 2) * leg_pose[i]
- motor_pose[int(2 * i
- + 1)] = leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i]
+ motor_pose[int(2 * i + 1)] = leg_pose[NUM_LEGS + i] + (-1)**int(i / 2) * leg_pose[i]
return motor_pose
def _gen_signal(self, t, phase):
@@ -179,8 +175,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
The desired leg extension and swing angle at the current time.
"""
period = 1 / self._step_frequency
- extension = self._extension_amplitude * math.cos(
- 2 * math.pi / period * t + phase)
+ extension = self._extension_amplitude * math.cos(2 * math.pi / period * t + phase)
swing = self._swing_amplitude * math.sin(2 * math.pi / period * t + phase)
return extension, swing
@@ -198,8 +193,8 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
ext_second_pair, sw_second_pair = self._gen_signal(t, math.pi)
trotting_signal = np.array([
- sw_first_pair, sw_second_pair, sw_second_pair, sw_first_pair,
- ext_first_pair, ext_second_pair, ext_second_pair, ext_first_pair
+ sw_first_pair, sw_second_pair, sw_second_pair, sw_first_pair, ext_first_pair,
+ ext_second_pair, ext_second_pair, ext_first_pair
])
signal = np.array(self._init_pose) + trotting_signal
return signal
@@ -286,8 +281,7 @@ class MinitaurTrottingEnv(minitaur_gym_env.MinitaurGymEnv):
"""
upper_bound = []
upper_bound.extend([2 * math.pi] * 2) # Roll, pitch, yaw of the base.
- upper_bound.extend(
- [2 * math.pi / self._time_step] * 2) # Roll, pitch, yaw rate.
+ upper_bound.extend([2 * math.pi / self._time_step] * 2) # Roll, pitch, yaw rate.
if self._use_signal_in_observation:
upper_bound.extend([2 * math.pi] * NUM_MOTORS) # Signal
if self._use_angle_in_observation:
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env_example.py
index e158e1160..e38f86428 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/minitaur_trotting_env_example.py
@@ -26,13 +26,12 @@ def main(argv):
network = config.network
with tf.Session() as sess:
- agent = simple_ppo_agent.SimplePPOPolicy(
- sess,
- env,
- network,
- policy_layers=policy_layers,
- value_layers=value_layers,
- checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
+ agent = simple_ppo_agent.SimplePPOPolicy(sess,
+ env,
+ network,
+ policy_layers=policy_layers,
+ value_layers=value_layers,
+ checkpoint=os.path.join(LOG_DIR, CHECKPOINT))
sum_reward = 0
observation = env.reset()
@@ -48,4 +47,3 @@ def main(argv):
if __name__ == "__main__":
tf.app.run(main)
-
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py
index 20e271e1b..dc852b02b 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/motor.py
@@ -8,8 +8,7 @@ MOTOR_VOLTAGE = 16.0
MOTOR_RESISTANCE = 0.186
MOTOR_TORQUE_CONSTANT = 0.0954
MOTOR_VISCOUS_DAMPING = 0
-MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (
- MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT)
+MOTOR_SPEED_LIMIT = MOTOR_VOLTAGE / (MOTOR_VISCOUS_DAMPING + MOTOR_TORQUE_CONSTANT)
NUM_MOTORS = 8
@@ -124,21 +123,19 @@ class MotorModel(object):
observed_torque: The torque observed by the sensor.
"""
observed_torque = np.clip(
- self._torque_constant *
- (np.asarray(pwm) * self._voltage / self._resistance),
+ self._torque_constant * (np.asarray(pwm) * self._voltage / self._resistance),
-OBSERVED_TORQUE_LIMIT, OBSERVED_TORQUE_LIMIT)
# Net voltage is clipped at 50V by diodes on the motor controller.
voltage_net = np.clip(
np.asarray(pwm) * self._voltage -
- (self._torque_constant + self._viscous_damping) *
- np.asarray(true_motor_velocity), -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
+ (self._torque_constant + self._viscous_damping) * np.asarray(true_motor_velocity),
+ -VOLTAGE_CLIPPING, VOLTAGE_CLIPPING)
current = voltage_net / self._resistance
current_sign = np.sign(current)
current_magnitude = np.absolute(current)
# Saturate torque based on empirical current relation.
- actual_torque = np.interp(current_magnitude, self._current_table,
- self._torque_table)
+ actual_torque = np.interp(current_magnitude, self._current_table, self._torque_table)
actual_torque = np.multiply(current_sign, actual_torque)
actual_torque = np.multiply(self._strength_ratios, actual_torque)
return actual_torque, observed_torque
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent.py
index e3c4b4ed3..85e35ad52 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent.py
@@ -4,7 +4,6 @@ from __future__ import absolute_import
from __future__ import division
from __future__ import print_function
-
import tensorflow as tf
from pybullet_envs.agents.ppo import normalize
from pybullet_envs.agents import utility
@@ -20,29 +19,25 @@ class SimplePPOPolicy(object):
https://cs.corp.google.com/piper///depot/google3/robotics/reinforcement_learning/agents/scripts/visualize.py.
"""
- def __init__(self, sess, env, network, policy_layers, value_layers,
- checkpoint):
+ def __init__(self, sess, env, network, policy_layers, value_layers, checkpoint):
self.env = env
self.sess = sess
observation_size = len(env.observation_space.low)
action_size = len(env.action_space.low)
- self.observation_placeholder = tf.placeholder(
- tf.float32, [None, observation_size], name="Input")
- self._observ_filter = normalize.StreamingNormalize(
- self.observation_placeholder[0],
- center=True,
- scale=True,
- clip=5,
- name="normalize_observ")
- self._restore_policy(
- network,
- policy_layers=policy_layers,
- value_layers=value_layers,
- action_size=action_size,
- checkpoint=checkpoint)
+ self.observation_placeholder = tf.placeholder(tf.float32, [None, observation_size],
+ name="Input")
+ self._observ_filter = normalize.StreamingNormalize(self.observation_placeholder[0],
+ center=True,
+ scale=True,
+ clip=5,
+ name="normalize_observ")
+ self._restore_policy(network,
+ policy_layers=policy_layers,
+ value_layers=value_layers,
+ action_size=action_size,
+ checkpoint=checkpoint)
- def _restore_policy(self, network, policy_layers, value_layers, action_size,
- checkpoint):
+ def _restore_policy(self, network, policy_layers, value_layers, action_size, checkpoint):
"""Restore the PPO policy from a TensorFlow checkpoint.
Args:
@@ -56,24 +51,21 @@ class SimplePPOPolicy(object):
"""
observ = self._observ_filter.transform(self.observation_placeholder)
with tf.variable_scope("network/rnn"):
- self.network = network(
- policy_layers=policy_layers,
- value_layers=value_layers,
- action_size=action_size)
+ self.network = network(policy_layers=policy_layers,
+ value_layers=value_layers,
+ action_size=action_size)
with tf.variable_scope("temporary"):
- self.last_state = tf.Variable(
- self.network.zero_state(1, tf.float32), False)
+ self.last_state = tf.Variable(self.network.zero_state(1, tf.float32), False)
self.sess.run(self.last_state.initializer)
with tf.variable_scope("network"):
- (mean_action, _, _), new_state = tf.nn.dynamic_rnn(
- self.network,
- observ[:, None],
- tf.ones(1),
- self.last_state,
- tf.float32,
- swap_memory=True)
+ (mean_action, _, _), new_state = tf.nn.dynamic_rnn(self.network,
+ observ[:, None],
+ tf.ones(1),
+ self.last_state,
+ tf.float32,
+ swap_memory=True)
self.mean_action = mean_action
self.update_state = self.last_state.assign(new_state)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent_example.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent_example.py
index 0d6f6f807..08808f98d 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent_example.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/simple_ppo_agent_example.py
@@ -29,8 +29,7 @@ from pybullet_envs.minitaur.agents import simple_ppo_agent
flags = tf.app.flags
FLAGS = tf.app.flags.FLAGS
-flags.DEFINE_string("logdir", None,
- "The directory that contains checkpoint and config.")
+flags.DEFINE_string("logdir", None, "The directory that contains checkpoint and config.")
flags.DEFINE_string("checkpoint", None, "The checkpoint file path.")
flags.DEFINE_string("log_path", None, "The output path to write log.")
@@ -44,13 +43,13 @@ def main(argv):
network = config.network
with tf.Session() as sess:
- agent = simple_ppo_agent.SimplePPOPolicy(
- sess,
- env,
- network,
- policy_layers=policy_layers,
- value_layers=value_layers,
- checkpoint=os.path.join(FLAGS.logdir, FLAGS.checkpoint))
+ agent = simple_ppo_agent.SimplePPOPolicy(sess,
+ env,
+ network,
+ policy_layers=policy_layers,
+ value_layers=value_layers,
+ checkpoint=os.path.join(FLAGS.logdir,
+ FLAGS.checkpoint))
sum_reward = 0
observation = env.reset()
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/timestamp_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/timestamp_pb2.py
index 25e3a230d..bd1bf7703 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/timestamp_pb2.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/timestamp_pb2.py
@@ -2,7 +2,7 @@
# source: timestamp.proto
import sys
-_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
+_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
from google.protobuf import descriptor as _descriptor
from google.protobuf import message as _message
from google.protobuf import reflection as _reflection
@@ -12,65 +12,76 @@ from google.protobuf import descriptor_pb2
_sym_db = _symbol_database.Default()
-
-
-
DESCRIPTOR = _descriptor.FileDescriptor(
- name='timestamp.proto',
- package='google.protobuf',
- syntax='proto3',
- serialized_pb=_b('\n\x0ftimestamp.proto\x12\x0fgoogle.protobuf\"+\n\tTimestamp\x12\x0f\n\x07seconds\x18\x01 \x01(\x03\x12\r\n\x05nanos\x18\x02 \x01(\x05\x62\x06proto3')
-)
-
-
-
+ name='timestamp.proto',
+ package='google.protobuf',
+ syntax='proto3',
+ serialized_pb=_b(
+ '\n\x0ftimestamp.proto\x12\x0fgoogle.protobuf\"+\n\tTimestamp\x12\x0f\n\x07seconds\x18\x01 \x01(\x03\x12\r\n\x05nanos\x18\x02 \x01(\x05\x62\x06proto3'
+ ))
_TIMESTAMP = _descriptor.Descriptor(
- name='Timestamp',
- full_name='google.protobuf.Timestamp',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='seconds', full_name='google.protobuf.Timestamp.seconds', index=0,
- number=1, type=3, cpp_type=2, label=1,
- has_default_value=False, default_value=0,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='nanos', full_name='google.protobuf.Timestamp.nanos', index=1,
- number=2, type=5, cpp_type=1, label=1,
- has_default_value=False, default_value=0,
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=36,
- serialized_end=79,
+ name='Timestamp',
+ full_name='google.protobuf.Timestamp',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='seconds',
+ full_name='google.protobuf.Timestamp.seconds',
+ index=0,
+ number=1,
+ type=3,
+ cpp_type=2,
+ label=1,
+ has_default_value=False,
+ default_value=0,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='nanos',
+ full_name='google.protobuf.Timestamp.nanos',
+ index=1,
+ number=2,
+ type=5,
+ cpp_type=1,
+ label=1,
+ has_default_value=False,
+ default_value=0,
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=36,
+ serialized_end=79,
)
DESCRIPTOR.message_types_by_name['Timestamp'] = _TIMESTAMP
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
-Timestamp = _reflection.GeneratedProtocolMessageType('Timestamp', (_message.Message,), dict(
- DESCRIPTOR = _TIMESTAMP,
- __module__ = 'timestamp_pb2'
- # @@protoc_insertion_point(class_scope:google.protobuf.Timestamp)
- ))
+Timestamp = _reflection.GeneratedProtocolMessageType(
+ 'Timestamp',
+ (_message.Message,),
+ dict(DESCRIPTOR=_TIMESTAMP,
+ __module__='timestamp_pb2'
+ # @@protoc_insertion_point(class_scope:google.protobuf.Timestamp)
+ ))
_sym_db.RegisterMessage(Timestamp)
-
# @@protoc_insertion_point(module_scope)
diff --git a/examples/pybullet/gym/pybullet_envs/minitaur/envs/vector_pb2.py b/examples/pybullet/gym/pybullet_envs/minitaur/envs/vector_pb2.py
index 67bacb9cd..400c6c805 100644
--- a/examples/pybullet/gym/pybullet_envs/minitaur/envs/vector_pb2.py
+++ b/examples/pybullet/gym/pybullet_envs/minitaur/envs/vector_pb2.py
@@ -2,7 +2,7 @@
# source: vector.proto
import sys
-_b=sys.version_info[0]<3 and (lambda x:x) or (lambda x:x.encode('latin1'))
+_b = sys.version_info[0] < 3 and (lambda x: x) or (lambda x: x.encode('latin1'))
from google.protobuf import descriptor as _descriptor
from google.protobuf import message as _message
from google.protobuf import reflection as _reflection
@@ -12,348 +12,494 @@ from google.protobuf import descriptor_pb2
_sym_db = _symbol_database.Default()
-
-
-
DESCRIPTOR = _descriptor.FileDescriptor(
- name='vector.proto',
- package='robotics.messages',
- syntax='proto3',
- serialized_pb=_b('\n\x0cvector.proto\x12\x11robotics.messages\"6\n\x08Vector4d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"6\n\x08Vector4f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\"+\n\x08Vector3d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"+\n\x08Vector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\" \n\x08Vector2d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\" \n\x08Vector2f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\"\x1b\n\x07Vectord\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x01\x42\x02\x10\x01\"\x1b\n\x07Vectorf\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x02\x42\x02\x10\x01\x62\x06proto3')
-)
-
-
-
+ name='vector.proto',
+ package='robotics.messages',
+ syntax='proto3',
+ serialized_pb=_b(
+ '\n\x0cvector.proto\x12\x11robotics.messages\"6\n\x08Vector4d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\x12\t\n\x01w\x18\x04 \x01(\x01\"6\n\x08Vector4f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\x12\t\n\x01w\x18\x04 \x01(\x02\"+\n\x08Vector3d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\x12\t\n\x01z\x18\x03 \x01(\x01\"+\n\x08Vector3f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\x12\t\n\x01z\x18\x03 \x01(\x02\" \n\x08Vector2d\x12\t\n\x01x\x18\x01 \x01(\x01\x12\t\n\x01y\x18\x02 \x01(\x01\" \n\x08Vector2f\x12\t\n\x01x\x18\x01 \x01(\x02\x12\t\n\x01y\x18\x02 \x01(\x02\"\x1b\n\x07Vectord\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x01\x42\x02\x10\x01\"\x1b\n\x07Vectorf\x12\x10\n\x04\x64\x61ta\x18\x01 \x03(\x02\x42\x02\x10\x01\x62\x06proto3'
+ ))
_VECTOR4D = _descriptor.Descriptor(
- name='Vector4d',
- full_name='robotics.messages.Vector4d',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector4d.x', index=0,
- number=1, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector4d.y', index=1,
- number=2, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='z', full_name='robotics.messages.Vector4d.z', index=2,
- number=3, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='w', full_name='robotics.messages.Vector4d.w', index=3,
- number=4, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=35,
- serialized_end=89,
+ name='Vector4d',
+ full_name='robotics.messages.Vector4d',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector4d.x',
+ index=0,
+ number=1,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector4d.y',
+ index=1,
+ number=2,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='z',
+ full_name='robotics.messages.Vector4d.z',
+ index=2,
+ number=3,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='w',
+ full_name='robotics.messages.Vector4d.w',
+ index=3,
+ number=4,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=35,
+ serialized_end=89,
)
-
_VECTOR4F = _descriptor.Descriptor(
- name='Vector4f',
- full_name='robotics.messages.Vector4f',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector4f.x', index=0,
- number=1, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector4f.y', index=1,
- number=2, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='z', full_name='robotics.messages.Vector4f.z', index=2,
- number=3, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='w', full_name='robotics.messages.Vector4f.w', index=3,
- number=4, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=91,
- serialized_end=145,
+ name='Vector4f',
+ full_name='robotics.messages.Vector4f',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector4f.x',
+ index=0,
+ number=1,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector4f.y',
+ index=1,
+ number=2,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='z',
+ full_name='robotics.messages.Vector4f.z',
+ index=2,
+ number=3,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='w',
+ full_name='robotics.messages.Vector4f.w',
+ index=3,
+ number=4,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=91,
+ serialized_end=145,
)
-
_VECTOR3D = _descriptor.Descriptor(
- name='Vector3d',
- full_name='robotics.messages.Vector3d',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector3d.x', index=0,
- number=1, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector3d.y', index=1,
- number=2, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='z', full_name='robotics.messages.Vector3d.z', index=2,
- number=3, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=147,
- serialized_end=190,
+ name='Vector3d',
+ full_name='robotics.messages.Vector3d',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector3d.x',
+ index=0,
+ number=1,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector3d.y',
+ index=1,
+ number=2,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='z',
+ full_name='robotics.messages.Vector3d.z',
+ index=2,
+ number=3,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=147,
+ serialized_end=190,
)
-
_VECTOR3F = _descriptor.Descriptor(
- name='Vector3f',
- full_name='robotics.messages.Vector3f',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector3f.x', index=0,
- number=1, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector3f.y', index=1,
- number=2, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='z', full_name='robotics.messages.Vector3f.z', index=2,
- number=3, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=192,
- serialized_end=235,
+ name='Vector3f',
+ full_name='robotics.messages.Vector3f',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector3f.x',
+ index=0,
+ number=1,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector3f.y',
+ index=1,
+ number=2,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='z',
+ full_name='robotics.messages.Vector3f.z',
+ index=2,
+ number=3,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=192,
+ serialized_end=235,
)
-
_VECTOR2D = _descriptor.Descriptor(
- name='Vector2d',
- full_name='robotics.messages.Vector2d',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector2d.x', index=0,
- number=1, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector2d.y', index=1,
- number=2, type=1, cpp_type=5, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=237,
- serialized_end=269,
+ name='Vector2d',
+ full_name='robotics.messages.Vector2d',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector2d.x',
+ index=0,
+ number=1,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector2d.y',
+ index=1,
+ number=2,
+ type=1,
+ cpp_type=5,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=237,
+ serialized_end=269,
)
-
_VECTOR2F = _descriptor.Descriptor(
- name='Vector2f',
- full_name='robotics.messages.Vector2f',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='x', full_name='robotics.messages.Vector2f.x', index=0,
- number=1, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- _descriptor.FieldDescriptor(
- name='y', full_name='robotics.messages.Vector2f.y', index=1,
- number=2, type=2, cpp_type=6, label=1,
- has_default_value=False, default_value=float(0),
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=None, file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=271,
- serialized_end=303,
+ name='Vector2f',
+ full_name='robotics.messages.Vector2f',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='x',
+ full_name='robotics.messages.Vector2f.x',
+ index=0,
+ number=1,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ _descriptor.FieldDescriptor(name='y',
+ full_name='robotics.messages.Vector2f.y',
+ index=1,
+ number=2,
+ type=2,
+ cpp_type=6,
+ label=1,
+ has_default_value=False,
+ default_value=float(0),
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=None,
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=271,
+ serialized_end=303,
)
-
_VECTORD = _descriptor.Descriptor(
- name='Vectord',
- full_name='robotics.messages.Vectord',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='data', full_name='robotics.messages.Vectord.data', index=0,
- number=1, type=1, cpp_type=5, label=3,
- has_default_value=False, default_value=[],
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=_descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001')), file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=305,
- serialized_end=332,
+ name='Vectord',
+ full_name='robotics.messages.Vectord',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='data',
+ full_name='robotics.messages.Vectord.data',
+ index=0,
+ number=1,
+ type=1,
+ cpp_type=5,
+ label=3,
+ has_default_value=False,
+ default_value=[],
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=_descriptor._ParseOptions(
+ descriptor_pb2.FieldOptions(), _b('\020\001')),
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=305,
+ serialized_end=332,
)
-
_VECTORF = _descriptor.Descriptor(
- name='Vectorf',
- full_name='robotics.messages.Vectorf',
- filename=None,
- file=DESCRIPTOR,
- containing_type=None,
- fields=[
- _descriptor.FieldDescriptor(
- name='data', full_name='robotics.messages.Vectorf.data', index=0,
- number=1, type=2, cpp_type=6, label=3,
- has_default_value=False, default_value=[],
- message_type=None, enum_type=None, containing_type=None,
- is_extension=False, extension_scope=None,
- options=_descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001')), file=DESCRIPTOR),
- ],
- extensions=[
- ],
- nested_types=[],
- enum_types=[
- ],
- options=None,
- is_extendable=False,
- syntax='proto3',
- extension_ranges=[],
- oneofs=[
- ],
- serialized_start=334,
- serialized_end=361,
+ name='Vectorf',
+ full_name='robotics.messages.Vectorf',
+ filename=None,
+ file=DESCRIPTOR,
+ containing_type=None,
+ fields=[
+ _descriptor.FieldDescriptor(name='data',
+ full_name='robotics.messages.Vectorf.data',
+ index=0,
+ number=1,
+ type=2,
+ cpp_type=6,
+ label=3,
+ has_default_value=False,
+ default_value=[],
+ message_type=None,
+ enum_type=None,
+ containing_type=None,
+ is_extension=False,
+ extension_scope=None,
+ options=_descriptor._ParseOptions(
+ descriptor_pb2.FieldOptions(), _b('\020\001')),
+ file=DESCRIPTOR),
+ ],
+ extensions=[],
+ nested_types=[],
+ enum_types=[],
+ options=None,
+ is_extendable=False,
+ syntax='proto3',
+ extension_ranges=[],
+ oneofs=[],
+ serialized_start=334,
+ serialized_end=361,
)
DESCRIPTOR.message_types_by_name['Vector4d'] = _VECTOR4D
@@ -366,65 +512,82 @@ DESCRIPTOR.message_types_by_name['Vectord'] = _VECTORD
DESCRIPTOR.message_types_by_name['Vectorf'] = _VECTORF
_sym_db.RegisterFileDescriptor(DESCRIPTOR)
-Vector4d = _reflection.GeneratedProtocolMessageType('Vector4d', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR4D,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector4d)
- ))
+Vector4d = _reflection.GeneratedProtocolMessageType(
+ 'Vector4d',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR4D,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector4d)
+ ))
_sym_db.RegisterMessage(Vector4d)
-Vector4f = _reflection.GeneratedProtocolMessageType('Vector4f', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR4F,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector4f)
- ))
+Vector4f = _reflection.GeneratedProtocolMessageType(
+ 'Vector4f',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR4F,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector4f)
+ ))
_sym_db.RegisterMessage(Vector4f)
-Vector3d = _reflection.GeneratedProtocolMessageType('Vector3d', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR3D,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector3d)
- ))
+Vector3d = _reflection.GeneratedProtocolMessageType(
+ 'Vector3d',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR3D,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector3d)
+ ))
_sym_db.RegisterMessage(Vector3d)
-Vector3f = _reflection.GeneratedProtocolMessageType('Vector3f', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR3F,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector3f)
- ))
+Vector3f = _reflection.GeneratedProtocolMessageType(
+ 'Vector3f',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR3F,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector3f)
+ ))
_sym_db.RegisterMessage(Vector3f)
-Vector2d = _reflection.GeneratedProtocolMessageType('Vector2d', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR2D,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector2d)
- ))
+Vector2d = _reflection.GeneratedProtocolMessageType(
+ 'Vector2d',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR2D,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector2d)
+ ))
_sym_db.RegisterMessage(Vector2d)
-Vector2f = _reflection.GeneratedProtocolMessageType('Vector2f', (_message.Message,), dict(
- DESCRIPTOR = _VECTOR2F,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vector2f)
- ))
+Vector2f = _reflection.GeneratedProtocolMessageType(
+ 'Vector2f',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTOR2F,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vector2f)
+ ))
_sym_db.RegisterMessage(Vector2f)
-Vectord = _reflection.GeneratedProtocolMessageType('Vectord', (_message.Message,), dict(
- DESCRIPTOR = _VECTORD,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vectord)
- ))
+Vectord = _reflection.GeneratedProtocolMessageType(
+ 'Vectord',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTORD,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vectord)
+ ))
_sym_db.RegisterMessage(Vectord)
-Vectorf = _reflection.GeneratedProtocolMessageType('Vectorf', (_message.Message,), dict(
- DESCRIPTOR = _VECTORF,
- __module__ = 'vector_pb2'
- # @@protoc_insertion_point(class_scope:robotics.messages.Vectorf)
- ))
+Vectorf = _reflection.GeneratedProtocolMessageType(
+ 'Vectorf',
+ (_message.Message,),
+ dict(DESCRIPTOR=_VECTORF,
+ __module__='vector_pb2'
+ # @@protoc_insertion_point(class_scope:robotics.messages.Vectorf)
+ ))
_sym_db.RegisterMessage(Vectorf)
-
_VECTORD.fields_by_name['data'].has_options = True
-_VECTORD.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001'))
+_VECTORD.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(),
+ _b('\020\001'))
_VECTORF.fields_by_name['data'].has_options = True
-_VECTORF.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(), _b('\020\001'))
+_VECTORF.fields_by_name['data']._options = _descriptor._ParseOptions(descriptor_pb2.FieldOptions(),
+ _b('\020\001'))
# @@protoc_insertion_point(module_scope)
diff --git a/examples/pybullet/gym/pybullet_envs/prediction/__init__.py b/examples/pybullet/gym/pybullet_envs/prediction/__init__.py
index 26f76e102..a575195ec 100644
--- a/examples/pybullet/gym/pybullet_envs/prediction/__init__.py
+++ b/examples/pybullet/gym/pybullet_envs/prediction/__init__.py
@@ -1,3 +1,2 @@
from . import boxstack_pybullet_sim
from . import pybullet_sim_gym_env
-
diff --git a/examples/pybullet/gym/pybullet_envs/prediction/boxstack_pybullet_sim.py b/examples/pybullet/gym/pybullet_envs/prediction/boxstack_pybullet_sim.py
index 42bc3cffa..85e29cc60 100644
--- a/examples/pybullet/gym/pybullet_envs/prediction/boxstack_pybullet_sim.py
+++ b/examples/pybullet/gym/pybullet_envs/prediction/boxstack_pybullet_sim.py
@@ -14,10 +14,7 @@ class BoxStackPyBulletSim(object):
"""
- def __init__(self,
- pybullet_client,
- urdf_root= pybullet_data.getDataPath(),
- time_step=0.01):
+ def __init__(self, pybullet_client, urdf_root=pybullet_data.getDataPath(), time_step=0.01):
"""Constructs an example simulation and reset it to the initial states.
Args:
@@ -28,11 +25,10 @@ class BoxStackPyBulletSim(object):
"""
self._pybullet_client = pybullet_client
self._urdf_root = urdf_root
- self.m_actions_taken_since_reset=0
+ self.m_actions_taken_since_reset = 0
self.time_step = time_step
self.stateId = -1
self.Reset(reload_urdf=True)
-
def Reset(self, reload_urdf=False):
"""Reset the minitaur to its initial states.
@@ -41,58 +37,59 @@ class BoxStackPyBulletSim(object):
reload_urdf: Whether to reload the urdf file. If not, Reset() just place
the minitaur back to its starting position.
"""
- self.m_actions_taken_since_reset=0
- xPosRange=0.025
- yPosRange=0.025
+ self.m_actions_taken_since_reset = 0
+ xPosRange = 0.025
+ yPosRange = 0.025
boxHalfExtents = 0.025
-
+
if reload_urdf:
camInfo = self._pybullet_client.getDebugVisualizerCamera()
- cameraDistance=camInfo[10]
- print("cameraYaw=",camInfo[8])
- print("cameraPitch=",camInfo[9])
- print("camtarget=",camInfo[11])
- print("projectionMatrix=",camInfo[3])
- self._pybullet_client.resetDebugVisualizerCamera(cameraDistance=0.3, cameraYaw=camInfo[8], cameraPitch=camInfo[9],cameraTargetPosition=camInfo[11])
+ cameraDistance = camInfo[10]
+ print("cameraYaw=", camInfo[8])
+ print("cameraPitch=", camInfo[9])
+ print("camtarget=", camInfo[11])
+ print("projectionMatrix=", camInfo[3])
+ self._pybullet_client.resetDebugVisualizerCamera(cameraDistance=0.3,
+ cameraYaw=camInfo[8],
+ cameraPitch=camInfo[9],
+ cameraTargetPosition=camInfo[11])
plane = self._pybullet_client.loadURDF("plane.urdf")
texUid = self._pybullet_client.loadTexture("checker_blue.png")
- self._pybullet_client.changeVisualShape(plane,-1, textureUniqueId = texUid)
-
-
- self._numObjects=4 #random number?
-
-
- self._cubes=[]
-
- red=[0.97,0.25,0.25,1]
- green=[0.41,0.68,0.31,1]
- yellow=[0.92,0.73,0,1]
- blue=[0,0.55,0.81,1]
- colors=[red,green,yellow,blue]
-
- for i in range (self._numObjects):
- pos=[0,0,boxHalfExtents + i*2*boxHalfExtents]
- orn = self._pybullet_client.getQuaternionFromEuler([0,0,0])
- orn=[0,0,0,1]
- cube = self._pybullet_client.loadURDF("cube_small.urdf",pos,orn)
- self._pybullet_client.changeVisualShape(cube,-1,rgbaColor=colors[i])
- self._cubes.append(cube)
-
+ self._pybullet_client.changeVisualShape(plane, -1, textureUniqueId=texUid)
+
+ self._numObjects = 4 #random number?
+
+ self._cubes = []
+
+ red = [0.97, 0.25, 0.25, 1]
+ green = [0.41, 0.68, 0.31, 1]
+ yellow = [0.92, 0.73, 0, 1]
+ blue = [0, 0.55, 0.81, 1]
+ colors = [red, green, yellow, blue]
+
+ for i in range(self._numObjects):
+ pos = [0, 0, boxHalfExtents + i * 2 * boxHalfExtents]
+ orn = self._pybullet_client.getQuaternionFromEuler([0, 0, 0])
+ orn = [0, 0, 0, 1]
+ cube = self._pybullet_client.loadURDF("cube_small.urdf", pos, orn)
+ self._pybullet_client.changeVisualShape(cube, -1, rgbaColor=colors[i])
+ self._cubes.append(cube)
+
self._pybullet_client.setGravity(0, 0, -10)
self.stateId = self._pybullet_client.saveState()
else:
- if (self.stateId>=0):
+ if (self.stateId >= 0):
self._pybullet_client.restoreState(self.stateId)
- index=0
+ index = 0
for i in self._cubes:
- posX = random.uniform(-xPosRange,xPosRange)
- posY = random.uniform(-yPosRange,yPosRange)
- yaw = random.uniform(-math.pi,math.pi)
- pos=[posX,posY,boxHalfExtents + index*2*boxHalfExtents]
- index+=1
- orn = self._pybullet_client.getQuaternionFromEuler([0,0,yaw])
- self._pybullet_client.resetBasePositionAndOrientation(i,pos,orn)
+ posX = random.uniform(-xPosRange, xPosRange)
+ posY = random.uniform(-yPosRange, yPosRange)
+ yaw = random.uniform(-math.pi, math.pi)
+ pos = [posX, posY, boxHalfExtents + index * 2 * boxHalfExtents]
+ index += 1
+ orn = self._pybullet_client.getQuaternionFromEuler([0, 0, yaw])
+ self._pybullet_client.resetBasePositionAndOrientation(i, pos, orn)
def GetActionDimension(self):
"""Get the length of the action list.
@@ -100,7 +97,7 @@ class BoxStackPyBulletSim(object):
Returns:
The length of the action list.
"""
- return 4#self.num_motors
+ return 4 #self.num_motors
def GetObservationUpperBound(self):
"""Get the upper bound of the observation.
@@ -124,7 +121,7 @@ class BoxStackPyBulletSim(object):
The length of the observation list.
"""
sz = len(self.GetObservation())
- print("sz=",sz)
+ print("sz=", sz)
return sz
def GetObservation(self):
@@ -135,7 +132,7 @@ class BoxStackPyBulletSim(object):
"""
observation = []
for i in self._cubes:
- pos,orn=self._pybullet_client.getBasePositionAndOrientation(i)
+ pos, orn = self._pybullet_client.getBasePositionAndOrientation(i)
observation.extend(list(pos))
observation.extend(list(orn))
return observation
@@ -143,14 +140,14 @@ class BoxStackPyBulletSim(object):
def ApplyAction(self, action):
"""Set the desired action.
"""
- self.m_actions_taken_since_reset+=1
-
+ self.m_actions_taken_since_reset += 1
def Termination(self):
- return self.m_actions_taken_since_reset>=200
-
-def CreateSim(pybullet_client,urdf_root,time_step):
+ return self.m_actions_taken_since_reset >= 200
+
+
+def CreateSim(pybullet_client, urdf_root, time_step):
sim = BoxStackPyBulletSim(pybullet_client=pybullet_client,
- urdf_root=urdf_root,
- time_step=time_step)
+ urdf_root=urdf_root,
+ time_step=time_step)
return sim
diff --git a/examples/pybullet/gym/pybullet_envs/prediction/pybullet_sim_gym_env.py b/examples/pybullet/gym/pybullet_envs/prediction/pybullet_sim_gym_env.py
index 2f451529a..1c308a7fb 100644
--- a/examples/pybullet/gym/pybullet_envs/prediction/pybullet_sim_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/prediction/pybullet_sim_gym_env.py
@@ -5,8 +5,7 @@
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 math
import time
@@ -30,20 +29,18 @@ class PyBulletSimGymEnv(gym.Env):
"""
- metadata = {
- "render.modes": ["human", "rgb_array"],
- "video.frames_per_second": 50
- }
+ metadata = {"render.modes": ["human", "rgb_array"], "video.frames_per_second": 50}
- def __init__(self,pybullet_sim_factory = boxstack_pybullet_sim,
+ def __init__(self,
+ pybullet_sim_factory=boxstack_pybullet_sim,
render=True,
render_sleep=False,
debug_visualization=True,
- hard_reset = False,
+ hard_reset=False,
render_width=240,
render_height=240,
action_repeat=1,
- time_step = 1./240.,
+ time_step=1. / 240.,
num_bullet_solver_iterations=50,
urdf_root=pybullet_data.getDataPath()):
"""Initialize the gym environment.
@@ -55,45 +52,46 @@ class PyBulletSimGymEnv(gym.Env):
self._time_step = time_step
self._urdf_root = urdf_root
self._observation = []
- self._action_repeat=action_repeat
+ self._action_repeat = action_repeat
self._num_bullet_solver_iterations = num_bullet_solver_iterations
self._env_step_counter = 0
self._is_render = render
self._debug_visualization = debug_visualization
self._render_sleep = render_sleep
- self._render_width=render_width
- self._render_height=render_height
+ self._render_width = render_width
+ self._render_height = render_height
self._cam_dist = .3
self._cam_yaw = 50
self._cam_pitch = -35
self._hard_reset = True
self._last_frame_time = 0.0
- optionstring='--width={} --height={}'.format(render_width,render_height)
+ optionstring = '--width={} --height={}'.format(render_width, render_height)
print("urdf_root=" + self._urdf_root)
if self._is_render:
- self._pybullet_client = bullet_client.BulletClient(
- connection_mode=pybullet.GUI, options=optionstring)
+ self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI,
+ options=optionstring)
else:
self._pybullet_client = bullet_client.BulletClient()
- if (debug_visualization==False):
- self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,enable=0)
- self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW,enable=0)
- self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_DEPTH_BUFFER_PREVIEW,enable=0)
- self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_SEGMENTATION_MARK_PREVIEW,enable=0)
-
+ if (debug_visualization == False):
+ self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,
+ enable=0)
+ self._pybullet_client.configureDebugVisualizer(
+ flag=self._pybullet_client.COV_ENABLE_RGB_BUFFER_PREVIEW, enable=0)
+ self._pybullet_client.configureDebugVisualizer(
+ flag=self._pybullet_client.COV_ENABLE_DEPTH_BUFFER_PREVIEW, enable=0)
+ self._pybullet_client.configureDebugVisualizer(
+ flag=self._pybullet_client.COV_ENABLE_SEGMENTATION_MARK_PREVIEW, enable=0)
self._pybullet_client.setAdditionalSearchPath(urdf_root)
self.seed()
self.reset()
- observation_high = (
- self._example_sim.GetObservationUpperBound())
- observation_low = (
- self._example_sim.GetObservationLowerBound())
+ observation_high = (self._example_sim.GetObservationUpperBound())
+ observation_low = (self._example_sim.GetObservationLowerBound())
action_dim = self._example_sim.GetActionDimension()
self._action_bound = 1
@@ -104,7 +102,6 @@ class PyBulletSimGymEnv(gym.Env):
self.viewer = None
self._hard_reset = hard_reset # This assignment need to be after reset()
-
def configure(self, args):
self._args = args
@@ -163,7 +160,6 @@ class PyBulletSimGymEnv(gym.Env):
#self._pybullet_client.resetDebugVisualizerCamera(
# self._cam_dist, self._cam_yaw, self._cam_pitch, base_pos)
-
for _ in range(self._action_repeat):
self._example_sim.ApplyAction(action)
self._pybullet_client.stepSimulation()
@@ -176,7 +172,7 @@ class PyBulletSimGymEnv(gym.Env):
def render(self, mode="rgb_array", close=False):
if mode != "rgb_array":
return np.array([])
- base_pos = [0,0,0]
+ base_pos = [0, 0, 0]
view_matrix = self._pybullet_client.computeViewMatrixFromYawPitchRoll(
cameraTargetPosition=base_pos,
distance=self._cam_dist,
@@ -185,19 +181,24 @@ class PyBulletSimGymEnv(gym.Env):
roll=0,
upAxisIndex=2)
proj_matrix = self._pybullet_client.computeProjectionMatrixFOV(
- fov=60, aspect=float(self._render_width)/self._render_width,
- nearVal=0.01, farVal=100.0)
- proj_matrix=[1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
+ fov=60, aspect=float(self._render_width) / self._render_width, nearVal=0.01, farVal=100.0)
+ proj_matrix = [
+ 1.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0,
+ -0.02000020071864128, 0.0
+ ]
(_, _, px, _, _) = self._pybullet_client.getCameraImage(
- width=self._render_width, height=self._render_height, viewMatrix=view_matrix,
- projectionMatrix=proj_matrix, renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)#ER_TINY_RENDERER)
+ width=self._render_width,
+ height=self._render_height,
+ viewMatrix=view_matrix,
+ projectionMatrix=proj_matrix,
+ renderer=pybullet.ER_BULLET_HARDWARE_OPENGL) #ER_TINY_RENDERER)
rgb_array = np.array(px, dtype=np.uint8)
rgb_array = np.reshape(rgb_array, (self._render_height, self._render_width, 4))
rgb_array = rgb_array[:, :, :3]
return rgb_array
def _termination(self):
- terminate=self._example_sim.Termination()
+ terminate = self._example_sim.Termination()
return terminate
def _reward(self):
diff --git a/examples/pybullet/gym/pybullet_envs/prediction/test_pybullet_sim_gym_env.py b/examples/pybullet/gym/pybullet_envs/prediction/test_pybullet_sim_gym_env.py
index 23f734e4e..ae24b3a9d 100644
--- a/examples/pybullet/gym/pybullet_envs/prediction/test_pybullet_sim_gym_env.py
+++ b/examples/pybullet/gym/pybullet_envs/prediction/test_pybullet_sim_gym_env.py
@@ -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
@@ -16,18 +16,18 @@ import time
from pybullet_envs.prediction import boxstack_pybullet_sim
from gym.wrappers.monitoring import video_recorder
+
def ResetPoseExample(steps):
"""An example that the minitaur stands still using the reset pose."""
-
-
- environment = pybullet_sim_gym_env.PyBulletSimGymEnv(
- pybullet_sim_factory=boxstack_pybullet_sim,
- debug_visualization=False,
- render=True, action_repeat=30)
+
+ environment = pybullet_sim_gym_env.PyBulletSimGymEnv(pybullet_sim_factory=boxstack_pybullet_sim,
+ debug_visualization=False,
+ render=True,
+ action_repeat=30)
action = [math.pi / 2] * 8
-
- vid = video_recorder.VideoRecorder(env=environment,path="vid.mp4")
-
+
+ vid = video_recorder.VideoRecorder(env=environment, path="vid.mp4")
+
for _ in range(steps):
print(_)
startsim = time.time()
@@ -37,24 +37,21 @@ def ResetPoseExample(steps):
#environment.render(mode='rgb_array')
vid.capture_frame()
stoprender = time.time()
- print ("env.step " , (stopsim - startsim))
- print ("env.render " , (stoprender - startrender))
+ print("env.step ", (stopsim - startsim))
+ print("env.render ", (stoprender - startrender))
if done:
- environment.reset()
-
-
+ environment.reset()
def main():
- parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
- parser.add_argument('--env', help='environment ID (0==reset)',type=int, default=0)
- args = parser.parse_args()
- print("--env=" + str(args.env))
-
- if (args.env == 0):
- ResetPoseExample(steps = 1000)
+ parser = argparse.ArgumentParser(formatter_class=argparse.ArgumentDefaultsHelpFormatter)
+ parser.add_argument('--env', help='environment ID (0==reset)', type=int, default=0)
+ args = parser.parse_args()
+ print("--env=" + str(args.env))
-if __name__ == '__main__':
- main()
+ if (args.env == 0):
+ ResetPoseExample(steps=1000)
+if __name__ == '__main__':
+ main()
diff --git a/examples/pybullet/gym/pybullet_envs/robot_bases.py b/examples/pybullet/gym/pybullet_envs/robot_bases.py
index 36e5b8c76..51c2791c1 100644
--- a/examples/pybullet/gym/pybullet_envs/robot_bases.py
+++ b/examples/pybullet/gym/pybullet_envs/robot_bases.py
@@ -4,339 +4,404 @@ import numpy as np
import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(currentdir)
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import pybullet_data
class XmlBasedRobot:
- """
+ """
Base class for mujoco .xml based agents.
"""
- self_collision = True
- def __init__(self, robot_name, action_dim, obs_dim, self_collision):
- self.parts = None
- self.objects = []
- self.jdict = None
- self.ordered_joints = None
- self.robot_body = None
-
- high = np.ones([action_dim])
- self.action_space = gym.spaces.Box(-high, high)
- high = np.inf * np.ones([obs_dim])
- self.observation_space = gym.spaces.Box(-high, high)
-
- #self.model_xml = model_xml
- self.robot_name = robot_name
- self.self_collision = self_collision
-
- def addToScene(self, bullet_client, bodies):
- self._p = bullet_client
-
- if self.parts is not None:
- parts = self.parts
- else:
- parts = {}
-
- if self.jdict is not None:
- joints = self.jdict
- else:
- joints = {}
-
- if self.ordered_joints is not None:
- ordered_joints = self.ordered_joints
- else:
- ordered_joints = []
-
- if np.isscalar(bodies): # streamline the case where bodies is actually just one body
- bodies = [bodies]
-
- dump = 0
- for i in range(len(bodies)):
- if self._p.getNumJoints(bodies[i]) == 0:
- part_name, robot_name = self._p.getBodyInfo(bodies[i])
- self.robot_name = robot_name.decode("utf8")
- part_name = part_name.decode("utf8")
- parts[part_name] = BodyPart(self._p, part_name, bodies, i, -1)
- for j in range(self._p.getNumJoints(bodies[i])):
- self._p.setJointMotorControl2(bodies[i],j,pybullet.POSITION_CONTROL,positionGain=0.1,velocityGain=0.1,force=0)
- jointInfo = self._p.getJointInfo(bodies[i], j)
- joint_name=jointInfo[1]
- part_name=jointInfo[12]
-
- joint_name = joint_name.decode("utf8")
- part_name = part_name.decode("utf8")
-
- if dump: print("ROBOT PART '%s'" % part_name)
- if dump: print("ROBOT JOINT '%s'" % joint_name) # limits = %+0.2f..%+0.2f effort=%0.3f speed=%0.3f" % ((joint_name,) + j.limits()) )
-
- parts[part_name] = BodyPart(self._p, part_name, bodies, i, j)
-
- if part_name == self.robot_name:
- self.robot_body = parts[part_name]
+ self_collision = True
+
+ def __init__(self, robot_name, action_dim, obs_dim, self_collision):
+ self.parts = None
+ self.objects = []
+ self.jdict = None
+ self.ordered_joints = None
+ self.robot_body = None
+
+ high = np.ones([action_dim])
+ self.action_space = gym.spaces.Box(-high, high)
+ high = np.inf * np.ones([obs_dim])
+ self.observation_space = gym.spaces.Box(-high, high)
+
+ #self.model_xml = model_xml
+ self.robot_name = robot_name
+ self.self_collision = self_collision
+
+ def addToScene(self, bullet_client, bodies):
+ self._p = bullet_client
+
+ if self.parts is not None:
+ parts = self.parts
+ else:
+ parts = {}
+
+ if self.jdict is not None:
+ joints = self.jdict
+ else:
+ joints = {}
+
+ if self.ordered_joints is not None:
+ ordered_joints = self.ordered_joints
+ else:
+ ordered_joints = []
+
+ if np.isscalar(bodies): # streamline the case where bodies is actually just one body
+ bodies = [bodies]
+
+ dump = 0
+ for i in range(len(bodies)):
+ if self._p.getNumJoints(bodies[i]) == 0:
+ part_name, robot_name = self._p.getBodyInfo(bodies[i])
+ self.robot_name = robot_name.decode("utf8")
+ part_name = part_name.decode("utf8")
+ parts[part_name] = BodyPart(self._p, part_name, bodies, i, -1)
+ for j in range(self._p.getNumJoints(bodies[i])):
+ self._p.setJointMotorControl2(bodies[i],
+ j,
+ pybullet.POSITION_CONTROL,
+ positionGain=0.1,
+ velocityGain=0.1,
+ force=0)
+ jointInfo = self._p.getJointInfo(bodies[i], j)
+ joint_name = jointInfo[1]
+ part_name = jointInfo[12]
+
+ joint_name = joint_name.decode("utf8")
+ part_name = part_name.decode("utf8")
+
+ if dump: print("ROBOT PART '%s'" % part_name)
+ if dump:
+ print(
+ "ROBOT JOINT '%s'" % joint_name
+ ) # limits = %+0.2f..%+0.2f effort=%0.3f speed=%0.3f" % ((joint_name,) + j.limits()) )
+
+ parts[part_name] = BodyPart(self._p, part_name, bodies, i, j)
+
+ if part_name == self.robot_name:
+ self.robot_body = parts[part_name]
+
+ if i == 0 and j == 0 and self.robot_body is None: # if nothing else works, we take this as robot_body
+ parts[self.robot_name] = BodyPart(self._p, self.robot_name, bodies, 0, -1)
+ self.robot_body = parts[self.robot_name]
+
+ if joint_name[:6] == "ignore":
+ Joint(self._p, joint_name, bodies, i, j).disable_motor()
+ continue
+
+ if joint_name[:8] != "jointfix":
+ joints[joint_name] = Joint(self._p, joint_name, bodies, i, j)
+ ordered_joints.append(joints[joint_name])
+
+ joints[joint_name].power_coef = 100.0
+
+ # TODO: Maybe we need this
+ # joints[joint_name].power_coef, joints[joint_name].max_velocity = joints[joint_name].limits()[2:4]
+ # self.ordered_joints.append(joints[joint_name])
+ # self.jdict[joint_name] = joints[joint_name]
+
+ return parts, joints, ordered_joints, self.robot_body
+
+ def reset_pose(self, position, orientation):
+ self.parts[self.robot_name].reset_pose(position, orientation)
- if i == 0 and j == 0 and self.robot_body is None: # if nothing else works, we take this as robot_body
- parts[self.robot_name] = BodyPart(self._p, self.robot_name, bodies, 0, -1)
- self.robot_body = parts[self.robot_name]
-
- if joint_name[:6] == "ignore":
- Joint(self._p, joint_name, bodies, i, j).disable_motor()
- continue
-
- if joint_name[:8] != "jointfix":
- joints[joint_name] = Joint(self._p, joint_name, bodies, i, j)
- ordered_joints.append(joints[joint_name])
-
- joints[joint_name].power_coef = 100.0
-
- # TODO: Maybe we need this
- # joints[joint_name].power_coef, joints[joint_name].max_velocity = joints[joint_name].limits()[2:4]
- # self.ordered_joints.append(joints[joint_name])
- # self.jdict[joint_name] = joints[joint_name]
-
- return parts, joints, ordered_joints, self.robot_body
-
- def reset_pose(self, position, orientation):
- self.parts[self.robot_name].reset_pose(position, orientation)
class MJCFBasedRobot(XmlBasedRobot):
- """
+ """
Base class for mujoco .xml based agents.
"""
- def __init__(self, model_xml, robot_name, action_dim, obs_dim, self_collision=True):
- XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
- self.model_xml = model_xml
- self.doneLoading=0
- def reset(self, bullet_client):
-
- self._p = bullet_client
- #print("Created bullet_client with id=", self._p._client)
- if (self.doneLoading==0):
- self.ordered_joints = []
- self.doneLoading=1
- if self.self_collision:
- self.objects = self._p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml), flags=pybullet.URDF_USE_SELF_COLLISION|pybullet.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p, self.objects )
- else:
- self.objects = self._p.loadMJCF(os.path.join(pybullet_data.getDataPath(),"mjcf", self.model_xml))
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p, self.objects)
- self.robot_specific_reset(self._p)
-
- s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
-
- return s
-
- def calc_potential(self):
- return 0
+ def __init__(self, model_xml, robot_name, action_dim, obs_dim, self_collision=True):
+ XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
+ self.model_xml = model_xml
+ self.doneLoading = 0
+
+ def reset(self, bullet_client):
+
+ self._p = bullet_client
+ #print("Created bullet_client with id=", self._p._client)
+ if (self.doneLoading == 0):
+ self.ordered_joints = []
+ self.doneLoading = 1
+ if self.self_collision:
+ self.objects = self._p.loadMJCF(os.path.join(pybullet_data.getDataPath(), "mjcf",
+ self.model_xml),
+ flags=pybullet.URDF_USE_SELF_COLLISION |
+ pybullet.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
+ self._p, self.objects)
+ else:
+ self.objects = self._p.loadMJCF(
+ os.path.join(pybullet_data.getDataPath(), "mjcf", self.model_xml))
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
+ self._p, self.objects)
+ self.robot_specific_reset(self._p)
+
+ s = self.calc_state(
+ ) # optimization: calc_state() can calculate something in self.* for calc_potential() to use
+
+ return s
+
+ def calc_potential(self):
+ return 0
class URDFBasedRobot(XmlBasedRobot):
- """
+ """
Base class for URDF .xml based robots.
"""
- def __init__(self, model_urdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
- XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
-
- self.model_urdf = model_urdf
- self.basePosition = basePosition
- self.baseOrientation = baseOrientation
- self.fixed_base = fixed_base
-
- def reset(self, bullet_client):
- self._p = bullet_client
- self.ordered_joints = []
-
- print(os.path.join(os.path.dirname(__file__), "data", self.model_urdf))
-
- if self.self_collision:
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
- self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
- basePosition=self.basePosition,
- baseOrientation=self.baseOrientation,
- useFixedBase=self.fixed_base,
- flags=pybullet.URDF_USE_SELF_COLLISION))
- else:
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p,
- self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
- basePosition=self.basePosition,
- baseOrientation=self.baseOrientation,
- useFixedBase=self.fixed_base))
-
- self.robot_specific_reset(self._p)
-
- s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
- self.potential = self.calc_potential()
-
- return s
-
- def calc_potential(self):
- return 0
+ def __init__(self,
+ model_urdf,
+ robot_name,
+ action_dim,
+ obs_dim,
+ basePosition=[0, 0, 0],
+ baseOrientation=[0, 0, 0, 1],
+ fixed_base=False,
+ self_collision=False):
+ XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
+
+ self.model_urdf = model_urdf
+ self.basePosition = basePosition
+ self.baseOrientation = baseOrientation
+ self.fixed_base = fixed_base
+
+ def reset(self, bullet_client):
+ self._p = bullet_client
+ self.ordered_joints = []
+
+ print(os.path.join(os.path.dirname(__file__), "data", self.model_urdf))
+
+ if self.self_collision:
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
+ self._p,
+ self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
+ basePosition=self.basePosition,
+ baseOrientation=self.baseOrientation,
+ useFixedBase=self.fixed_base,
+ flags=pybullet.URDF_USE_SELF_COLLISION))
+ else:
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
+ self._p,
+ self._p.loadURDF(os.path.join(pybullet_data.getDataPath(), self.model_urdf),
+ basePosition=self.basePosition,
+ baseOrientation=self.baseOrientation,
+ useFixedBase=self.fixed_base))
+
+ self.robot_specific_reset(self._p)
+
+ s = self.calc_state(
+ ) # optimization: calc_state() can calculate something in self.* for calc_potential() to use
+ self.potential = self.calc_potential()
+
+ return s
+
+ def calc_potential(self):
+ return 0
class SDFBasedRobot(XmlBasedRobot):
- """
+ """
Base class for SDF robots in a Scene.
"""
- def __init__(self, model_sdf, robot_name, action_dim, obs_dim, basePosition=[0, 0, 0], baseOrientation=[0, 0, 0, 1], fixed_base=False, self_collision=False):
- XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
-
- self.model_sdf = model_sdf
- self.fixed_base = fixed_base
+ def __init__(self,
+ model_sdf,
+ robot_name,
+ action_dim,
+ obs_dim,
+ basePosition=[0, 0, 0],
+ baseOrientation=[0, 0, 0, 1],
+ fixed_base=False,
+ self_collision=False):
+ XmlBasedRobot.__init__(self, robot_name, action_dim, obs_dim, self_collision)
- def reset(self, bullet_client):
- self._p = bullet_client
+ self.model_sdf = model_sdf
+ self.fixed_base = fixed_base
- self.ordered_joints = []
+ def reset(self, bullet_client):
+ self._p = bullet_client
- self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(self._p, # TODO: Not sure if this works, try it with kuka
- self._p.loadSDF(os.path.join("models_robot", self.model_sdf)))
+ self.ordered_joints = []
- self.robot_specific_reset(self._p)
+ self.parts, self.jdict, self.ordered_joints, self.robot_body = self.addToScene(
+ self._p, # TODO: Not sure if this works, try it with kuka
+ self._p.loadSDF(os.path.join("models_robot", self.model_sdf)))
- s = self.calc_state() # optimization: calc_state() can calculate something in self.* for calc_potential() to use
- self.potential = self.calc_potential()
+ self.robot_specific_reset(self._p)
- return s
+ s = self.calc_state(
+ ) # optimization: calc_state() can calculate something in self.* for calc_potential() to use
+ self.potential = self.calc_potential()
- def calc_potential(self):
- return 0
+ return s
+ def calc_potential(self):
+ return 0
-class Pose_Helper: # dummy class to comply to original interface
- def __init__(self, body_part):
- self.body_part = body_part
- def xyz(self):
- return self.body_part.current_position()
+class Pose_Helper: # dummy class to comply to original interface
- def rpy(self):
- return pybullet.getEulerFromQuaternion(self.body_part.current_orientation())
-
- def orientation(self):
- return self.body_part.current_orientation()
-
-class BodyPart:
- def __init__(self, bullet_client, body_name, bodies, bodyIndex, bodyPartIndex):
- self.bodies = bodies
- self._p = bullet_client
- self.bodyIndex = bodyIndex
- self.bodyPartIndex = bodyPartIndex
- self.initialPosition = self.current_position()
- self.initialOrientation = self.current_orientation()
- self.bp_pose = Pose_Helper(self)
+ def __init__(self, body_part):
+ self.body_part = body_part
- def state_fields_of_pose_of(self, body_id, link_id=-1): # a method you will most probably need a lot to get pose and orientation
- if link_id == -1:
- (x, y, z), (a, b, c, d) = self._p.getBasePositionAndOrientation(body_id)
- else:
- (x, y, z), (a, b, c, d), _, _, _, _ = self._p.getLinkState(body_id, link_id)
- return np.array([x, y, z, a, b, c, d])
+ def xyz(self):
+ return self.body_part.current_position()
- def get_position(self): return self.current_position()
+ def rpy(self):
+ return pybullet.getEulerFromQuaternion(self.body_part.current_orientation())
- def get_pose(self):
- return self.state_fields_of_pose_of(self.bodies[self.bodyIndex], self.bodyPartIndex)
+ def orientation(self):
+ return self.body_part.current_orientation()
- def speed(self):
- if self.bodyPartIndex == -1:
- (vx, vy, vz), _ = self._p.getBaseVelocity(self.bodies[self.bodyIndex])
- else:
- (x,y,z), (a,b,c,d), _,_,_,_, (vx, vy, vz), (vr,vp,vy) = self._p.getLinkState(self.bodies[self.bodyIndex], self.bodyPartIndex, computeLinkVelocity=1)
- return np.array([vx, vy, vz])
-
- def current_position(self):
- return self.get_pose()[:3]
-
- def current_orientation(self):
- return self.get_pose()[3:]
-
- def get_orientation(self):
- return self.current_orientation()
-
- def reset_position(self, position):
- self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, self.get_orientation())
-
- def reset_orientation(self, orientation):
- self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(), orientation)
-
- def reset_velocity(self, linearVelocity=[0,0,0], angularVelocity =[0,0,0]):
- self._p.resetBaseVelocity(self.bodies[self.bodyIndex], linearVelocity, angularVelocity)
-
- def reset_pose(self, position, orientation):
- self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
-
- def pose(self):
- return self.bp_pose
-
- def contact_list(self):
- return self._p.getContactPoints(self.bodies[self.bodyIndex], -1, self.bodyPartIndex, -1)
+class BodyPart:
-class Joint:
- def __init__(self, bullet_client, joint_name, bodies, bodyIndex, jointIndex):
- self.bodies = bodies
- self._p = bullet_client
- self.bodyIndex = bodyIndex
- self.jointIndex = jointIndex
- self.joint_name = joint_name
+ def __init__(self, bullet_client, body_name, bodies, bodyIndex, bodyPartIndex):
+ self.bodies = bodies
+ self._p = bullet_client
+ self.bodyIndex = bodyIndex
+ self.bodyPartIndex = bodyPartIndex
+ self.initialPosition = self.current_position()
+ self.initialOrientation = self.current_orientation()
+ self.bp_pose = Pose_Helper(self)
- jointInfo = self._p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
- self.lowerLimit = jointInfo[8]
- self.upperLimit = jointInfo[9]
+ def state_fields_of_pose_of(
+ self, body_id,
+ link_id=-1): # a method you will most probably need a lot to get pose and orientation
+ if link_id == -1:
+ (x, y, z), (a, b, c, d) = self._p.getBasePositionAndOrientation(body_id)
+ else:
+ (x, y, z), (a, b, c, d), _, _, _, _ = self._p.getLinkState(body_id, link_id)
+ return np.array([x, y, z, a, b, c, d])
- self.power_coeff = 0
+ def get_position(self):
+ return self.current_position()
- def set_state(self, x, vx):
- self._p.resetJointState(self.bodies[self.bodyIndex], self.jointIndex, x, vx)
+ def get_pose(self):
+ return self.state_fields_of_pose_of(self.bodies[self.bodyIndex], self.bodyPartIndex)
- def current_position(self): # just some synonyme method
- return self.get_state()
+ def speed(self):
+ if self.bodyPartIndex == -1:
+ (vx, vy, vz), _ = self._p.getBaseVelocity(self.bodies[self.bodyIndex])
+ else:
+ (x, y, z), (a, b, c, d), _, _, _, _, (vx, vy, vz), (vr, vp, vy) = self._p.getLinkState(
+ self.bodies[self.bodyIndex], self.bodyPartIndex, computeLinkVelocity=1)
+ return np.array([vx, vy, vz])
- def current_relative_position(self):
- pos, vel = self.get_state()
- pos_mid = 0.5 * (self.lowerLimit + self.upperLimit);
- return (
- 2 * (pos - pos_mid) / (self.upperLimit - self.lowerLimit),
- 0.1 * vel
- )
+ def current_position(self):
+ return self.get_pose()[:3]
- def get_state(self):
- x, vx,_,_ = self._p.getJointState(self.bodies[self.bodyIndex],self.jointIndex)
- return x, vx
+ def current_orientation(self):
+ return self.get_pose()[3:]
- def get_position(self):
- x, _ = self.get_state()
- return x
+ def get_orientation(self):
+ return self.current_orientation()
- def get_orientation(self):
- _,r = self.get_state()
- return r
+ def reset_position(self, position):
+ self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position,
+ self.get_orientation())
- def get_velocity(self):
- _, vx = self.get_state()
- return vx
+ def reset_orientation(self, orientation):
+ self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], self.get_position(),
+ orientation)
- def set_position(self, position):
- self._p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,pybullet.POSITION_CONTROL, targetPosition=position)
+ def reset_velocity(self, linearVelocity=[0, 0, 0], angularVelocity=[0, 0, 0]):
+ self._p.resetBaseVelocity(self.bodies[self.bodyIndex], linearVelocity, angularVelocity)
- def set_velocity(self, velocity):
- self._p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,pybullet.VELOCITY_CONTROL, targetVelocity=velocity)
+ def reset_pose(self, position, orientation):
+ self._p.resetBasePositionAndOrientation(self.bodies[self.bodyIndex], position, orientation)
- def set_motor_torque(self, torque): # just some synonyme method
- self.set_torque(torque)
+ def pose(self):
+ return self.bp_pose
- def set_torque(self, torque):
- self._p.setJointMotorControl2(bodyIndex=self.bodies[self.bodyIndex], jointIndex=self.jointIndex, controlMode=pybullet.TORQUE_CONTROL, force=torque) #, positionGain=0.1, velocityGain=0.1)
+ def contact_list(self):
+ return self._p.getContactPoints(self.bodies[self.bodyIndex], -1, self.bodyPartIndex, -1)
- def reset_current_position(self, position, velocity): # just some synonyme method
- self.reset_position(position, velocity)
- def reset_position(self, position, velocity):
- self._p.resetJointState(self.bodies[self.bodyIndex],self.jointIndex,targetValue=position, targetVelocity=velocity)
- self.disable_motor()
+class Joint:
- def disable_motor(self):
- self._p.setJointMotorControl2(self.bodies[self.bodyIndex],self.jointIndex,controlMode=pybullet.POSITION_CONTROL, targetPosition=0, targetVelocity=0, positionGain=0.1, velocityGain=0.1, force=0)
+ def __init__(self, bullet_client, joint_name, bodies, bodyIndex, jointIndex):
+ self.bodies = bodies
+ self._p = bullet_client
+ self.bodyIndex = bodyIndex
+ self.jointIndex = jointIndex
+ self.joint_name = joint_name
+
+ jointInfo = self._p.getJointInfo(self.bodies[self.bodyIndex], self.jointIndex)
+ self.lowerLimit = jointInfo[8]
+ self.upperLimit = jointInfo[9]
+
+ self.power_coeff = 0
+
+ def set_state(self, x, vx):
+ self._p.resetJointState(self.bodies[self.bodyIndex], self.jointIndex, x, vx)
+
+ def current_position(self): # just some synonyme method
+ return self.get_state()
+
+ def current_relative_position(self):
+ pos, vel = self.get_state()
+ pos_mid = 0.5 * (self.lowerLimit + self.upperLimit)
+ return (2 * (pos - pos_mid) / (self.upperLimit - self.lowerLimit), 0.1 * vel)
+
+ def get_state(self):
+ x, vx, _, _ = self._p.getJointState(self.bodies[self.bodyIndex], self.jointIndex)
+ return x, vx
+
+ def get_position(self):
+ x, _ = self.get_state()
+ return x
+
+ def get_orientation(self):
+ _, r = self.get_state()
+ return r
+
+ def get_velocity(self):
+ _, vx = self.get_state()
+ return vx
+
+ def set_position(self, position):
+ self._p.setJointMotorControl2(self.bodies[self.bodyIndex],
+ self.jointIndex,
+ pybullet.POSITION_CONTROL,
+ targetPosition=position)
+
+ def set_velocity(self, velocity):
+ self._p.setJointMotorControl2(self.bodies[self.bodyIndex],
+ self.jointIndex,
+ pybullet.VELOCITY_CONTROL,
+ targetVelocity=velocity)
+
+ def set_motor_torque(self, torque): # just some synonyme method
+ self.set_torque(torque)
+
+ def set_torque(self, torque):
+ self._p.setJointMotorControl2(bodyIndex=self.bodies[self.bodyIndex],
+ jointIndex=self.jointIndex,
+ controlMode=pybullet.TORQUE_CONTROL,
+ force=torque) #, positionGain=0.1, velocityGain=0.1)
+
+ def reset_current_position(self, position, velocity): # just some synonyme method
+ self.reset_position(position, velocity)
+
+ def reset_position(self, position, velocity):
+ self._p.resetJointState(self.bodies[self.bodyIndex],
+ self.jointIndex,
+ targetValue=position,
+ targetVelocity=velocity)
+ self.disable_motor()
+
+ def disable_motor(self):
+ self._p.setJointMotorControl2(self.bodies[self.bodyIndex],
+ self.jointIndex,
+ controlMode=pybullet.POSITION_CONTROL,
+ targetPosition=0,
+ targetVelocity=0,
+ positionGain=0.1,
+ velocityGain=0.1,
+ force=0)
diff --git a/examples/pybullet/gym/pybullet_envs/robot_locomotors.py b/examples/pybullet/gym/pybullet_envs/robot_locomotors.py
index 7ed7a1272..43ff604ac 100644
--- a/examples/pybullet/gym/pybullet_envs/robot_locomotors.py
+++ b/examples/pybullet/gym/pybullet_envs/robot_locomotors.py
@@ -1,321 +1,344 @@
from robot_bases import XmlBasedRobot, MJCFBasedRobot, URDFBasedRobot
import numpy as np
-import pybullet
+import pybullet
import os
import pybullet_data
from robot_bases import BodyPart
+
class WalkerBase(MJCFBasedRobot):
- def __init__(self, fn, robot_name, action_dim, obs_dim, power):
- MJCFBasedRobot.__init__(self, fn, robot_name, action_dim, obs_dim)
- self.power = power
- self.camera_x = 0
- self.start_pos_x, self.start_pos_y, self.start_pos_z = 0, 0, 0
- self.walk_target_x = 1e3 # kilometer away
- self.walk_target_y = 0
- self.body_xyz=[0,0,0]
-
- def robot_specific_reset(self, bullet_client):
- self._p = bullet_client
- for j in self.ordered_joints:
- j.reset_current_position(self.np_random.uniform(low=-0.1, high=0.1), 0)
-
- self.feet = [self.parts[f] for f in self.foot_list]
- self.feet_contact = np.array([0.0 for f in self.foot_list], dtype=np.float32)
- self.scene.actor_introduce(self)
- self.initial_z = None
-
- def apply_action(self, a):
- assert (np.isfinite(a).all())
- for n, j in enumerate(self.ordered_joints):
- j.set_motor_torque(self.power * j.power_coef * float(np.clip(a[n], -1, +1)))
-
- def calc_state(self):
- j = np.array([j.current_relative_position() for j in self.ordered_joints], dtype=np.float32).flatten()
- # even elements [0::2] position, scaled to -1..+1 between limits
- # odd elements [1::2] angular speed, scaled to show -1..+1
- self.joint_speeds = j[1::2]
- self.joints_at_limit = np.count_nonzero(np.abs(j[0::2]) > 0.99)
-
- body_pose = self.robot_body.pose()
- parts_xyz = np.array([p.pose().xyz() for p in self.parts.values()]).flatten()
- self.body_xyz = (
- parts_xyz[0::3].mean(), parts_xyz[1::3].mean(), body_pose.xyz()[2]) # torso z is more informative than mean z
- self.body_rpy = body_pose.rpy()
- z = self.body_xyz[2]
- if self.initial_z == None:
- self.initial_z = z
- r, p, yaw = self.body_rpy
- self.walk_target_theta = np.arctan2(self.walk_target_y - self.body_xyz[1],
- self.walk_target_x - self.body_xyz[0])
- self.walk_target_dist = np.linalg.norm(
- [self.walk_target_y - self.body_xyz[1], self.walk_target_x - self.body_xyz[0]])
- angle_to_target = self.walk_target_theta - yaw
-
- rot_speed = np.array(
- [[np.cos(-yaw), -np.sin(-yaw), 0],
- [np.sin(-yaw), np.cos(-yaw), 0],
- [ 0, 0, 1]]
- )
- vx, vy, vz = np.dot(rot_speed, self.robot_body.speed()) # rotate speed back to body point of view
-
- more = np.array([ z-self.initial_z,
- np.sin(angle_to_target), np.cos(angle_to_target),
- 0.3* vx , 0.3* vy , 0.3* vz , # 0.3 is just scaling typical speed into -1..+1, no physical sense here
- r, p], dtype=np.float32)
- return np.clip( np.concatenate([more] + [j] + [self.feet_contact]), -5, +5)
-
- def calc_potential(self):
- # progress in potential field is speed*dt, typical speed is about 2-3 meter per second, this potential will change 2-3 per frame (not per second),
- # all rewards have rew/frame units and close to 1.0
- debugmode=0
- if (debugmode):
- print("calc_potential: self.walk_target_dist")
- print(self.walk_target_dist)
- print("self.scene.dt")
- print(self.scene.dt)
- print("self.scene.frame_skip")
- print(self.scene.frame_skip)
- print("self.scene.timestep")
- print(self.scene.timestep)
- return - self.walk_target_dist / self.scene.dt
+
+ def __init__(self, fn, robot_name, action_dim, obs_dim, power):
+ MJCFBasedRobot.__init__(self, fn, robot_name, action_dim, obs_dim)
+ self.power = power
+ self.camera_x = 0
+ self.start_pos_x, self.start_pos_y, self.start_pos_z = 0, 0, 0
+ self.walk_target_x = 1e3 # kilometer away
+ self.walk_target_y = 0
+ self.body_xyz = [0, 0, 0]
+
+ def robot_specific_reset(self, bullet_client):
+ self._p = bullet_client
+ for j in self.ordered_joints:
+ j.reset_current_position(self.np_random.uniform(low=-0.1, high=0.1), 0)
+
+ self.feet = [self.parts[f] for f in self.foot_list]
+ self.feet_contact = np.array([0.0 for f in self.foot_list], dtype=np.float32)
+ self.scene.actor_introduce(self)
+ self.initial_z = None
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ for n, j in enumerate(self.ordered_joints):
+ j.set_motor_torque(self.power * j.power_coef * float(np.clip(a[n], -1, +1)))
+
+ def calc_state(self):
+ j = np.array([j.current_relative_position() for j in self.ordered_joints],
+ dtype=np.float32).flatten()
+ # even elements [0::2] position, scaled to -1..+1 between limits
+ # odd elements [1::2] angular speed, scaled to show -1..+1
+ self.joint_speeds = j[1::2]
+ self.joints_at_limit = np.count_nonzero(np.abs(j[0::2]) > 0.99)
+
+ body_pose = self.robot_body.pose()
+ parts_xyz = np.array([p.pose().xyz() for p in self.parts.values()]).flatten()
+ self.body_xyz = (parts_xyz[0::3].mean(), parts_xyz[1::3].mean(), body_pose.xyz()[2]
+ ) # torso z is more informative than mean z
+ self.body_rpy = body_pose.rpy()
+ z = self.body_xyz[2]
+ if self.initial_z == None:
+ self.initial_z = z
+ r, p, yaw = self.body_rpy
+ self.walk_target_theta = np.arctan2(self.walk_target_y - self.body_xyz[1],
+ self.walk_target_x - self.body_xyz[0])
+ self.walk_target_dist = np.linalg.norm(
+ [self.walk_target_y - self.body_xyz[1], self.walk_target_x - self.body_xyz[0]])
+ angle_to_target = self.walk_target_theta - yaw
+
+ rot_speed = np.array([[np.cos(-yaw), -np.sin(-yaw), 0], [np.sin(-yaw),
+ np.cos(-yaw), 0], [0, 0, 1]])
+ vx, vy, vz = np.dot(rot_speed,
+ self.robot_body.speed()) # rotate speed back to body point of view
+
+ more = np.array(
+ [
+ z - self.initial_z,
+ np.sin(angle_to_target),
+ np.cos(angle_to_target),
+ 0.3 * vx,
+ 0.3 * vy,
+ 0.3 * vz, # 0.3 is just scaling typical speed into -1..+1, no physical sense here
+ r,
+ p
+ ],
+ dtype=np.float32)
+ return np.clip(np.concatenate([more] + [j] + [self.feet_contact]), -5, +5)
+
+ def calc_potential(self):
+ # progress in potential field is speed*dt, typical speed is about 2-3 meter per second, this potential will change 2-3 per frame (not per second),
+ # all rewards have rew/frame units and close to 1.0
+ debugmode = 0
+ if (debugmode):
+ print("calc_potential: self.walk_target_dist")
+ print(self.walk_target_dist)
+ print("self.scene.dt")
+ print(self.scene.dt)
+ print("self.scene.frame_skip")
+ print(self.scene.frame_skip)
+ print("self.scene.timestep")
+ print(self.scene.timestep)
+ return -self.walk_target_dist / self.scene.dt
class Hopper(WalkerBase):
- foot_list = ["foot"]
+ foot_list = ["foot"]
- def __init__(self):
- WalkerBase.__init__(self, "hopper.xml", "torso", action_dim=3, obs_dim=15, power=0.75)
+ def __init__(self):
+ WalkerBase.__init__(self, "hopper.xml", "torso", action_dim=3, obs_dim=15, power=0.75)
- def alive_bonus(self, z, pitch):
- return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
+ def alive_bonus(self, z, pitch):
+ return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
class Walker2D(WalkerBase):
- foot_list = ["foot", "foot_left"]
+ foot_list = ["foot", "foot_left"]
- def __init__(self):
- WalkerBase.__init__(self, "walker2d.xml", "torso", action_dim=6, obs_dim=22, power=0.40)
+ def __init__(self):
+ WalkerBase.__init__(self, "walker2d.xml", "torso", action_dim=6, obs_dim=22, power=0.40)
- def alive_bonus(self, z, pitch):
- return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
+ def alive_bonus(self, z, pitch):
+ return +1 if z > 0.8 and abs(pitch) < 1.0 else -1
- def robot_specific_reset(self, bullet_client):
- WalkerBase.robot_specific_reset(self, bullet_client)
- for n in ["foot_joint", "foot_left_joint"]:
- self.jdict[n].power_coef = 30.0
+ def robot_specific_reset(self, bullet_client):
+ WalkerBase.robot_specific_reset(self, bullet_client)
+ for n in ["foot_joint", "foot_left_joint"]:
+ self.jdict[n].power_coef = 30.0
class HalfCheetah(WalkerBase):
- foot_list = ["ffoot", "fshin", "fthigh", "bfoot", "bshin", "bthigh"] # track these contacts with ground
+ foot_list = ["ffoot", "fshin", "fthigh", "bfoot", "bshin",
+ "bthigh"] # track these contacts with ground
- def __init__(self):
- WalkerBase.__init__(self, "half_cheetah.xml", "torso", action_dim=6, obs_dim=26, power=0.90)
+ def __init__(self):
+ WalkerBase.__init__(self, "half_cheetah.xml", "torso", action_dim=6, obs_dim=26, power=0.90)
- def alive_bonus(self, z, pitch):
- # Use contact other than feet to terminate episode: due to a lot of strange walks using knees
- return +1 if np.abs(pitch) < 1.0 and not self.feet_contact[1] and not self.feet_contact[2] and not self.feet_contact[4] and not self.feet_contact[5] else -1
+ def alive_bonus(self, z, pitch):
+ # Use contact other than feet to terminate episode: due to a lot of strange walks using knees
+ return +1 if np.abs(pitch) < 1.0 and not self.feet_contact[1] and not self.feet_contact[
+ 2] and not self.feet_contact[4] and not self.feet_contact[5] else -1
- def robot_specific_reset(self, bullet_client):
- WalkerBase.robot_specific_reset(self, bullet_client)
- self.jdict["bthigh"].power_coef = 120.0
- self.jdict["bshin"].power_coef = 90.0
- self.jdict["bfoot"].power_coef = 60.0
- self.jdict["fthigh"].power_coef = 140.0
- self.jdict["fshin"].power_coef = 60.0
- self.jdict["ffoot"].power_coef = 30.0
+ def robot_specific_reset(self, bullet_client):
+ WalkerBase.robot_specific_reset(self, bullet_client)
+ self.jdict["bthigh"].power_coef = 120.0
+ self.jdict["bshin"].power_coef = 90.0
+ self.jdict["bfoot"].power_coef = 60.0
+ self.jdict["fthigh"].power_coef = 140.0
+ self.jdict["fshin"].power_coef = 60.0
+ self.jdict["ffoot"].power_coef = 30.0
class Ant(WalkerBase):
- foot_list = ['front_left_foot', 'front_right_foot', 'left_back_foot', 'right_back_foot']
+ foot_list = ['front_left_foot', 'front_right_foot', 'left_back_foot', 'right_back_foot']
- def __init__(self):
- WalkerBase.__init__(self, "ant.xml", "torso", action_dim=8, obs_dim=28, power=2.5)
+ def __init__(self):
+ WalkerBase.__init__(self, "ant.xml", "torso", action_dim=8, obs_dim=28, power=2.5)
- def alive_bonus(self, z, pitch):
- return +1 if z > 0.26 else -1 # 0.25 is central sphere rad, die if it scrapes the ground
+ def alive_bonus(self, z, pitch):
+ return +1 if z > 0.26 else -1 # 0.25 is central sphere rad, die if it scrapes the ground
class Humanoid(WalkerBase):
- self_collision = True
- foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
-
- def __init__(self):
- WalkerBase.__init__(self, 'humanoid_symmetric.xml', 'torso', action_dim=17, obs_dim=44, power=0.41)
- # 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25
-
- def robot_specific_reset(self, bullet_client):
- WalkerBase.robot_specific_reset(self, bullet_client)
- self.motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"]
- self.motor_power = [100, 100, 100]
- self.motor_names += ["right_hip_x", "right_hip_z", "right_hip_y", "right_knee"]
- self.motor_power += [100, 100, 300, 200]
- self.motor_names += ["left_hip_x", "left_hip_z", "left_hip_y", "left_knee"]
- self.motor_power += [100, 100, 300, 200]
- self.motor_names += ["right_shoulder1", "right_shoulder2", "right_elbow"]
- self.motor_power += [75, 75, 75]
- self.motor_names += ["left_shoulder1", "left_shoulder2", "left_elbow"]
- self.motor_power += [75, 75, 75]
- self.motors = [self.jdict[n] for n in self.motor_names]
- if self.random_yaw:
- position = [0,0,0]
- orientation = [0,0,0]
- yaw = self.np_random.uniform(low=-3.14, high=3.14)
- if self.random_lean and self.np_random.randint(2)==0:
- cpose.set_xyz(0, 0, 1.4)
- if self.np_random.randint(2)==0:
- pitch = np.pi/2
- position = [0, 0, 0.45]
- else:
- pitch = np.pi*3/2
- position = [0, 0, 0.25]
- roll = 0
- orientation = [roll, pitch, yaw]
- else:
- position = [0, 0, 1.4]
- orientation = [0, 0, yaw] # just face random direction, but stay straight otherwise
- self.robot_body.reset_position(position)
- self.robot_body.reset_orientation(orientation)
- self.initial_z = 0.8
-
- random_yaw = False
- random_lean = False
-
- def apply_action(self, a):
- assert( np.isfinite(a).all() )
- force_gain = 1
- for i, m, power in zip(range(17), self.motors, self.motor_power):
- m.set_motor_torque(float(force_gain * power * self.power * np.clip(a[i], -1, +1)))
-
- def alive_bonus(self, z, pitch):
- return +2 if z > 0.78 else -1 # 2 here because 17 joints produce a lot of electricity cost just from policy noise, living must be better than dying
-
-
-
-
-def get_cube(_p, x, y, z):
- body = _p.loadURDF(os.path.join(pybullet_data.getDataPath(),"cube_small.urdf"), [x, y, z])
- _p.changeDynamics(body,-1, mass=1.2)#match Roboschool
- part_name, _ = _p.getBodyInfo(body)
- part_name = part_name.decode("utf8")
- bodies = [body]
- return BodyPart(_p, part_name, bodies, 0, -1)
+ self_collision = True
+ foot_list = ["right_foot", "left_foot"] # "left_hand", "right_hand"
+
+ def __init__(self):
+ WalkerBase.__init__(self,
+ 'humanoid_symmetric.xml',
+ 'torso',
+ action_dim=17,
+ obs_dim=44,
+ power=0.41)
+ # 17 joints, 4 of them important for walking (hip, knee), others may as well be turned off, 17/4 = 4.25
+
+ def robot_specific_reset(self, bullet_client):
+ WalkerBase.robot_specific_reset(self, bullet_client)
+ self.motor_names = ["abdomen_z", "abdomen_y", "abdomen_x"]
+ self.motor_power = [100, 100, 100]
+ self.motor_names += ["right_hip_x", "right_hip_z", "right_hip_y", "right_knee"]
+ self.motor_power += [100, 100, 300, 200]
+ self.motor_names += ["left_hip_x", "left_hip_z", "left_hip_y", "left_knee"]
+ self.motor_power += [100, 100, 300, 200]
+ self.motor_names += ["right_shoulder1", "right_shoulder2", "right_elbow"]
+ self.motor_power += [75, 75, 75]
+ self.motor_names += ["left_shoulder1", "left_shoulder2", "left_elbow"]
+ self.motor_power += [75, 75, 75]
+ self.motors = [self.jdict[n] for n in self.motor_names]
+ if self.random_yaw:
+ position = [0, 0, 0]
+ orientation = [0, 0, 0]
+ yaw = self.np_random.uniform(low=-3.14, high=3.14)
+ if self.random_lean and self.np_random.randint(2) == 0:
+ cpose.set_xyz(0, 0, 1.4)
+ if self.np_random.randint(2) == 0:
+ pitch = np.pi / 2
+ position = [0, 0, 0.45]
+ else:
+ pitch = np.pi * 3 / 2
+ position = [0, 0, 0.25]
+ roll = 0
+ orientation = [roll, pitch, yaw]
+ else:
+ position = [0, 0, 1.4]
+ orientation = [0, 0, yaw] # just face random direction, but stay straight otherwise
+ self.robot_body.reset_position(position)
+ self.robot_body.reset_orientation(orientation)
+ self.initial_z = 0.8
+
+ random_yaw = False
+ random_lean = False
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ force_gain = 1
+ for i, m, power in zip(range(17), self.motors, self.motor_power):
+ m.set_motor_torque(float(force_gain * power * self.power * np.clip(a[i], -1, +1)))
+
+ def alive_bonus(self, z, pitch):
+ return +2 if z > 0.78 else -1 # 2 here because 17 joints produce a lot of electricity cost just from policy noise, living must be better than dying
+
+
+def get_cube(_p, x, y, z):
+ body = _p.loadURDF(os.path.join(pybullet_data.getDataPath(), "cube_small.urdf"), [x, y, z])
+ _p.changeDynamics(body, -1, mass=1.2) #match Roboschool
+ part_name, _ = _p.getBodyInfo(body)
+ part_name = part_name.decode("utf8")
+ bodies = [body]
+ return BodyPart(_p, part_name, bodies, 0, -1)
def get_sphere(_p, x, y, z):
- body = _p.loadURDF(os.path.join(pybullet_data.getDataPath(),"sphere2red_nocol.urdf"), [x, y, z])
- part_name, _ = _p.getBodyInfo(body)
- part_name = part_name.decode("utf8")
- bodies = [body]
- return BodyPart(_p, part_name, bodies, 0, -1)
+ body = _p.loadURDF(os.path.join(pybullet_data.getDataPath(), "sphere2red_nocol.urdf"), [x, y, z])
+ part_name, _ = _p.getBodyInfo(body)
+ part_name = part_name.decode("utf8")
+ bodies = [body]
+ return BodyPart(_p, part_name, bodies, 0, -1)
+
class HumanoidFlagrun(Humanoid):
- def __init__(self):
- Humanoid.__init__(self)
- self.flag = None
-
- def robot_specific_reset(self, bullet_client):
- Humanoid.robot_specific_reset(self, bullet_client)
- self.flag_reposition()
-
- def flag_reposition(self):
- self.walk_target_x = self.np_random.uniform(low=-self.scene.stadium_halflen, high=+self.scene.stadium_halflen)
- self.walk_target_y = self.np_random.uniform(low=-self.scene.stadium_halfwidth, high=+self.scene.stadium_halfwidth)
- more_compact = 0.5 # set to 1.0 whole football field
- self.walk_target_x *= more_compact
- self.walk_target_y *= more_compact
-
- if (self.flag):
- #for b in self.flag.bodies:
- # print("remove body uid",b)
- # p.removeBody(b)
- self._p.resetBasePositionAndOrientation(self.flag.bodies[0],[self.walk_target_x, self.walk_target_y, 0.7],[0,0,0,1])
- else:
- self.flag = get_sphere(self._p, self.walk_target_x, self.walk_target_y, 0.7)
- self.flag_timeout = 600/self.scene.frame_skip #match Roboschool
-
- def calc_state(self):
- self.flag_timeout -= 1
- state = Humanoid.calc_state(self)
- if self.walk_target_dist < 1 or self.flag_timeout <= 0:
- self.flag_reposition()
- state = Humanoid.calc_state(self) # caclulate state again, against new flag pos
- self.potential = self.calc_potential() # avoid reward jump
- return state
+
+ def __init__(self):
+ Humanoid.__init__(self)
+ self.flag = None
+
+ def robot_specific_reset(self, bullet_client):
+ Humanoid.robot_specific_reset(self, bullet_client)
+ self.flag_reposition()
+
+ def flag_reposition(self):
+ self.walk_target_x = self.np_random.uniform(low=-self.scene.stadium_halflen,
+ high=+self.scene.stadium_halflen)
+ self.walk_target_y = self.np_random.uniform(low=-self.scene.stadium_halfwidth,
+ high=+self.scene.stadium_halfwidth)
+ more_compact = 0.5 # set to 1.0 whole football field
+ self.walk_target_x *= more_compact
+ self.walk_target_y *= more_compact
+
+ if (self.flag):
+ #for b in self.flag.bodies:
+ # print("remove body uid",b)
+ # p.removeBody(b)
+ self._p.resetBasePositionAndOrientation(self.flag.bodies[0],
+ [self.walk_target_x, self.walk_target_y, 0.7],
+ [0, 0, 0, 1])
+ else:
+ self.flag = get_sphere(self._p, self.walk_target_x, self.walk_target_y, 0.7)
+ self.flag_timeout = 600 / self.scene.frame_skip #match Roboschool
+
+ def calc_state(self):
+ self.flag_timeout -= 1
+ state = Humanoid.calc_state(self)
+ if self.walk_target_dist < 1 or self.flag_timeout <= 0:
+ self.flag_reposition()
+ state = Humanoid.calc_state(self) # caclulate state again, against new flag pos
+ self.potential = self.calc_potential() # avoid reward jump
+ return state
class HumanoidFlagrunHarder(HumanoidFlagrun):
- def __init__(self):
- HumanoidFlagrun.__init__(self)
- self.flag = None
- self.aggressive_cube = None
- self.frame = 0
-
- def robot_specific_reset(self, bullet_client):
-
- HumanoidFlagrun.robot_specific_reset(self, bullet_client)
-
- self.frame = 0
- if (self.aggressive_cube):
- self._p.resetBasePositionAndOrientation(self.aggressive_cube.bodies[0],[-1.5,0,0.05],[0,0,0,1])
- else:
- self.aggressive_cube = get_cube(self._p, -1.5,0,0.05)
- self.on_ground_frame_counter = 0
- self.crawl_start_potential = None
- self.crawl_ignored_potential = 0.0
- self.initial_z = 0.8
-
- def alive_bonus(self, z, pitch):
- if self.frame%30==0 and self.frame>100 and self.on_ground_frame_counter==0:
- target_xyz = np.array(self.body_xyz)
- robot_speed = np.array(self.robot_body.speed())
- angle = self.np_random.uniform(low=-3.14, high=3.14)
- from_dist = 4.0
- attack_speed = self.np_random.uniform(low=20.0, high=30.0) # speed 20..30 (* mass in cube.urdf = impulse)
- time_to_travel = from_dist / attack_speed
- target_xyz += robot_speed*time_to_travel # predict future position at the moment the cube hits the robot
- position = [target_xyz[0] + from_dist*np.cos(angle),
- target_xyz[1] + from_dist*np.sin(angle),
- target_xyz[2] + 1.0]
- attack_speed_vector = target_xyz - np.array(position)
- attack_speed_vector *= attack_speed / np.linalg.norm(attack_speed_vector)
- attack_speed_vector += self.np_random.uniform(low=-1.0, high=+1.0, size=(3,))
- self.aggressive_cube.reset_position(position)
- self.aggressive_cube.reset_velocity(linearVelocity=attack_speed_vector)
- if z < 0.8:
- self.on_ground_frame_counter += 1
- elif self.on_ground_frame_counter > 0:
- self.on_ground_frame_counter -= 1
- # End episode if the robot can't get up in 170 frames, to save computation and decorrelate observations.
- self.frame += 1
- return self.potential_leak() if self.on_ground_frame_counter<170 else -1
-
- def potential_leak(self):
- z = self.body_xyz[2] # 0.00 .. 0.8 .. 1.05 normal walk, 1.2 when jumping
- z = np.clip(z, 0, 0.8)
- return z/0.8 + 1.0 # 1.00 .. 2.0
-
- def calc_potential(self):
- # We see alive bonus here as a leak from potential field. Value V(s) of a given state equals
- # potential, if it is topped up with gamma*potential every frame. Gamma is assumed 0.99.
- #
- # 2.0 alive bonus if z>0.8, potential is 200, leak gamma=0.99, (1-0.99)*200==2.0
- # 1.0 alive bonus on the ground z==0, potential is 100, leak (1-0.99)*100==1.0
- #
- # Why robot whould stand up: to receive 100 points in potential field difference.
- flag_running_progress = Humanoid.calc_potential(self)
-
- # This disables crawl.
- if self.body_xyz[2] < 0.8:
- if self.crawl_start_potential is None:
- self.crawl_start_potential = flag_running_progress - self.crawl_ignored_potential
- #print("CRAWL START %+0.1f %+0.1f" % (self.crawl_start_potential, flag_running_progress))
- self.crawl_ignored_potential = flag_running_progress - self.crawl_start_potential
- flag_running_progress = self.crawl_start_potential
- else:
- #print("CRAWL STOP %+0.1f %+0.1f" % (self.crawl_ignored_potential, flag_running_progress))
- flag_running_progress -= self.crawl_ignored_potential
- self.crawl_start_potential = None
-
- return flag_running_progress + self.potential_leak()*100
+ def __init__(self):
+ HumanoidFlagrun.__init__(self)
+ self.flag = None
+ self.aggressive_cube = None
+ self.frame = 0
+
+ def robot_specific_reset(self, bullet_client):
+
+ HumanoidFlagrun.robot_specific_reset(self, bullet_client)
+
+ self.frame = 0
+ if (self.aggressive_cube):
+ self._p.resetBasePositionAndOrientation(self.aggressive_cube.bodies[0], [-1.5, 0, 0.05],
+ [0, 0, 0, 1])
+ else:
+ self.aggressive_cube = get_cube(self._p, -1.5, 0, 0.05)
+ self.on_ground_frame_counter = 0
+ self.crawl_start_potential = None
+ self.crawl_ignored_potential = 0.0
+ self.initial_z = 0.8
+
+ def alive_bonus(self, z, pitch):
+ if self.frame % 30 == 0 and self.frame > 100 and self.on_ground_frame_counter == 0:
+ target_xyz = np.array(self.body_xyz)
+ robot_speed = np.array(self.robot_body.speed())
+ angle = self.np_random.uniform(low=-3.14, high=3.14)
+ from_dist = 4.0
+ attack_speed = self.np_random.uniform(
+ low=20.0, high=30.0) # speed 20..30 (* mass in cube.urdf = impulse)
+ time_to_travel = from_dist / attack_speed
+ target_xyz += robot_speed * time_to_travel # predict future position at the moment the cube hits the robot
+ position = [
+ target_xyz[0] + from_dist * np.cos(angle), target_xyz[1] + from_dist * np.sin(angle),
+ target_xyz[2] + 1.0
+ ]
+ attack_speed_vector = target_xyz - np.array(position)
+ attack_speed_vector *= attack_speed / np.linalg.norm(attack_speed_vector)
+ attack_speed_vector += self.np_random.uniform(low=-1.0, high=+1.0, size=(3,))
+ self.aggressive_cube.reset_position(position)
+ self.aggressive_cube.reset_velocity(linearVelocity=attack_speed_vector)
+ if z < 0.8:
+ self.on_ground_frame_counter += 1
+ elif self.on_ground_frame_counter > 0:
+ self.on_ground_frame_counter -= 1
+ # End episode if the robot can't get up in 170 frames, to save computation and decorrelate observations.
+ self.frame += 1
+ return self.potential_leak() if self.on_ground_frame_counter < 170 else -1
+
+ def potential_leak(self):
+ z = self.body_xyz[2] # 0.00 .. 0.8 .. 1.05 normal walk, 1.2 when jumping
+ z = np.clip(z, 0, 0.8)
+ return z / 0.8 + 1.0 # 1.00 .. 2.0
+
+ def calc_potential(self):
+ # We see alive bonus here as a leak from potential field. Value V(s) of a given state equals
+ # potential, if it is topped up with gamma*potential every frame. Gamma is assumed 0.99.
+ #
+ # 2.0 alive bonus if z>0.8, potential is 200, leak gamma=0.99, (1-0.99)*200==2.0
+ # 1.0 alive bonus on the ground z==0, potential is 100, leak (1-0.99)*100==1.0
+ #
+ # Why robot whould stand up: to receive 100 points in potential field difference.
+ flag_running_progress = Humanoid.calc_potential(self)
+
+ # This disables crawl.
+ if self.body_xyz[2] < 0.8:
+ if self.crawl_start_potential is None:
+ self.crawl_start_potential = flag_running_progress - self.crawl_ignored_potential
+ #print("CRAWL START %+0.1f %+0.1f" % (self.crawl_start_potential, flag_running_progress))
+ self.crawl_ignored_potential = flag_running_progress - self.crawl_start_potential
+ flag_running_progress = self.crawl_start_potential
+ else:
+ #print("CRAWL STOP %+0.1f %+0.1f" % (self.crawl_ignored_potential, flag_running_progress))
+ flag_running_progress -= self.crawl_ignored_potential
+ self.crawl_start_potential = None
+
+ return flag_running_progress + self.potential_leak() * 100
diff --git a/examples/pybullet/gym/pybullet_envs/robot_manipulators.py b/examples/pybullet/gym/pybullet_envs/robot_manipulators.py
index 07e41888e..30f2a3805 100644
--- a/examples/pybullet/gym/pybullet_envs/robot_manipulators.py
+++ b/examples/pybullet/gym/pybullet_envs/robot_manipulators.py
@@ -3,308 +3,317 @@ import numpy as np
class Reacher(MJCFBasedRobot):
- TARG_LIMIT = 0.27
-
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'reacher.xml', 'body0', action_dim=2, obs_dim=9)
-
- def robot_specific_reset(self, bullet_client):
- self.jdict["target_x"].reset_current_position(
- self.np_random.uniform(low=-self.TARG_LIMIT, high=self.TARG_LIMIT), 0)
- self.jdict["target_y"].reset_current_position(
- self.np_random.uniform(low=-self.TARG_LIMIT, high=self.TARG_LIMIT), 0)
- self.fingertip = self.parts["fingertip"]
- self.target = self.parts["target"]
- self.central_joint = self.jdict["joint0"]
- self.elbow_joint = self.jdict["joint1"]
- self.central_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.elbow_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
-
- def apply_action(self, a):
- assert (np.isfinite(a).all())
- self.central_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
- self.elbow_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
-
- def calc_state(self):
- theta, self.theta_dot = self.central_joint.current_relative_position()
- self.gamma, self.gamma_dot = self.elbow_joint.current_relative_position()
- target_x, _ = self.jdict["target_x"].current_position()
- target_y, _ = self.jdict["target_y"].current_position()
- self.to_target_vec = np.array(self.fingertip.pose().xyz()) - np.array(self.target.pose().xyz())
- return np.array([
- target_x,
- target_y,
- self.to_target_vec[0],
- self.to_target_vec[1],
- np.cos(theta),
- np.sin(theta),
- self.theta_dot,
- self.gamma,
- self.gamma_dot,
- ])
-
- def calc_potential(self):
- return -100 * np.linalg.norm(self.to_target_vec)
+ TARG_LIMIT = 0.27
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'reacher.xml', 'body0', action_dim=2, obs_dim=9)
+
+ def robot_specific_reset(self, bullet_client):
+ self.jdict["target_x"].reset_current_position(
+ self.np_random.uniform(low=-self.TARG_LIMIT, high=self.TARG_LIMIT), 0)
+ self.jdict["target_y"].reset_current_position(
+ self.np_random.uniform(low=-self.TARG_LIMIT, high=self.TARG_LIMIT), 0)
+ self.fingertip = self.parts["fingertip"]
+ self.target = self.parts["target"]
+ self.central_joint = self.jdict["joint0"]
+ self.elbow_joint = self.jdict["joint1"]
+ self.central_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.elbow_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ self.central_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
+ self.elbow_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
+
+ def calc_state(self):
+ theta, self.theta_dot = self.central_joint.current_relative_position()
+ self.gamma, self.gamma_dot = self.elbow_joint.current_relative_position()
+ target_x, _ = self.jdict["target_x"].current_position()
+ target_y, _ = self.jdict["target_y"].current_position()
+ self.to_target_vec = np.array(self.fingertip.pose().xyz()) - np.array(self.target.pose().xyz())
+ return np.array([
+ target_x,
+ target_y,
+ self.to_target_vec[0],
+ self.to_target_vec[1],
+ np.cos(theta),
+ np.sin(theta),
+ self.theta_dot,
+ self.gamma,
+ self.gamma_dot,
+ ])
+
+ def calc_potential(self):
+ return -100 * np.linalg.norm(self.to_target_vec)
class Pusher(MJCFBasedRobot):
- min_target_placement_radius = 0.5
- max_target_placement_radius = 0.8
- min_object_to_target_distance = 0.1
- max_object_to_target_distance = 0.4
-
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'pusher.xml', 'body0', action_dim=7, obs_dim=55)
-
- def robot_specific_reset(self, bullet_client):
- # parts
- self.fingertip = self.parts["fingertip"]
- self.target = self.parts["target"]
- self.object = self.parts["object"]
-
- # joints
- self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
- self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
- self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
- self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
- self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
- self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
- self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
-
- self.target_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_target_placement_radius
- self.target_pos = self.target_pos \
- / np.linalg.norm(self.target_pos) \
- * self.np_random.uniform(low=self.min_target_placement_radius,
- high=self.max_target_placement_radius, size=1)
-
- self.object_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_object_to_target_distance
- self.object_pos = self.object_pos \
- / np.linalg.norm(self.object_pos - self.target_pos) \
- * self.np_random.uniform(low=self.min_object_to_target_distance,
- high=self.max_object_to_target_distance, size=1)
-
- # set position of objects
- self.zero_offset = np.array([0.45, 0.55])
- self.jdict["target_x"].reset_current_position(self.target_pos[0] - self.zero_offset[0], 0)
- self.jdict["target_y"].reset_current_position(self.target_pos[1] - self.zero_offset[1], 0)
- self.jdict["object_x"].reset_current_position(self.object_pos[0] - self.zero_offset[0], 0)
- self.jdict["object_y"].reset_current_position(self.object_pos[1] - self.zero_offset[1], 0)
-
- # randomize all joints TODO: Will this work or do we have to constrain this resetting in some way?
- self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
-
- def apply_action(self, a):
- assert (np.isfinite(a).all())
- self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
- self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
- self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
- self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
- self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
- self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
- self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
-
- def calc_state(self):
- self.to_target_vec = self.target_pos - self.object_pos
- return np.concatenate([
- np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
- np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # all speeds
- self.to_target_vec,
- self.fingertip.pose().xyz(),
- self.object.pose().xyz(),
- self.target.pose().xyz(),
- ])
+ min_target_placement_radius = 0.5
+ max_target_placement_radius = 0.8
+ min_object_to_target_distance = 0.1
+ max_object_to_target_distance = 0.4
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'pusher.xml', 'body0', action_dim=7, obs_dim=55)
+
+ def robot_specific_reset(self, bullet_client):
+ # parts
+ self.fingertip = self.parts["fingertip"]
+ self.target = self.parts["target"]
+ self.object = self.parts["object"]
+
+ # joints
+ self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
+ self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
+ self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
+ self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
+ self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
+ self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
+ self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
+
+ self.target_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_target_placement_radius
+ self.target_pos = self.target_pos \
+ / np.linalg.norm(self.target_pos) \
+ * self.np_random.uniform(low=self.min_target_placement_radius,
+ high=self.max_target_placement_radius, size=1)
+
+ self.object_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_object_to_target_distance
+ self.object_pos = self.object_pos \
+ / np.linalg.norm(self.object_pos - self.target_pos) \
+ * self.np_random.uniform(low=self.min_object_to_target_distance,
+ high=self.max_object_to_target_distance, size=1)
+
+ # set position of objects
+ self.zero_offset = np.array([0.45, 0.55])
+ self.jdict["target_x"].reset_current_position(self.target_pos[0] - self.zero_offset[0], 0)
+ self.jdict["target_y"].reset_current_position(self.target_pos[1] - self.zero_offset[1], 0)
+ self.jdict["object_x"].reset_current_position(self.object_pos[0] - self.zero_offset[0], 0)
+ self.jdict["object_y"].reset_current_position(self.object_pos[1] - self.zero_offset[1], 0)
+
+ # randomize all joints TODO: Will this work or do we have to constrain this resetting in some way?
+ self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
+ self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
+ self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
+ self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
+ self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
+ self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
+ self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
+
+ def calc_state(self):
+ self.to_target_vec = self.target_pos - self.object_pos
+ return np.concatenate([
+ np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
+ np.array([j.current_relative_position() for j in self.ordered_joints
+ ]).flatten(), # all speeds
+ self.to_target_vec,
+ self.fingertip.pose().xyz(),
+ self.object.pose().xyz(),
+ self.target.pose().xyz(),
+ ])
class Striker(MJCFBasedRobot):
- min_target_placement_radius = 0.1
- max_target_placement_radius = 0.8
- min_object_placement_radius = 0.1
- max_object_placement_radius = 0.8
-
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'striker.xml', 'body0', action_dim=7, obs_dim=55)
-
- def robot_specific_reset(self, bullet_client):
- # parts
- self.fingertip = self.parts["fingertip"]
- self.target = self.parts["target"]
- self.object = self.parts["object"]
-
- # joints
- self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
- self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
- self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
- self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
- self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
- self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
- self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
-
- self._min_strike_dist = np.inf
- self._striked = False
- self._strike_pos = None
-
- # reset position and speed of manipulator
- # TODO: Will this work or do we have to constrain this resetting in some way?
- self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
-
- self.zero_offset = np.array([0.45, 0.55, 0])
- self.object_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_object_placement_radius
- self.object_pos = self.object_pos \
- / np.linalg.norm(self.object_pos) \
- * self.np_random.uniform(low=self.min_object_placement_radius,
- high=self.max_object_placement_radius, size=1)
-
- # reset object position
- self.jdict["object_x"].reset_current_position(self.object_pos[0] - self.zero_offset[0], 0)
- self.jdict["object_y"].reset_current_position(self.object_pos[1] - self.zero_offset[1], 0)
-
- self.target_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_target_placement_radius
- self.target_pos = self.target_pos \
- / np.linalg.norm(self.target_pos) \
- * self.np_random.uniform(low=self.min_target_placement_radius,
- high=self.max_target_placement_radius, size=1)
-
- self.target.reset_pose(self.target_pos - self.zero_offset, np.array([0, 0, 0, 1]))
-
- def apply_action(self, a):
- assert (np.isfinite(a).all())
- self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
- self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
- self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
- self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
- self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
- self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
- self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
-
- def calc_state(self):
- self.to_target_vec = self.target_pos - self.object_pos
- return np.concatenate([
- np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
- np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # all speeds
- self.to_target_vec,
- self.fingertip.pose().xyz(),
- self.object.pose().xyz(),
- self.target.pose().xyz(),
- ])
+ min_target_placement_radius = 0.1
+ max_target_placement_radius = 0.8
+ min_object_placement_radius = 0.1
+ max_object_placement_radius = 0.8
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'striker.xml', 'body0', action_dim=7, obs_dim=55)
+
+ def robot_specific_reset(self, bullet_client):
+ # parts
+ self.fingertip = self.parts["fingertip"]
+ self.target = self.parts["target"]
+ self.object = self.parts["object"]
+
+ # joints
+ self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
+ self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
+ self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
+ self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
+ self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
+ self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
+ self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
+
+ self._min_strike_dist = np.inf
+ self._striked = False
+ self._strike_pos = None
+
+ # reset position and speed of manipulator
+ # TODO: Will this work or do we have to constrain this resetting in some way?
+ self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+
+ self.zero_offset = np.array([0.45, 0.55, 0])
+ self.object_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_object_placement_radius
+ self.object_pos = self.object_pos \
+ / np.linalg.norm(self.object_pos) \
+ * self.np_random.uniform(low=self.min_object_placement_radius,
+ high=self.max_object_placement_radius, size=1)
+
+ # reset object position
+ self.jdict["object_x"].reset_current_position(self.object_pos[0] - self.zero_offset[0], 0)
+ self.jdict["object_y"].reset_current_position(self.object_pos[1] - self.zero_offset[1], 0)
+
+ self.target_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_target_placement_radius
+ self.target_pos = self.target_pos \
+ / np.linalg.norm(self.target_pos) \
+ * self.np_random.uniform(low=self.min_target_placement_radius,
+ high=self.max_target_placement_radius, size=1)
+
+ self.target.reset_pose(self.target_pos - self.zero_offset, np.array([0, 0, 0, 1]))
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
+ self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
+ self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
+ self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
+ self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
+ self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
+ self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
+
+ def calc_state(self):
+ self.to_target_vec = self.target_pos - self.object_pos
+ return np.concatenate([
+ np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
+ np.array([j.current_relative_position() for j in self.ordered_joints
+ ]).flatten(), # all speeds
+ self.to_target_vec,
+ self.fingertip.pose().xyz(),
+ self.object.pose().xyz(),
+ self.target.pose().xyz(),
+ ])
class Thrower(MJCFBasedRobot):
- min_target_placement_radius = 0.1
- max_target_placement_radius = 0.8
- min_object_placement_radius = 0.1
- max_object_placement_radius = 0.8
-
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'thrower.xml', 'body0', action_dim=7, obs_dim=48)
-
- def robot_specific_reset(self, bullet_client):
- # parts
- self.fingertip = self.parts["fingertip"]
- self.target = self.parts["target"]
- self.object = self.parts["object"]
-
- # joints
- self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
- self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
- self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
- self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
- self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
- self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
- self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
-
- self._object_hit_ground = False
- self._object_hit_location = None
-
- # reset position and speed of manipulator
- # TODO: Will this work or do we have to constrain this resetting in some way?
- self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
- self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
-
- self.zero_offset = np.array([0.45, 0.55, 0])
- self.object_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_object_placement_radius
- self.object_pos = self.object_pos \
- / np.linalg.norm(self.object_pos) \
- * self.np_random.uniform(low=self.min_object_placement_radius,
- high=self.max_object_placement_radius, size=1)
-
- # reset object position
- self.parts["object"].reset_pose(self.object_pos - self.zero_offset, np.array([0, 0, 0, 1]))
-
- self.target_pos = np.concatenate([
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1),
- self.np_random.uniform(low=-1, high=1, size=1)
- ])
-
- # make length of vector between min and max_target_placement_radius
- self.target_pos = self.target_pos \
- / np.linalg.norm(self.target_pos) \
- * self.np_random.uniform(low=self.min_target_placement_radius,
- high=self.max_target_placement_radius, size=1)
-
- self.parts["target"].reset_pose(self.target_pos - self.zero_offset, np.array([0, 0, 0, 1]))
-
- def apply_action(self, a):
- assert (np.isfinite(a).all())
- self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
- self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
- self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
- self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
- self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
- self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
- self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
-
- def calc_state(self):
- self.to_target_vec = self.target_pos - self.object_pos
- return np.concatenate([
- np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
- np.array([j.current_relative_position() for j in self.ordered_joints]).flatten(), # all speeds
- self.to_target_vec,
- self.fingertip.pose().xyz(),
- self.object.pose().xyz(),
- self.target.pose().xyz(),
- ])
+ min_target_placement_radius = 0.1
+ max_target_placement_radius = 0.8
+ min_object_placement_radius = 0.1
+ max_object_placement_radius = 0.8
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'thrower.xml', 'body0', action_dim=7, obs_dim=48)
+
+ def robot_specific_reset(self, bullet_client):
+ # parts
+ self.fingertip = self.parts["fingertip"]
+ self.target = self.parts["target"]
+ self.object = self.parts["object"]
+
+ # joints
+ self.shoulder_pan_joint = self.jdict["shoulder_pan_joint"]
+ self.shoulder_lift_joint = self.jdict["shoulder_lift_joint"]
+ self.upper_arm_roll_joint = self.jdict["upper_arm_roll_joint"]
+ self.elbow_flex_joint = self.jdict["elbow_flex_joint"]
+ self.forearm_roll_joint = self.jdict["forearm_roll_joint"]
+ self.wrist_flex_joint = self.jdict["wrist_flex_joint"]
+ self.wrist_roll_joint = self.jdict["wrist_roll_joint"]
+
+ self._object_hit_ground = False
+ self._object_hit_location = None
+
+ # reset position and speed of manipulator
+ # TODO: Will this work or do we have to constrain this resetting in some way?
+ self.shoulder_pan_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.shoulder_lift_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.upper_arm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14),
+ 0)
+ self.elbow_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.forearm_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_flex_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+ self.wrist_roll_joint.reset_current_position(self.np_random.uniform(low=-3.14, high=3.14), 0)
+
+ self.zero_offset = np.array([0.45, 0.55, 0])
+ self.object_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_object_placement_radius
+ self.object_pos = self.object_pos \
+ / np.linalg.norm(self.object_pos) \
+ * self.np_random.uniform(low=self.min_object_placement_radius,
+ high=self.max_object_placement_radius, size=1)
+
+ # reset object position
+ self.parts["object"].reset_pose(self.object_pos - self.zero_offset, np.array([0, 0, 0, 1]))
+
+ self.target_pos = np.concatenate([
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1),
+ self.np_random.uniform(low=-1, high=1, size=1)
+ ])
+
+ # make length of vector between min and max_target_placement_radius
+ self.target_pos = self.target_pos \
+ / np.linalg.norm(self.target_pos) \
+ * self.np_random.uniform(low=self.min_target_placement_radius,
+ high=self.max_target_placement_radius, size=1)
+
+ self.parts["target"].reset_pose(self.target_pos - self.zero_offset, np.array([0, 0, 0, 1]))
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ self.shoulder_pan_joint.set_motor_torque(0.05 * float(np.clip(a[0], -1, +1)))
+ self.shoulder_lift_joint.set_motor_torque(0.05 * float(np.clip(a[1], -1, +1)))
+ self.upper_arm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[2], -1, +1)))
+ self.elbow_flex_joint.set_motor_torque(0.05 * float(np.clip(a[3], -1, +1)))
+ self.forearm_roll_joint.set_motor_torque(0.05 * float(np.clip(a[4], -1, +1)))
+ self.wrist_flex_joint.set_motor_torque(0.05 * float(np.clip(a[5], -1, +1)))
+ self.wrist_roll_joint.set_motor_torque(0.05 * float(np.clip(a[6], -1, +1)))
+
+ def calc_state(self):
+ self.to_target_vec = self.target_pos - self.object_pos
+ return np.concatenate([
+ np.array([j.current_position() for j in self.ordered_joints]).flatten(), # all positions
+ np.array([j.current_relative_position() for j in self.ordered_joints
+ ]).flatten(), # all speeds
+ self.to_target_vec,
+ self.fingertip.pose().xyz(),
+ self.object.pose().xyz(),
+ self.target.pose().xyz(),
+ ])
diff --git a/examples/pybullet/gym/pybullet_envs/robot_pendula.py b/examples/pybullet/gym/pybullet_envs/robot_pendula.py
index a90728128..924d84292 100644
--- a/examples/pybullet/gym/pybullet_envs/robot_pendula.py
+++ b/examples/pybullet/gym/pybullet_envs/robot_pendula.py
@@ -1,86 +1,92 @@
from robot_bases import MJCFBasedRobot
import numpy as np
+
class InvertedPendulum(MJCFBasedRobot):
- swingup = False
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'inverted_pendulum.xml', 'cart', action_dim=1, obs_dim=5)
-
- def robot_specific_reset(self, bullet_client):
- self._p = bullet_client
- self.pole = self.parts["pole"]
- self.slider = self.jdict["slider"]
- self.j1 = self.jdict["hinge"]
- u = self.np_random.uniform(low=-.1, high=.1)
- self.j1.reset_current_position( u if not self.swingup else 3.1415+u , 0)
- self.j1.set_motor_torque(0)
-
- def apply_action(self, a):
- assert( np.isfinite(a).all() )
- if not np.isfinite(a).all():
- print("a is inf")
- a[0] = 0
- self.slider.set_motor_torque( 100*float(np.clip(a[0], -1, +1)) )
-
- def calc_state(self):
- self.theta, theta_dot = self.j1.current_position()
- x, vx = self.slider.current_position()
- assert( np.isfinite(x) )
-
- if not np.isfinite(x):
- print("x is inf")
- x = 0
-
- if not np.isfinite(vx):
- print("vx is inf")
- vx = 0
-
- if not np.isfinite(self.theta):
- print("theta is inf")
- self.theta = 0
-
- if not np.isfinite(theta_dot):
- print("theta_dot is inf")
- theta_dot = 0
-
- return np.array([
- x, vx,
- np.cos(self.theta), np.sin(self.theta), theta_dot
- ])
+ swingup = False
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'inverted_pendulum.xml', 'cart', action_dim=1, obs_dim=5)
+
+ def robot_specific_reset(self, bullet_client):
+ self._p = bullet_client
+ self.pole = self.parts["pole"]
+ self.slider = self.jdict["slider"]
+ self.j1 = self.jdict["hinge"]
+ u = self.np_random.uniform(low=-.1, high=.1)
+ self.j1.reset_current_position(u if not self.swingup else 3.1415 + u, 0)
+ self.j1.set_motor_torque(0)
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ if not np.isfinite(a).all():
+ print("a is inf")
+ a[0] = 0
+ self.slider.set_motor_torque(100 * float(np.clip(a[0], -1, +1)))
+
+ def calc_state(self):
+ self.theta, theta_dot = self.j1.current_position()
+ x, vx = self.slider.current_position()
+ assert (np.isfinite(x))
+
+ if not np.isfinite(x):
+ print("x is inf")
+ x = 0
+
+ if not np.isfinite(vx):
+ print("vx is inf")
+ vx = 0
+
+ if not np.isfinite(self.theta):
+ print("theta is inf")
+ self.theta = 0
+
+ if not np.isfinite(theta_dot):
+ print("theta_dot is inf")
+ theta_dot = 0
+
+ return np.array([x, vx, np.cos(self.theta), np.sin(self.theta), theta_dot])
+
class InvertedPendulumSwingup(InvertedPendulum):
- swingup = True
+ swingup = True
class InvertedDoublePendulum(MJCFBasedRobot):
- def __init__(self):
- MJCFBasedRobot.__init__(self, 'inverted_double_pendulum.xml', 'cart', action_dim=1, obs_dim=9)
-
- def robot_specific_reset(self, bullet_client):
- self._p = bullet_client
- self.pole2 = self.parts["pole2"]
- self.slider = self.jdict["slider"]
- self.j1 = self.jdict["hinge"]
- self.j2 = self.jdict["hinge2"]
- u = self.np_random.uniform(low=-.1, high=.1, size=[2])
- self.j1.reset_current_position(float(u[0]), 0)
- self.j2.reset_current_position(float(u[1]), 0)
- self.j1.set_motor_torque(0)
- self.j2.set_motor_torque(0)
-
- def apply_action(self, a):
- assert( np.isfinite(a).all() )
- self.slider.set_motor_torque( 200*float(np.clip(a[0], -1, +1)) )
-
- def calc_state(self):
- theta, theta_dot = self.j1.current_position()
- gamma, gamma_dot = self.j2.current_position()
- x, vx = self.slider.current_position()
- self.pos_x, _, self.pos_y = self.pole2.pose().xyz()
- assert( np.isfinite(x) )
- return np.array([
- x, vx,
- self.pos_x,
- np.cos(theta), np.sin(theta), theta_dot,
- np.cos(gamma), np.sin(gamma), gamma_dot,
- ])
+
+ def __init__(self):
+ MJCFBasedRobot.__init__(self, 'inverted_double_pendulum.xml', 'cart', action_dim=1, obs_dim=9)
+
+ def robot_specific_reset(self, bullet_client):
+ self._p = bullet_client
+ self.pole2 = self.parts["pole2"]
+ self.slider = self.jdict["slider"]
+ self.j1 = self.jdict["hinge"]
+ self.j2 = self.jdict["hinge2"]
+ u = self.np_random.uniform(low=-.1, high=.1, size=[2])
+ self.j1.reset_current_position(float(u[0]), 0)
+ self.j2.reset_current_position(float(u[1]), 0)
+ self.j1.set_motor_torque(0)
+ self.j2.set_motor_torque(0)
+
+ def apply_action(self, a):
+ assert (np.isfinite(a).all())
+ self.slider.set_motor_torque(200 * float(np.clip(a[0], -1, +1)))
+
+ def calc_state(self):
+ theta, theta_dot = self.j1.current_position()
+ gamma, gamma_dot = self.j2.current_position()
+ x, vx = self.slider.current_position()
+ self.pos_x, _, self.pos_y = self.pole2.pose().xyz()
+ assert (np.isfinite(x))
+ return np.array([
+ x,
+ vx,
+ self.pos_x,
+ np.cos(theta),
+ np.sin(theta),
+ theta_dot,
+ np.cos(gamma),
+ np.sin(gamma),
+ gamma_dot,
+ ])
diff --git a/examples/pybullet/gym/pybullet_envs/scene_abstract.py b/examples/pybullet/gym/pybullet_envs/scene_abstract.py
index b50dd524b..f4bbfae0c 100644
--- a/examples/pybullet/gym/pybullet_envs/scene_abstract.py
+++ b/examples/pybullet/gym/pybullet_envs/scene_abstract.py
@@ -1,78 +1,79 @@
import sys, os
sys.path.append(os.path.dirname(__file__))
-import pybullet
+import pybullet
import gym
class Scene:
- "A base class for single- and multiplayer scenes"
+ "A base class for single- and multiplayer scenes"
- def __init__(self, bullet_client, gravity, timestep, frame_skip):
- self._p = bullet_client
- self.np_random, seed = gym.utils.seeding.np_random(None)
- self.timestep = timestep
- self.frame_skip = frame_skip
+ def __init__(self, bullet_client, gravity, timestep, frame_skip):
+ self._p = bullet_client
+ self.np_random, seed = gym.utils.seeding.np_random(None)
+ self.timestep = timestep
+ self.frame_skip = frame_skip
- self.dt = self.timestep * self.frame_skip
- self.cpp_world = World(self._p, gravity, timestep, frame_skip)
+ self.dt = self.timestep * self.frame_skip
+ self.cpp_world = World(self._p, gravity, timestep, frame_skip)
- self.test_window_still_open = True # or never opened
- self.human_render_detected = False # if user wants render("human"), we open test window
+ self.test_window_still_open = True # or never opened
+ self.human_render_detected = False # if user wants render("human"), we open test window
- self.multiplayer_robots = {}
+ self.multiplayer_robots = {}
- def test_window(self):
- "Call this function every frame, to see what's going on. Not necessary in learning."
- self.human_render_detected = True
- return self.test_window_still_open
+ def test_window(self):
+ "Call this function every frame, to see what's going on. Not necessary in learning."
+ self.human_render_detected = True
+ return self.test_window_still_open
- def actor_introduce(self, robot):
- "Usually after scene reset"
- if not self.multiplayer: return
- self.multiplayer_robots[robot.player_n] = robot
+ def actor_introduce(self, robot):
+ "Usually after scene reset"
+ if not self.multiplayer: return
+ self.multiplayer_robots[robot.player_n] = robot
- def actor_is_active(self, robot):
- """
+ def actor_is_active(self, robot):
+ """
Used by robots to see if they are free to exclusiveley put their HUD on the test window.
Later can be used for click-focus robots.
"""
- return not self.multiplayer
+ return not self.multiplayer
- def episode_restart(self, bullet_client):
- "This function gets overridden by specific scene, to reset specific objects into their start positions"
- self.cpp_world.clean_everything()
- #self.cpp_world.test_window_history_reset()
+ def episode_restart(self, bullet_client):
+ "This function gets overridden by specific scene, to reset specific objects into their start positions"
+ self.cpp_world.clean_everything()
+ #self.cpp_world.test_window_history_reset()
- def global_step(self):
- """
+ def global_step(self):
+ """
The idea is: apply motor torques for all robots, then call global_step(), then collect
observations from robots using step() with the same action.
"""
- self.cpp_world.step(self.frame_skip)
+ self.cpp_world.step(self.frame_skip)
-class SingleRobotEmptyScene(Scene):
- multiplayer = False # this class is used "as is" for InvertedPendulum, Reacher
-class World:
+class SingleRobotEmptyScene(Scene):
+ multiplayer = False # this class is used "as is" for InvertedPendulum, Reacher
- def __init__(self, bullet_client, gravity, timestep, frame_skip):
- self._p = bullet_client
- self.gravity = gravity
- self.timestep = timestep
- self.frame_skip = frame_skip
- self.numSolverIterations = 5
- self.clean_everything()
-
-
- def clean_everything(self):
- #p.resetSimulation()
- self._p.setGravity(0, 0, -self.gravity)
- self._p.setDefaultContactERP(0.9)
- #print("self.numSolverIterations=",self.numSolverIterations)
- self._p.setPhysicsEngineParameter(fixedTimeStep=self.timestep*self.frame_skip, numSolverIterations=self.numSolverIterations, numSubSteps=self.frame_skip)
-
- def step(self, frame_skip):
- self._p.stepSimulation()
+class World:
+ def __init__(self, bullet_client, gravity, timestep, frame_skip):
+ self._p = bullet_client
+ self.gravity = gravity
+ self.timestep = timestep
+ self.frame_skip = frame_skip
+ self.numSolverIterations = 5
+ self.clean_everything()
+
+ def clean_everything(self):
+ #p.resetSimulation()
+ self._p.setGravity(0, 0, -self.gravity)
+ self._p.setDefaultContactERP(0.9)
+ #print("self.numSolverIterations=",self.numSolverIterations)
+ self._p.setPhysicsEngineParameter(fixedTimeStep=self.timestep * self.frame_skip,
+ numSolverIterations=self.numSolverIterations,
+ numSubSteps=self.frame_skip)
+
+ def step(self, frame_skip):
+ self._p.stepSimulation()
diff --git a/examples/pybullet/gym/pybullet_envs/scene_stadium.py b/examples/pybullet/gym/pybullet_envs/scene_stadium.py
index c105983db..0ab34f202 100644
--- a/examples/pybullet/gym/pybullet_envs/scene_stadium.py
+++ b/examples/pybullet/gym/pybullet_envs/scene_stadium.py
@@ -1,52 +1,54 @@
-import os, inspect
+import os, inspect
currentdir = os.path.dirname(os.path.abspath(inspect.getfile(inspect.currentframe())))
parentdir = os.path.dirname(currentdir)
-os.sys.path.insert(0,parentdir)
+os.sys.path.insert(0, parentdir)
import pybullet_data
-
from pybullet_envs.scene_abstract import Scene
-import pybullet
+import pybullet
class StadiumScene(Scene):
- zero_at_running_strip_start_line = True # if False, center of coordinates (0,0,0) will be at the middle of the stadium
- stadium_halflen = 105*0.25 # FOOBALL_FIELD_HALFLEN
- stadium_halfwidth = 50*0.25 # FOOBALL_FIELD_HALFWID
- stadiumLoaded=0
-
- def episode_restart(self, bullet_client):
- self._p = bullet_client
- Scene.episode_restart(self, bullet_client) # contains cpp_world.clean_everything()
- if (self.stadiumLoaded==0):
- self.stadiumLoaded=1
-
- # stadium_pose = cpp_household.Pose()
- # if self.zero_at_running_strip_start_line:
- # stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
-
- filename = os.path.join(pybullet_data.getDataPath(),"plane_stadium.sdf")
- self.ground_plane_mjcf=self._p.loadSDF(filename)
- #filename = os.path.join(pybullet_data.getDataPath(),"stadium_no_collision.sdf")
- #self.ground_plane_mjcf = self._p.loadSDF(filename)
- #
- for i in self.ground_plane_mjcf:
- self._p.changeDynamics(i,-1,lateralFriction=0.8, restitution=0.5)
- self._p.changeVisualShape(i,-1,rgbaColor=[1,1,1,0.8])
- self._p.configureDebugVisualizer(pybullet.COV_ENABLE_PLANAR_REFLECTION,1)
-
- # for j in range(p.getNumJoints(i)):
- # self._p.changeDynamics(i,j,lateralFriction=0)
- #despite the name (stadium_no_collision), it DID have collision, so don't add duplicate ground
-
+ zero_at_running_strip_start_line = True # if False, center of coordinates (0,0,0) will be at the middle of the stadium
+ stadium_halflen = 105 * 0.25 # FOOBALL_FIELD_HALFLEN
+ stadium_halfwidth = 50 * 0.25 # FOOBALL_FIELD_HALFWID
+ stadiumLoaded = 0
+
+ def episode_restart(self, bullet_client):
+ self._p = bullet_client
+ Scene.episode_restart(self, bullet_client) # contains cpp_world.clean_everything()
+ if (self.stadiumLoaded == 0):
+ self.stadiumLoaded = 1
+
+ # stadium_pose = cpp_household.Pose()
+ # if self.zero_at_running_strip_start_line:
+ # stadium_pose.set_xyz(27, 21, 0) # see RUN_STARTLINE, RUN_RAD constants
+
+ filename = os.path.join(pybullet_data.getDataPath(), "plane_stadium.sdf")
+ self.ground_plane_mjcf = self._p.loadSDF(filename)
+ #filename = os.path.join(pybullet_data.getDataPath(),"stadium_no_collision.sdf")
+ #self.ground_plane_mjcf = self._p.loadSDF(filename)
+ #
+ for i in self.ground_plane_mjcf:
+ self._p.changeDynamics(i, -1, lateralFriction=0.8, restitution=0.5)
+ self._p.changeVisualShape(i, -1, rgbaColor=[1, 1, 1, 0.8])
+ self._p.configureDebugVisualizer(pybullet.COV_ENABLE_PLANAR_REFLECTION, 1)
+
+ # for j in range(p.getNumJoints(i)):
+ # self._p.changeDynamics(i,j,lateralFriction=0)
+ #despite the name (stadium_no_collision), it DID have collision, so don't add duplicate ground
+
+
class SinglePlayerStadiumScene(StadiumScene):
- "This scene created by environment, to work in a way as if there was no concept of scene visible to user."
- multiplayer = False
+ "This scene created by environment, to work in a way as if there was no concept of scene visible to user."
+ multiplayer = False
+
class MultiplayerStadiumScene(StadiumScene):
- multiplayer = True
- players_count = 3
- def actor_introduce(self, robot):
- StadiumScene.actor_introduce(self, robot)
- i = robot.player_n - 1 # 0 1 2 => -1 0 +1
- robot.move_robot(0, i, 0)
+ multiplayer = True
+ players_count = 3
+
+ def actor_introduce(self, robot):
+ StadiumScene.actor_introduce(self, robot)
+ i = robot.player_n - 1 # 0 1 2 => -1 0 +1
+ robot.move_robot(0, i, 0)