diff --git a/CMakeLists.txt b/CMakeLists.txt
index f31ff95..4d04f1c 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -16,20 +16,23 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
endif()
find_package(Eigen3 REQUIRED)
+find_package(Lua 5.4 REQUIRED)
+find_package(PCL REQUIRED)
find_package(yaml-cpp REQUIRED)
+find_package(pcl_conversions REQUIRED)
+
find_package(rclcpp REQUIRED)
find_package(rclcpp_action REQUIRED)
-find_package(nav2_msgs REQUIRED)
-find_package(PCL REQUIRED)
+find_package(rmcs_executor REQUIRED)
+
+find_package(nav2_msgs REQUIRED)
+find_package(sensor_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
-find_package(std_srvs REQUIRED)
find_package(rmcs_msgs REQUIRED)
+find_package(std_srvs REQUIRED)
find_package(ament_index_cpp REQUIRED)
find_package(tf2_ros REQUIRED)
-find_package(Lua 5.4 REQUIRED)
-
-find_package(rmcs_executor REQUIRED)
include(FetchContent)
FetchContent_Declare(
@@ -49,14 +52,17 @@ target_compile_features(
target_sources(
${PROJECT_NAME}
PRIVATE
+ # src/cxx/util/localization/engine.cc
+ src/cxx/util/navigation/navigation.cc
src/cxx/context.cc
- src/cxx/navigation.cc
src/cxx/component.cc
)
+set(RMCS_CORE_SOURCE_DIR "${PROJECT_SOURCE_DIR}/../../rmcs_core/src")
target_include_directories(
${PROJECT_NAME}
- PRIVATE
+ SYSTEM PRIVATE
${PROJECT_SOURCE_DIR}/src/
+ ${RMCS_CORE_SOURCE_DIR}
${rmcs_executor_INCLUDE_DIRS}
${geometry_msgs_INCLUDE_DIRS}
${rmcs_msgs_INCLUDE_DIRS}
@@ -65,7 +71,10 @@ target_include_directories(
${tf2_ros_INCLUDE_DIRS}
${rclcpp_action_INCLUDE_DIRS}
${nav2_msgs_INCLUDE_DIRS}
+ ${sensor_msgs_INCLUDE_DIRS}
+ ${pcl_conversions_INCLUDE_DIRS}
${LUA_INCLUDE_DIR}
+ ${PCL_INCLUDE_DIRS}
)
target_link_libraries(
${PROJECT_NAME}
@@ -84,6 +93,33 @@ target_link_libraries(
${tf2_ros_LIBRARIES}
${rclcpp_action_LIBRARIES}
${nav2_msgs_LIBRARIES}
+ ${sensor_msgs_LIBRARIES}
+ ${pcl_conversions_LIBRARIES}
+)
+
+add_executable(${PROJECT_NAME}-sim-sidecar src/cxx/sim_sidecar.cc)
+target_compile_features(
+ ${PROJECT_NAME}-sim-sidecar
+ PRIVATE
+ cxx_std_23
+)
+target_compile_definitions(
+ ${PROJECT_NAME}-sim-sidecar
+ PRIVATE
+ RMCS_NAVIGATION_SOURCE_DIR="${PROJECT_SOURCE_DIR}"
+)
+target_include_directories(
+ ${PROJECT_NAME}-sim-sidecar
+ PRIVATE
+ ${PROJECT_SOURCE_DIR}/src/
+ ${LUA_INCLUDE_DIR}
+)
+target_link_libraries(
+ ${PROJECT_NAME}-sim-sidecar
+ PRIVATE
+ ${LUA_LIBRARIES}
+ sol2::sol2
+ yaml-cpp::yaml-cpp
)
find_package(pluginlib REQUIRED)
diff --git a/cmake/export.cmake b/cmake/export.cmake
index 742ff6d..a80fd93 100644
--- a/cmake/export.cmake
+++ b/cmake/export.cmake
@@ -1,5 +1,5 @@
install(
- TARGETS ${PROJECT_NAME}
+ TARGETS ${PROJECT_NAME} ${PROJECT_NAME}-sim-sidecar
DESTINATION lib/${PROJECT_NAME}/
)
install(
diff --git a/config/motion.yaml b/config/motion.yaml
index 5d13575..5dce07e 100644
--- a/config/motion.yaml
+++ b/config/motion.yaml
@@ -106,32 +106,32 @@ controller_server:
"PathAlignCritic",
"PathFollowCritic",
]
-
- ConstraintCritic.enabled: true
- ConstraintCritic.cost_weight: 5.0
-
- CostCritic.enabled: true
- CostCritic.cost_weight: 16.0
- CostCritic.critical_cost: 120.0
- CostCritic.collision_cost: 8000000.0
- CostCritic.near_collision_cost: 253
- CostCritic.cost_power: 2
- CostCritic.consider_footprint: true
- CostCritic.near_goal_distance: 0.8
- CostCritic.trajectory_point_step: 1
-
- GoalCritic.enabled: true
- GoalCritic.cost_weight: 4.5
- GoalCritic.threshold_to_consider: 1.2
-
- PathAlignCritic.enabled: true
- PathAlignCritic.cost_weight: 0.8
- PathAlignCritic.threshold_to_consider: 1.0
- PathAlignCritic.trajectory_point_step: 3
-
- PathFollowCritic.enabled: true
- PathFollowCritic.cost_weight: 3.2
- PathFollowCritic.threshold_to_consider: 1.5
+ ConstraintCritic:
+ enabled: true
+ cost_weight: 5.0
+ CostCritic:
+ enabled: true
+ cost_weight: 10.0
+ critical_cost: 120.0
+ collision_cost: 8000000.0
+ near_collision_cost: 230
+ cost_power: 2
+ consider_footprint: true
+ near_goal_distance: 1.0
+ trajectory_point_step: 1
+ GoalCritic:
+ enabled: true
+ cost_weight: 10.0
+ threshold_to_consider: 1.0
+ PathAlignCritic:
+ enabled: true
+ cost_weight: 0.8
+ threshold_to_consider: 1.0
+ trajectory_point_step: 3
+ PathFollowCritic:
+ enabled: true
+ cost_weight: 3.2
+ threshold_to_consider: 1.5
local_costmap:
local_costmap:
@@ -162,5 +162,5 @@ local_costmap:
inflation_layer:
plugin: "nav2_costmap_2d::InflationLayer"
- inflation_radius: 0.25
+ inflation_radius: 0.4
cost_scaling_factor: 0.5
diff --git a/godot-mock/.editorconfig b/godot-mock/.editorconfig
new file mode 100644
index 0000000..f28239b
--- /dev/null
+++ b/godot-mock/.editorconfig
@@ -0,0 +1,4 @@
+root = true
+
+[*]
+charset = utf-8
diff --git a/godot-mock/.gitattributes b/godot-mock/.gitattributes
new file mode 100644
index 0000000..8ad74f7
--- /dev/null
+++ b/godot-mock/.gitattributes
@@ -0,0 +1,2 @@
+# Normalize EOL for all files that Git considers text files.
+* text=auto eol=lf
diff --git a/godot-mock/.gitignore b/godot-mock/.gitignore
new file mode 100644
index 0000000..0af181c
--- /dev/null
+++ b/godot-mock/.gitignore
@@ -0,0 +1,3 @@
+# Godot 4+ specific ignores
+.godot/
+/android/
diff --git a/godot-mock/material/20260422-192911.png b/godot-mock/material/20260422-192911.png
new file mode 100644
index 0000000..d9cdb99
Binary files /dev/null and b/godot-mock/material/20260422-192911.png differ
diff --git a/godot-mock/material/20260422-192911.png.import b/godot-mock/material/20260422-192911.png.import
new file mode 100644
index 0000000..f150224
--- /dev/null
+++ b/godot-mock/material/20260422-192911.png.import
@@ -0,0 +1,41 @@
+[remap]
+
+importer="texture"
+type="CompressedTexture2D"
+uid="uid://dqtsgnct0ijl0"
+path.s3tc="res://.godot/imported/20260422-192911.png-f31ee39485589f6eb4a8fd243ef62172.s3tc.ctex"
+metadata={
+"imported_formats": ["s3tc_bptc"],
+"vram_texture": true
+}
+
+[deps]
+
+source_file="res://material/20260422-192911.png"
+dest_files=["res://.godot/imported/20260422-192911.png-f31ee39485589f6eb4a8fd243ef62172.s3tc.ctex"]
+
+[params]
+
+compress/mode=2
+compress/high_quality=false
+compress/lossy_quality=0.7
+compress/uastc_level=0
+compress/rdo_quality_loss=0.0
+compress/hdr_compression=1
+compress/normal_map=0
+compress/channel_pack=0
+mipmaps/generate=true
+mipmaps/limit=-1
+roughness/mode=0
+roughness/src_normal=""
+process/channel_remap/red=0
+process/channel_remap/green=1
+process/channel_remap/blue=2
+process/channel_remap/alpha=3
+process/fix_alpha_border=true
+process/premult_alpha=false
+process/normal_map_invert_y=false
+process/hdr_as_srgb=false
+process/hdr_clamp_exposure=false
+process/size_limit=0
+detect_3d/compress_to=0
diff --git a/godot-mock/material/Cn_Mat_U_LMSuit_21_body_BIANSE.tres b/godot-mock/material/Cn_Mat_U_LMSuit_21_body_BIANSE.tres
new file mode 100644
index 0000000..e5338aa
--- /dev/null
+++ b/godot-mock/material/Cn_Mat_U_LMSuit_21_body_BIANSE.tres
@@ -0,0 +1,7 @@
+[gd_resource type="StandardMaterial3D" format=3 uid="uid://bnfxtpyuftji1"]
+
+[resource]
+resource_name = "Cn_Mat_U_LMSuit_21_body_BIANSE"
+cull_mode = 2
+albedo_color = Color(0.9063318, 0.9063318, 0.9063318, 1)
+roughness = 0.9090847
diff --git a/godot-mock/material/white_wood.png b/godot-mock/material/white_wood.png
new file mode 100644
index 0000000..a570227
Binary files /dev/null and b/godot-mock/material/white_wood.png differ
diff --git a/godot-mock/material/white_wood.png.import b/godot-mock/material/white_wood.png.import
new file mode 100644
index 0000000..b810d77
--- /dev/null
+++ b/godot-mock/material/white_wood.png.import
@@ -0,0 +1,41 @@
+[remap]
+
+importer="texture"
+type="CompressedTexture2D"
+uid="uid://dodhbatwmlp07"
+path.s3tc="res://.godot/imported/white_wood.png-a533a54625f96f5b178df59798e15a83.s3tc.ctex"
+metadata={
+"imported_formats": ["s3tc_bptc"],
+"vram_texture": true
+}
+
+[deps]
+
+source_file="res://material/white_wood.png"
+dest_files=["res://.godot/imported/white_wood.png-a533a54625f96f5b178df59798e15a83.s3tc.ctex"]
+
+[params]
+
+compress/mode=2
+compress/high_quality=false
+compress/lossy_quality=0.7
+compress/uastc_level=0
+compress/rdo_quality_loss=0.0
+compress/hdr_compression=1
+compress/normal_map=0
+compress/channel_pack=0
+mipmaps/generate=true
+mipmaps/limit=-1
+roughness/mode=0
+roughness/src_normal=""
+process/channel_remap/red=0
+process/channel_remap/green=1
+process/channel_remap/blue=2
+process/channel_remap/alpha=3
+process/fix_alpha_border=true
+process/premult_alpha=false
+process/normal_map_invert_y=false
+process/hdr_as_srgb=false
+process/hdr_clamp_exposure=false
+process/size_limit=0
+detect_3d/compress_to=0
diff --git a/godot-mock/models/Cn_Mat_U_LMSuit_21_body_BIANSE.tres b/godot-mock/models/Cn_Mat_U_LMSuit_21_body_BIANSE.tres
new file mode 100644
index 0000000..d4c7f48
--- /dev/null
+++ b/godot-mock/models/Cn_Mat_U_LMSuit_21_body_BIANSE.tres
@@ -0,0 +1,7 @@
+[gd_resource type="StandardMaterial3D" format=3 uid="uid://8d75nvfc3dnj"]
+
+[resource]
+resource_name = "Cn_Mat_U_LMSuit_21_body_BIANSE"
+cull_mode = 2
+albedo_color = Color(0.9063318, 0.9063318, 0.9063318, 1)
+roughness = 0.9090847
diff --git a/godot-mock/models/cube.glb b/godot-mock/models/cube.glb
new file mode 100644
index 0000000..771c83e
Binary files /dev/null and b/godot-mock/models/cube.glb differ
diff --git a/godot-mock/models/cube.glb.import b/godot-mock/models/cube.glb.import
new file mode 100644
index 0000000..b9acc3e
--- /dev/null
+++ b/godot-mock/models/cube.glb.import
@@ -0,0 +1,50 @@
+[remap]
+
+importer="scene"
+importer_version=1
+type="PackedScene"
+uid="uid://iisq5ccb4jt1"
+path="res://.godot/imported/cube.glb-c6bf6ebacd621473d1ca4ff4a368b9dc.scn"
+
+[deps]
+
+source_file="res://models/cube.glb"
+dest_files=["res://.godot/imported/cube.glb-c6bf6ebacd621473d1ca4ff4a368b9dc.scn"]
+
+[params]
+
+nodes/root_type="Node3D"
+nodes/root_name="Cube"
+nodes/root_script=null
+nodes/apply_root_scale=true
+nodes/root_scale=1.0
+nodes/import_as_skeleton_bones=false
+nodes/use_name_suffixes=true
+nodes/use_node_type_suffixes=true
+meshes/ensure_tangents=true
+meshes/generate_lods=true
+meshes/create_shadow_meshes=true
+meshes/light_baking=0
+meshes/lightmap_texel_size=0.1
+meshes/force_disable_compression=false
+skins/use_named_skins=true
+animation/import=false
+animation/fps=15
+animation/trimming=false
+animation/remove_immutable_tracks=true
+animation/import_rest_as_RESET=false
+import_script/path=""
+materials/extract=0
+materials/extract_format=0
+materials/extract_path=""
+_subresources={
+"materials": {
+"cube_material": {
+"use_external/enabled": true,
+"use_external/fallback_path": "res://models/cube_material.tres",
+"use_external/path": "uid://cbwgleagikdfb"
+}
+}
+}
+gltf/naming_version=2
+gltf/embedded_image_handling=1
diff --git a/godot-mock/models/cube.mesh b/godot-mock/models/cube.mesh
new file mode 100644
index 0000000..8e77371
Binary files /dev/null and b/godot-mock/models/cube.mesh differ
diff --git a/godot-mock/models/cube_material.tres b/godot-mock/models/cube_material.tres
new file mode 100644
index 0000000..0cd8f9d
--- /dev/null
+++ b/godot-mock/models/cube_material.tres
@@ -0,0 +1,9 @@
+[gd_resource type="StandardMaterial3D" format=3 uid="uid://cbwgleagikdfb"]
+
+[ext_resource type="Texture2D" uid="uid://dodhbatwmlp07" path="res://material/white_wood.png" id="1"]
+
+[resource]
+resource_name = "Material"
+albedo_color = Color(0, 0, 0, 1)
+albedo_texture = ExtResource("1")
+roughness = 0.75
diff --git a/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb b/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb
new file mode 100644
index 0000000..0585b83
Binary files /dev/null and b/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb differ
diff --git a/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb.import b/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb.import
new file mode 100644
index 0000000..370ad1d
--- /dev/null
+++ b/godot-mock/models/d7a3f20de4e4486182806c40699d26d4.glb.import
@@ -0,0 +1,42 @@
+[remap]
+
+importer="scene"
+importer_version=1
+type="PackedScene"
+uid="uid://bnx0kbsvbubto"
+path="res://.godot/imported/d7a3f20de4e4486182806c40699d26d4.glb-dbd1b1a6503096bd82aa2dd7e4f4cc15.scn"
+
+[deps]
+
+source_file="res://models/d7a3f20de4e4486182806c40699d26d4.glb"
+dest_files=["res://.godot/imported/d7a3f20de4e4486182806c40699d26d4.glb-dbd1b1a6503096bd82aa2dd7e4f4cc15.scn"]
+
+[params]
+
+nodes/root_type=""
+nodes/root_name=""
+nodes/root_script=null
+nodes/apply_root_scale=true
+nodes/root_scale=1.0
+nodes/import_as_skeleton_bones=false
+nodes/use_name_suffixes=true
+nodes/use_node_type_suffixes=true
+meshes/ensure_tangents=true
+meshes/generate_lods=true
+meshes/create_shadow_meshes=true
+meshes/light_baking=0
+meshes/lightmap_texel_size=0.2
+meshes/force_disable_compression=false
+skins/use_named_skins=true
+animation/import=true
+animation/fps=30
+animation/trimming=false
+animation/remove_immutable_tracks=true
+animation/import_rest_as_RESET=false
+import_script/path=""
+materials/extract=1
+materials/extract_format=0
+materials/extract_path=""
+_subresources={}
+gltf/naming_version=2
+gltf/embedded_image_handling=1
diff --git a/godot-mock/models/icon.svg b/godot-mock/models/icon.svg
new file mode 100644
index 0000000..c6bbb7d
--- /dev/null
+++ b/godot-mock/models/icon.svg
@@ -0,0 +1 @@
+
diff --git a/godot-mock/models/icon.svg.import b/godot-mock/models/icon.svg.import
new file mode 100644
index 0000000..96dde96
--- /dev/null
+++ b/godot-mock/models/icon.svg.import
@@ -0,0 +1,43 @@
+[remap]
+
+importer="texture"
+type="CompressedTexture2D"
+uid="uid://oya8wpn6jmc8"
+path="res://.godot/imported/icon.svg-82b480e8788590b4c788a28db538930c.ctex"
+metadata={
+"vram_texture": false
+}
+
+[deps]
+
+source_file="res://models/icon.svg"
+dest_files=["res://.godot/imported/icon.svg-82b480e8788590b4c788a28db538930c.ctex"]
+
+[params]
+
+compress/mode=0
+compress/high_quality=false
+compress/lossy_quality=0.7
+compress/uastc_level=0
+compress/rdo_quality_loss=0.0
+compress/hdr_compression=1
+compress/normal_map=0
+compress/channel_pack=0
+mipmaps/generate=false
+mipmaps/limit=-1
+roughness/mode=0
+roughness/src_normal=""
+process/channel_remap/red=0
+process/channel_remap/green=1
+process/channel_remap/blue=2
+process/channel_remap/alpha=3
+process/fix_alpha_border=true
+process/premult_alpha=false
+process/normal_map_invert_y=false
+process/hdr_as_srgb=false
+process/hdr_clamp_exposure=false
+process/size_limit=0
+detect_3d/compress_to=1
+svg/scale=1.0
+editor/scale_with_editor_scale=false
+editor/convert_colors_with_editor_theme=false
diff --git a/godot-mock/models/rmuc.glb b/godot-mock/models/rmuc.glb
new file mode 100644
index 0000000..dbc2c6c
Binary files /dev/null and b/godot-mock/models/rmuc.glb differ
diff --git a/godot-mock/models/rmuc.glb.import b/godot-mock/models/rmuc.glb.import
new file mode 100644
index 0000000..e24d646
--- /dev/null
+++ b/godot-mock/models/rmuc.glb.import
@@ -0,0 +1,48 @@
+[remap]
+
+importer="scene"
+importer_version=1
+type="PackedScene"
+uid="uid://syfeopdpojh0"
+path="res://.godot/imported/rmuc.glb-ede2179fe9b1c33d91fb5656aa809873.scn"
+
+[deps]
+
+source_file="res://models/rmuc.glb"
+dest_files=["res://.godot/imported/rmuc.glb-ede2179fe9b1c33d91fb5656aa809873.scn"]
+
+[params]
+
+nodes/root_type=""
+nodes/root_name=""
+nodes/root_script=null
+nodes/apply_root_scale=true
+nodes/root_scale=1.0
+nodes/import_as_skeleton_bones=false
+nodes/use_name_suffixes=true
+nodes/use_node_type_suffixes=true
+meshes/ensure_tangents=true
+meshes/generate_lods=true
+meshes/create_shadow_meshes=true
+meshes/light_baking=1
+meshes/lightmap_texel_size=0.2
+meshes/force_disable_compression=false
+skins/use_named_skins=true
+animation/import=true
+animation/fps=30
+animation/trimming=false
+animation/remove_immutable_tracks=true
+animation/import_rest_as_RESET=false
+import_script/path=""
+materials/extract=0
+materials/extract_format=0
+materials/extract_path=""
+_subresources={
+"nodes": {
+"PATH:RMUC2026": {
+"generate/physics": true
+}
+}
+}
+gltf/naming_version=2
+gltf/embedded_image_handling=1
diff --git a/godot-mock/models/white_cube_material.tres b/godot-mock/models/white_cube_material.tres
new file mode 100644
index 0000000..ca67bd5
--- /dev/null
+++ b/godot-mock/models/white_cube_material.tres
@@ -0,0 +1,8 @@
+[gd_resource type="StandardMaterial3D" format=2]
+
+[ext_resource type="Texture2D" uid="uid://dodhbatwmlp07" path="res://material/white_wood.png" id="1"]
+
+[resource]
+resource_name = "Material"
+albedo_texture = ExtResource( 1 )
+roughness = 0.75
diff --git a/godot-mock/project.godot b/godot-mock/project.godot
new file mode 100644
index 0000000..5391d03
--- /dev/null
+++ b/godot-mock/project.godot
@@ -0,0 +1,52 @@
+; Engine configuration file.
+; It's best edited using the editor UI and not directly,
+; since the parameters that go here are not all obvious.
+;
+; Format:
+; [section] ; section goes between []
+; param=value ; assign values to parameters
+
+config_version=5
+
+[application]
+
+config/name="Rm"
+run/main_scene="uid://dxbfgcfrit2k7"
+config/features=PackedStringArray("4.6", "Forward Plus")
+config/icon="res://models/icon.svg"
+
+[input]
+
+key_left={
+"deadzone": 0.2,
+"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":false,"ctrl_pressed":false,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":65,"key_label":0,"unicode":97,"location":0,"echo":false,"script":null)
+]
+}
+key_right={
+"deadzone": 0.2,
+"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":false,"ctrl_pressed":false,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":68,"key_label":0,"unicode":100,"location":0,"echo":false,"script":null)
+]
+}
+key_up={
+"deadzone": 0.2,
+"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":false,"ctrl_pressed":false,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":87,"key_label":0,"unicode":119,"location":0,"echo":false,"script":null)
+]
+}
+key_down={
+"deadzone": 0.2,
+"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":false,"ctrl_pressed":false,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":83,"key_label":0,"unicode":115,"location":0,"echo":false,"script":null)
+]
+}
+switch-camera={
+"deadzone": 0.2,
+"events": [Object(InputEventKey,"resource_local_to_scene":false,"resource_name":"","device":-1,"window_id":0,"alt_pressed":false,"shift_pressed":false,"ctrl_pressed":false,"meta_pressed":false,"pressed":false,"keycode":0,"physical_keycode":4194306,"key_label":0,"unicode":0,"location":0,"echo":false,"script":null)
+]
+}
+
+[physics]
+
+3d/physics_engine="Jolt Physics"
+
+[rendering]
+
+rendering_device/driver.windows="d3d12"
diff --git a/godot-mock/scene/base_cube.tscn b/godot-mock/scene/base_cube.tscn
new file mode 100644
index 0000000..f71b835
--- /dev/null
+++ b/godot-mock/scene/base_cube.tscn
@@ -0,0 +1,12 @@
+[gd_scene load_steps=2 format=3]
+
+[ext_resource type="Script" path="res://scene/sim_structure_target.gd" id="1_struct"]
+
+[node name="BaseCube" type="Node3D"]
+script = ExtResource("1_struct")
+structure_kind = "base"
+max_health = 5000
+team = "ally"
+cube_size = Vector3(1.8, 1.8, 1.8)
+hitbox_size = Vector3(1.9, 1.9, 1.9)
+display_height = 2.2
diff --git a/godot-mock/scene/battlefiled.tscn b/godot-mock/scene/battlefiled.tscn
new file mode 100644
index 0000000..7dbbb35
--- /dev/null
+++ b/godot-mock/scene/battlefiled.tscn
@@ -0,0 +1,669 @@
+[gd_scene format=3 uid="uid://dxbfgcfrit2k7"]
+
+[ext_resource type="Material" uid="uid://cbwgleagikdfb" path="res://models/cube_material.tres" id="2_316cc"]
+[ext_resource type="Script" uid="uid://c88svvsnwlpo3" path="res://scene/character_body_3d.gd" id="2_hk3fa"]
+[ext_resource type="Script" uid="uid://dkbfp0i2ppdrp" path="res://scene/sim_sidecar_client.gd" id="4_k1qk3"]
+[ext_resource type="PackedScene" uid="uid://syfeopdpojh0" path="res://models/rmuc.glb" id="5_fq2p7"]
+[ext_resource type="Script" uid="uid://biptn8maovcqt" path="res://scene/enemy.gd" id="5_rwmqo"]
+[ext_resource type="PackedScene" path="res://scene/base_cube.tscn" id="6_vblny"]
+[ext_resource type="PackedScene" path="res://scene/outpost_cube.tscn" id="7_6icyb"]
+
+[sub_resource type="BoxMesh" id="BoxMesh_k1qk3"]
+
+[sub_resource type="SphereMesh" id="SphereMesh_fq2p7"]
+
+[sub_resource type="CylinderMesh" id="CylinderMesh_k1qk3"]
+
+[sub_resource type="BoxMesh" id="BoxMesh_rwmqo"]
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_rwmqo"]
+albedo_color = Color(0, 0, 0, 1)
+
+[sub_resource type="BoxMesh" id="BoxMesh_fq2p7"]
+
+[sub_resource type="BoxShape3D" id="BoxShape3D_k1qk3"]
+size = Vector3(0.5, 0.6, 0.5)
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_fq2p7"]
+albedo_color = Color(0, 0, 0, 1)
+
+[sub_resource type="CylinderMesh" id="CylinderMesh_vblny"]
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_6icyb"]
+albedo_color = Color(0, 0, 0, 1)
+
+[sub_resource type="CylinderMesh" id="CylinderMesh_w3u4r"]
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_s7v34"]
+albedo_color = Color(0.11858138, 0.11858138, 0.11858138, 1)
+
+[sub_resource type="CapsuleMesh" id="CapsuleMesh_q2vgn"]
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_shieldfx"]
+transparency = 1
+cull_mode = 2
+albedo_color = Color(0.27450982, 0.92156863, 1, 0.24)
+emission_enabled = true
+emission = Color(0.27450982, 0.92156863, 1, 1)
+emission_energy_multiplier = 1.8
+
+[sub_resource type="SphereMesh" id="SphereMesh_shieldfx"]
+radius = 0.65
+height = 1.3
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_deathfx"]
+transparency = 1
+cull_mode = 2
+albedo_color = Color(1, 0.38431373, 0.14117648, 0)
+emission_enabled = true
+emission = Color(1, 0.38431373, 0.14117648, 1)
+emission_energy_multiplier = 0.0
+
+[sub_resource type="SphereMesh" id="SphereMesh_deathfx"]
+radius = 0.35
+height = 0.7
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_k1qk3"]
+albedo_color = Color(1, 0.2509804, 1, 1)
+
+[sub_resource type="SphereMesh" id="SphereMesh_rwmqo"]
+
+[sub_resource type="StandardMaterial3D" id="StandardMaterial3D_vblny"]
+albedo_color = Color(1, 0, 0, 1)
+
+[sub_resource type="NavigationMesh" id="NavigationMesh_rwmqo"]
+vertices = PackedVector3Array(24.13, 5.094656, 7.7003, -4.0799994, 5.094656, 7.5703, -4.0799994, 5.094656, 7.8303003, 24.519999, 5.094656, 7.8303003, -4.0799994, 5.094656, -7.769699, -4.0799994, 5.094656, -7.5096993, 24.26, 5.094656, -7.5096993, 24.519999, 5.094656, -7.769699, 8.27, 0.054656252, -5.8196993, 8.79, 0.054656252, -6.0796995, 6.3199997, 0.17465624, -6.0796995, -0.43999958, 0.29465625, -7.1196995, -0.43999958, 0.29465625, -4.9096994, 2.1600003, 0.29465625, -4.7796993, 6.58, 0.29465625, -7.1196995, 5.626666, 0.29465625, -5.863033, 2.0300002, 0.29465625, -3.8696995, 1.25, 0.054656252, -2.1796994, 5.1499996, 0.054656252, -1.2696996, 11.65, 0.29465625, -6.0796995, 9.7, 0.054656252, -6.0796995, 10.74, 0.29465625, -5.9496994, 12.82, 0.41465622, -4.3896995, 13.6, 0.5346562, -4.3896995, 13.860001, 0.41465622, -4.649699, 13.860001, 0.29465625, -5.4296994, 13.209999, 0.5346562, -4.3896995, 10.61, 0.41465622, -5.4296994, 12.690001, 0.41465622, -4.1296997, 14.25, 0.29465625, -7.1196995, 10.87, 0.5346562, -6.9896994, 11.65, 0.29465625, -6.8596992, 11.546, 0.29465625, -7.0156994, 14.25, 0.29465625, -5.8196993, 16.59, 0.41465622, -5.4296994, 16.98, 0.5346562, -5.4296994, 16.98, 0.29465625, -5.8196993, 15.549999, 0.29465625, -5.8196993, 19.189999, 0.29465625, -5.8196993, 19.32, 0.29465625, -5.4296994, 20.1, 0.29465625, -5.4296994, 20.1, 0.29465625, -7.1196995, 15.68, 0.29465625, -5.5596995, 13.73, 0.41465622, -3.0896997, 13.6, 0.5346562, -3.3496995, 12.950001, 0.41465622, -3.2196994, 11.389999, 0.41465622, -1.6596994, 12.43, 0.41465622, -0.48969936, 13.73, 0.41465622, 0.6803007, 12.299999, 0.41465622, 0.5503006, 12.690001, 0.41465622, -3.4796996, 10.61, 0.41465622, -1.6596994, 10.09, 0.5346562, -1.2696996, 8.79, 0.41465622, -5.4296994, 7.49, 0.41465622, -3.6096992, 17.24, 0.17465624, -3.7396994, 17.89, 0.29465625, -3.7396994, 17.89, 0.17465624, -3.9996996, 19.189999, 0.29465625, -4.9096994, 18.279999, 0.41465622, -3.7396994, 20.1, 0.41465622, -3.7396994, 18.279999, 0.29465625, -3.9996996, 15.68, 0.054656252, -5.0396996, 15.549999, 0.054656252, -4.7796993, 14.51, 0.17465624, -4.7796993, 13.99, 0.054656252, -4.1296997, 14.51, 0.054656252, -2.5696993, 17.369999, 0.054656252, -3.2196994, 22.439999, 0.29465625, 3.2803001, 22.83, 0.29465625, 3.2803001, 22.31, 0.17465624, 3.0203, 21.4, 0.054656252, 2.1103, 21.4, 0.17465624, 2.5003004, 21.66, 0.17465624, 2.6303005, 23.74, 0.054656252, -4.2596993, 23.09, 0.054656252, -4.2596993, 23.09, 0.054656252, -3.9996996, 23.74, 0.054656252, -1.6596994, 23.74, 0.054656252, 2.2403002, 23.74, 0.17465624, 1.4603004, 23.48, 0.054656252, 1.4603004, 22.31, 0.29465625, 4.0603, 21.66, 0.29465625, 4.0603, 22.375, 0.17465624, 3.6702995, 20.75, 0.054656252, -0.7496996, 21.66, 0.29465625, -0.8796997, 21.66, 0.054656252, -1.2696996, 21.01, 0.054656252, -3.3496995, 20.49, 0.054656252, -3.2196994, 21.529999, 0.054656252, 1.0703001, 21.01, 0.054656252, 2.1103, 22.57, 0.054656252, 2.2403002, 22.18, 0.054656252, 1.2003002, 22.83, 0.054656252, 0.6803007, 22.83, 0.054656252, -0.7496996, 23.48, 0.054656252, -1.5296993, 20.619999, 0.054656252, -0.48969936, 21.01, 0.054656252, -3.9996996, -2.1299996, 0.17465624, -3.3496995, -2.6499996, 0.29465625, -3.3496995, -2.1299996, 0.17465624, -3.2196994, -2.9099996, 0.17465624, 6.0102997, -2.9099996, 0.17465624, 6.2703, -2.2599998, 0.054656252, 6.1403, -2.1299996, 0.054656252, 6.0102997, -2.7799997, 0.054656252, 4.1903, -2.7799997, 0.17465624, 5.2303, -1.9999995, 0.054656252, 5.4903, -2.1299996, 0.054656252, 6.7903004, -1.9999995, 0.17465624, -3.9996996, -2.9099996, 0.17465624, 6.7903004, -2.9099996, 0.17465624, 7.0503006, -0.6999998, 0.054656252, 7.1802998, -3.5599995, 0.054656252, -2.3096995, -3.5599995, 0.054656252, -1.7896996, -3.1699996, 0.054656252, -1.5296993, -1.3499997, 0.17465624, -2.5696993, -1.3499997, 0.17465624, -3.9996996, -2.1299996, 0.054656252, -2.3096995, -0.6999998, 0.054656252, 3.2803001, -0.43999958, 0.054656252, 3.1503, -1.2199998, 0.054656252, 1.0703001, -1.8699996, 0.054656252, 1.2003002, -2.5199995, 0.054656252, 0.6803007, -3.1699996, 0.054656252, 1.4603004, -1.7399998, 0.054656252, -1.2696996, -1.3499997, 0.054656252, -1.1396995, -0.8299997, 0.054656252, -2.1796994, -2.5199995, 0.054656252, -0.7496996, -3.5599995, 0.054656252, 1.7203007, -3.5599995, 0.054656252, 4.1903, 8.53, 0.41465622, 0.42030048, 9.18, 0.77465624, 0.29030037, 9.05, 0.5346562, -0.22969961, 6.3199997, 0.41465622, 2.5003004, 6.71, 0.41465622, 3.2803001, 7.49, 0.41465622, 3.2803001, 8.53, 0.41465622, 1.2003002, 7.62, 0.41465622, 3.5403004, 9.05, 0.41465622, 1.5903006, 6.45, 0.41465622, -2.1796994, 21.14, 0.29465625, 0.5503006, 20.619999, 0.054656252, 0.5503006, 19.06, 0.054656252, 2.1103, 15.289999, 0.054656252, -0.8796997, 15.289999, 0.054656252, 0.9403, -0.30999947, 0.054656252, 0.5503006, -0.8299997, 0.29465625, 0.5503006, -1.3499997, 0.29465625, -0.8796997, -0.30999947, 0.054656252, -0.6196995, 2.94, 0.054656252, 3.1503, 5.0200005, 0.054656252, 0.9403, 5.8, 0.054656252, 2.6303005, 11.389999, 0.41465622, 5.1003, 11.389999, 0.41465622, 5.3603, 11.65, 0.41465622, 5.3603, 14.379999, 0.29465625, 1.4603004, 14.25, 0.41465622, 1.2003002, 13.73, 0.41465622, 1.7203007, 8.79, 0.29465625, 6.0102997, 10.61, 0.054656252, 6.0102997, 9.57, 0.29465625, 5.8803005, 9.57, 0.41465622, 5.3603, 7.62, 0.41465622, 4.0603, 10.74, 0.41465622, 5.3603, 10.74, 0.41465622, 5.1003, 12.299999, 0.41465622, 1.3303003, 11.13, 0.41465622, 2.2403002, 12.17, 0.054656252, 5.6203003, 11.52, 0.054656252, 5.8803005, 13.99, 0.17465624, 6.0102997, 20.619999, 0.29465625, 7.1802998, 20.75, 0.29465625, 4.9703007, 18.15, 0.29465625, 4.8403006, 13.6, 0.29465625, 7.1802998, 18.8, 0.054656252, 2.2403002, 18.15, 0.29465625, 4.1903, 18.583332, 0.29465625, 2.8902998, 0.21000004, 0.29465625, 5.3603, 0.99000025, 0.29465625, 5.3603, 1.1200004, 0.29465625, 4.9703007, 0.21000004, 0.41465622, 3.6703005, 5.8, 0.17465624, 4.8403006, 6.3199997, 0.054656252, 4.0603, 6.3199997, 0.054656252, 3.5403004, 3.0700002, 0.17465624, 3.6703005, 4.63, 0.054656252, 5.1003, 4.76, 0.054656252, 4.8403006, 1.6400003, 0.41465622, 3.6703005, 9.7, 0.65465623, 6.5303, 9.44, 0.65465623, 6.5303, 9.44, 0.5346562, 6.7903004, 9.7, 0.65465623, 7.1802998, 6.1900005, 0.29465625, 5.7503004, 3.33, 0.41465622, 5.4903, 3.33, 0.29465625, 5.7503004, 8.66, 0.29465625, 6.7903004, 1.1200004, 0.29465625, 5.7503004, 0.21000004, 0.29465625, 7.1802998, 6.58, 0.41465622, 4.4503, 6.3199997, 0.41465622, 4.8403006, 6.45, 0.29465625, 5.4903, 7.3599997, 0.41465622, 4.4503, 8.24, 0.29465625, 7.1802998, 23.74, 1.0146562, 4.8403006, 23.349998, 1.0146562, 4.4503, 23.09, 1.0146562, 4.4503, 22.96, 1.0146562, 5.8803005, 22.96, 1.0146562, 6.9203005, 23.74, 1.0146562, 6.4003, 23.09, 0.054656252, 7.1802998, 23.09, 0.054656252, 5.8803005, 22.96, 0.054656252, 7.0503006, 22.439999, 0.054656252, 7.0503006)
+polygons = [PackedInt32Array(1, 0, 2), PackedInt32Array(2, 0, 3), PackedInt32Array(5, 4, 6), PackedInt32Array(6, 4, 7), PackedInt32Array(0, 6, 3), PackedInt32Array(3, 6, 7), PackedInt32Array(10, 9, 8), PackedInt32Array(10, 15, 14), PackedInt32Array(14, 15, 13), PackedInt32Array(14, 13, 12), PackedInt32Array(14, 12, 11), PackedInt32Array(18, 17, 16), PackedInt32Array(10, 8, 15), PackedInt32Array(15, 8, 13), PackedInt32Array(13, 8, 16), PackedInt32Array(16, 8, 18), PackedInt32Array(19, 21, 20), PackedInt32Array(23, 26, 24), PackedInt32Array(24, 26, 22), PackedInt32Array(24, 22, 25), PackedInt32Array(21, 19, 27), PackedInt32Array(27, 19, 22), PackedInt32Array(27, 22, 28), PackedInt32Array(30, 32, 31), PackedInt32Array(31, 32, 29), PackedInt32Array(29, 33, 25), PackedInt32Array(19, 31, 22), PackedInt32Array(22, 31, 25), PackedInt32Array(25, 31, 29), PackedInt32Array(35, 34, 36), PackedInt32Array(36, 34, 37), PackedInt32Array(36, 37, 29), PackedInt32Array(39, 38, 40), PackedInt32Array(40, 38, 41), PackedInt32Array(34, 42, 37), PackedInt32Array(37, 33, 29), PackedInt32Array(38, 36, 41), PackedInt32Array(41, 36, 29), PackedInt32Array(44, 43, 45), PackedInt32Array(45, 43, 46), PackedInt32Array(46, 43, 47), PackedInt32Array(47, 43, 48), PackedInt32Array(48, 49, 47), PackedInt32Array(27, 28, 50), PackedInt32Array(45, 46, 50), PackedInt32Array(50, 46, 51), PackedInt32Array(51, 52, 50), PackedInt32Array(50, 52, 27), PackedInt32Array(27, 52, 53), PackedInt32Array(53, 52, 54), PackedInt32Array(57, 56, 55), PackedInt32Array(58, 39, 40), PackedInt32Array(61, 58, 59), PackedInt32Array(59, 58, 60), PackedInt32Array(60, 58, 40), PackedInt32Array(63, 62, 55), PackedInt32Array(55, 62, 57), PackedInt32Array(57, 62, 58), PackedInt32Array(64, 63, 65), PackedInt32Array(65, 63, 66), PackedInt32Array(66, 63, 55), PackedInt32Array(66, 55, 67), PackedInt32Array(58, 61, 57), PackedInt32Array(68, 70, 69), PackedInt32Array(73, 72, 71), PackedInt32Array(75, 74, 76), PackedInt32Array(76, 74, 77), PackedInt32Array(80, 79, 78), PackedInt32Array(68, 83, 70), PackedInt32Array(70, 83, 81), PackedInt32Array(70, 81, 82), PackedInt32Array(70, 82, 73), PackedInt32Array(85, 84, 86), PackedInt32Array(86, 84, 88), PackedInt32Array(86, 88, 87), PackedInt32Array(71, 90, 89), PackedInt32Array(70, 73, 91), PackedInt32Array(91, 73, 71), PackedInt32Array(91, 71, 92), PackedInt32Array(92, 71, 89), PackedInt32Array(93, 80, 92), PackedInt32Array(92, 80, 91), PackedInt32Array(91, 80, 78), PackedInt32Array(94, 86, 95), PackedInt32Array(84, 96, 88), PackedInt32Array(95, 86, 77), PackedInt32Array(77, 86, 87), PackedInt32Array(77, 87, 97), PackedInt32Array(77, 97, 76), PackedInt32Array(94, 95, 93), PackedInt32Array(93, 95, 80), PackedInt32Array(100, 99, 98), PackedInt32Array(102, 101, 103), PackedInt32Array(103, 101, 104), PackedInt32Array(107, 106, 105), PackedInt32Array(108, 103, 104), PackedInt32Array(100, 98, 109), PackedInt32Array(110, 108, 111), PackedInt32Array(111, 108, 112), PackedInt32Array(114, 113, 115), PackedInt32Array(109, 117, 100), PackedInt32Array(100, 117, 116), PackedInt32Array(100, 116, 118), PackedInt32Array(119, 121, 120), PackedInt32Array(124, 123, 122), PackedInt32Array(116, 127, 118), PackedInt32Array(118, 127, 125), PackedInt32Array(125, 127, 126), PackedInt32Array(128, 115, 125), PackedInt32Array(125, 115, 118), PackedInt32Array(118, 115, 113), PackedInt32Array(123, 124, 128), PackedInt32Array(128, 124, 115), PackedInt32Array(129, 124, 122), PackedInt32Array(104, 107, 108), PackedInt32Array(108, 107, 112), PackedInt32Array(105, 119, 107), PackedInt32Array(107, 119, 112), PackedInt32Array(122, 121, 129), PackedInt32Array(129, 121, 119), PackedInt32Array(129, 119, 105), PackedInt32Array(129, 105, 130), PackedInt32Array(133, 132, 131), PackedInt32Array(135, 134, 136), PackedInt32Array(136, 134, 137), PackedInt32Array(137, 134, 131), PackedInt32Array(138, 136, 139), PackedInt32Array(139, 136, 137), PackedInt32Array(133, 131, 140), PackedInt32Array(140, 131, 134), PackedInt32Array(133, 140, 52), PackedInt32Array(52, 140, 54), PackedInt32Array(141, 89, 142), PackedInt32Array(142, 89, 90), PackedInt32Array(142, 90, 143), PackedInt32Array(67, 144, 66), PackedInt32Array(144, 67, 145), PackedInt32Array(145, 67, 143), PackedInt32Array(143, 67, 96), PackedInt32Array(96, 67, 88), PackedInt32Array(96, 142, 143), PackedInt32Array(147, 146, 121), PackedInt32Array(121, 146, 120), PackedInt32Array(148, 126, 149), PackedInt32Array(149, 126, 127), PackedInt32Array(149, 127, 17), PackedInt32Array(17, 146, 149), PackedInt32Array(120, 146, 150), PackedInt32Array(150, 146, 151), PackedInt32Array(151, 146, 18), PackedInt32Array(18, 146, 17), PackedInt32Array(151, 152, 150), PackedInt32Array(155, 154, 153), PackedInt32Array(157, 156, 158), PackedInt32Array(158, 156, 155), PackedInt32Array(159, 161, 160), PackedInt32Array(161, 159, 162), PackedInt32Array(162, 159, 163), PackedInt32Array(165, 164, 162), PackedInt32Array(49, 48, 166), PackedInt32Array(166, 48, 158), PackedInt32Array(163, 138, 162), PackedInt32Array(162, 138, 165), PackedInt32Array(165, 138, 139), PackedInt32Array(165, 139, 167), PackedInt32Array(153, 165, 167), PackedInt32Array(166, 158, 167), PackedInt32Array(167, 158, 153), PackedInt32Array(153, 158, 155), PackedInt32Array(168, 170, 169), PackedInt32Array(172, 171, 173), PackedInt32Array(173, 171, 170), PackedInt32Array(170, 171, 174), PackedInt32Array(175, 145, 143), PackedInt32Array(175, 177, 145), PackedInt32Array(145, 177, 176), PackedInt32Array(173, 170, 176), PackedInt32Array(176, 170, 168), PackedInt32Array(176, 168, 145), PackedInt32Array(179, 178, 180), PackedInt32Array(180, 178, 181), PackedInt32Array(184, 183, 182), PackedInt32Array(181, 188, 180), PackedInt32Array(180, 188, 185), PackedInt32Array(180, 185, 186), PackedInt32Array(186, 185, 187), PackedInt32Array(182, 187, 184), PackedInt32Array(184, 187, 152), PackedInt32Array(152, 187, 185), PackedInt32Array(152, 185, 150), PackedInt32Array(190, 189, 191), PackedInt32Array(191, 189, 192), PackedInt32Array(194, 193, 195), PackedInt32Array(195, 193, 196), PackedInt32Array(179, 197, 178), PackedInt32Array(178, 197, 198), PackedInt32Array(200, 199, 201), PackedInt32Array(201, 199, 202), PackedInt32Array(201, 202, 159), PackedInt32Array(196, 191, 192), PackedInt32Array(192, 203, 196), PackedInt32Array(196, 203, 195), PackedInt32Array(195, 203, 197), PackedInt32Array(197, 203, 198), PackedInt32Array(201, 159, 193), PackedInt32Array(193, 159, 196), PackedInt32Array(202, 163, 159), PackedInt32Array(205, 204, 206), PackedInt32Array(206, 204, 207), PackedInt32Array(207, 204, 209), PackedInt32Array(207, 209, 208), PackedInt32Array(212, 211, 210), PackedInt32Array(212, 210, 213)]
+cell_size = 0.13
+cell_height = 0.12
+agent_height = 0.35
+agent_radius = 0.15
+agent_max_climb = 0.12
+
+[sub_resource type="BoxShape3D" id="BoxShape3D_fq2p7"]
+size = Vector3(29, 5, 0.5)
+
+[sub_resource type="BoxShape3D" id="BoxShape3D_rwmqo"]
+size = Vector3(29, 5, 0.5)
+
+[sub_resource type="BoxShape3D" id="BoxShape3D_vblny"]
+size = Vector3(15, 5, 0.5)
+
+[sub_resource type="PlaneMesh" id="PlaneMesh_rwmqo"]
+
+[sub_resource type="BoxShape3D" id="BoxShape3D_6icyb"]
+size = Vector3(2, 0.01, 2)
+
+[sub_resource type="CylinderMesh" id="CylinderMesh_rwmqo"]
+
+[sub_resource type="CylinderShape3D" id="CylinderShape3D_fq2p7"]
+radius = 0.1
+
+[node name="Node3D" type="Node3D" unique_id=1105996179]
+transform = Transform3D(1, -3.5527137e-15, -2.1175824e-22, 3.5527137e-15, 1, 3.5527137e-15, -2.1175824e-22, -3.5527137e-15, 1, 0, 0, 0)
+
+[node name="DirectionalLight3D" type="DirectionalLight3D" parent="." unique_id=95683172]
+transform = Transform3D(1, -3.1763736e-22, 3.9514623e-22, 7.523164e-37, 0.8660254, 0.5, 0, -0.5, 0.8660254, 8.955051, 8.054308, 17.734684)
+light_energy = 1.734
+light_indirect_energy = 3.0
+light_volumetric_fog_energy = 3.2
+
+[node name="CharacterBody3D" type="CharacterBody3D" parent="." unique_id=399290806 node_paths=PackedStringArray("target_node")]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 8, 0, 4.3)
+script = ExtResource("2_hk3fa")
+target_node = NodePath("../TargetPoint")
+move_speed = 2.0
+bullet_speed = 20.0
+
+[node name="chassis" type="MeshInstance3D" parent="CharacterBody3D" unique_id=377979430]
+transform = Transform3D(0.5, -6.018531e-38, 0, 3.761582e-37, 0.08, 0, 0, 0, 0.5, 0, 0, 0)
+material_override = ExtResource("2_316cc")
+mesh = SubResource("BoxMesh_k1qk3")
+
+[node name="wheel1" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=765830144]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, -0.4, -0.75, 0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel2" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1875644991]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, 0.4, -0.75, 0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel3" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=312304512]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, 0.4, -0.75, -0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel4" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1276586573]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, -0.4, -0.75, -0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="duo1" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=404427242]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, 0.4, 1.125, 0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo3" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=913570015]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, 0.4, 1.125, -0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo2" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1768590998]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, -0.4, 1.125, 0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo4" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1298475168]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, -0.4, 1.125, -0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="ban1" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=451402236]
+transform = Transform3D(0.7, -7.523163e-38, -1.5777218e-30, 3.2913842e-36, 0.625, 0, 0, 0, 0.1, -2.1175835e-23, 1.125, 0.4)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia1" type="MeshInstance3D" parent="CharacterBody3D/chassis/ban1" unique_id=1744243666]
+transform = Transform3D(0.35, -6.029561e-29, 3.3132164e-29, 1.8431748e-36, 1.8793852, 0.13680804, -3.0851198e-29, -0.6840402, 0.37587705, 1.1797959e-22, 1.2, 0.39999986)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban2" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1144099364]
+transform = Transform3D(0.7, -7.523163e-38, -1.5777218e-30, 3.2913842e-36, 0.625, 0, 0, 0, 0.1, 2.1175835e-23, 1.125, -0.4)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia3" type="MeshInstance3D" parent="CharacterBody3D/chassis/ban2" unique_id=1725608911]
+transform = Transform3D(-0.2857143, 8.542957e-09, -4.694316e-09, -1.9765971e-22, 1.8793852, 0.13680804, 1.7484554e-07, 0.6840402, -0.37587696, 9.377865e-23, 1.2, -0.39999986)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban3" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=451463991]
+transform = Transform3D(-3.059797e-08, -7.523163e-38, 0.1, -1.6940659e-21, 0.625, -1.1469945e-22, -0.7, 0, -4.371139e-09, 0.4, 1.125, 0)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia4" type="MeshInstance3D" parent="CharacterBody3D/chassis/ban3" unique_id=69680967]
+transform = Transform3D(0.28571433, 4.440892e-16, 0, 8.4703295e-22, 1.8793855, 0.13680805, 7.1054274e-15, -0.68404025, 0.375877, -2.4977922e-09, 1.2000004, 0.4000001)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban4" type="MeshInstance3D" parent="CharacterBody3D/chassis" unique_id=1898488303]
+transform = Transform3D(-3.059797e-08, -7.523163e-38, 0.1, -1.6940659e-21, 0.625, -1.1469945e-22, -0.7, 0, -4.371139e-09, -0.4, 1.125, 0)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia2" type="MeshInstance3D" parent="CharacterBody3D/chassis/ban4" unique_id=1823072376]
+transform = Transform3D(-0.28571433, -8.542958e-09, 4.694316e-09, -2.5410988e-21, 1.8793855, 0.13680805, -1.7484555e-07, 0.68404025, -0.375877, 2.4977922e-09, 1.2000004, -0.4000001)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="CharacterBody3D" unique_id=1621516590]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0.2, 0)
+shape = SubResource("BoxShape3D_k1qk3")
+
+[node name="NavigationAgent3D" type="NavigationAgent3D" parent="CharacterBody3D" unique_id=1467279966]
+path_desired_distance = 0.5
+target_desired_distance = 0.2
+path_postprocessing = 1
+radius = 0.3
+max_speed = 5.0
+
+[node name="gimbal" type="MeshInstance3D" parent="CharacterBody3D" unique_id=1574179399]
+transform = Transform3D(0.24999657, -7.523163e-38, 0.0013089909, -5.7902643e-24, 0.099999994, -5.293956e-23, -0.0013089909, 0, 0.24999657, 0, 0.15, 0)
+material_override = SubResource("StandardMaterial3D_fq2p7")
+mesh = SubResource("CylinderMesh_vblny")
+
+[node name="top_yaw" type="MeshInstance3D" parent="CharacterBody3D/gimbal" unique_id=1711492471]
+transform = Transform3D(0.24999657, -5.5462123e-25, -0.0013089909, 4.701977e-37, 1, -2.6481335e-23, 0.0013089909, 1.0592389e-22, 0.24999657, 0.2, 1.8, 0.002)
+material_override = SubResource("StandardMaterial3D_6icyb")
+mesh = SubResource("CylinderMesh_w3u4r")
+
+[node name="shooter" type="MeshInstance3D" parent="CharacterBody3D/gimbal/top_yaw" unique_id=310161605]
+transform = Transform3D(-2.1855694e-08, -1, 0, 0.5, -4.371139e-08, 0, 0, 0, 1, 0.7, 0.8, 0)
+material_override = SubResource("StandardMaterial3D_s7v34")
+mesh = SubResource("CapsuleMesh_q2vgn")
+
+[node name="ShieldFX" type="MeshInstance3D" parent="CharacterBody3D" unique_id=576506011]
+transform = Transform3D(0.778, 0, 0, 0, 1, 0, 0, 0, 0.778, 0, 0, 0)
+material_override = SubResource("StandardMaterial3D_shieldfx")
+mesh = SubResource("SphereMesh_shieldfx")
+
+[node name="DeathBurstFX" type="MeshInstance3D" parent="CharacterBody3D" unique_id=1893109395]
+transform = Transform3D(0.35, 0, 0, 0, 0.35, 0, 0, 0, 0.35, 0, 0.25, 0)
+visible = false
+material_override = SubResource("StandardMaterial3D_deathfx")
+mesh = SubResource("SphereMesh_deathfx")
+
+[node name="TargetPoint" type="Node3D" parent="." unique_id=574438231]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 8, 0, 4.3)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="TargetPoint" unique_id=1867471712]
+transform = Transform3D(0.01, -7.523164e-39, 0, 7.523164e-39, 0.01, 0, 0, 0, 0.01, 2, -1.0658141e-14, 1)
+material_override = SubResource("StandardMaterial3D_k1qk3")
+mesh = SubResource("SphereMesh_rwmqo")
+
+[node name="SimSidecarClient" type="Node" parent="." unique_id=1694324441]
+script = ExtResource("4_k1qk3")
+robot_path = NodePath("../CharacterBody3D")
+target_point_path = NodePath("../TargetPoint")
+
+[node name="Camera3D" type="Camera3D" parent="." unique_id=1537111299]
+transform = Transform3D(1.1924881e-08, 1, 4.371139e-08, 0, -4.371139e-08, 1, 1, -1.1924881e-08, -5.2125306e-16, 8.532, 9, 14.455)
+fov = 90.0
+
+[node name="Enemy" type="CharacterBody3D" parent="." unique_id=1772883805 node_paths=PackedStringArray("external_camera", "auto_aim_target")]
+transform = Transform3D(-4.3711385e-08, 0, 0.99999994, 0, 1, 0, -0.99999994, 0, -4.3711385e-08, 8.089448, 7.1499745e-15, 22.298016)
+script = ExtResource("5_rwmqo")
+external_camera = NodePath("../Camera3D")
+auto_aim_target = NodePath("../CharacterBody3D")
+bullet_speed = 20.0
+
+[node name="chassis" type="MeshInstance3D" parent="Enemy" unique_id=1296085395]
+transform = Transform3D(0.5, -6.018531e-38, 0, 3.761582e-37, 0.08, 0, 0, 0, 0.5, 0, 0, 0)
+material_override = ExtResource("2_316cc")
+mesh = SubResource("BoxMesh_k1qk3")
+
+[node name="wheel1" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1029360485]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, -0.4, -0.75, 0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel2" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1372360444]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, 0.4, -0.75, 0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel3" type="MeshInstance3D" parent="Enemy/chassis" unique_id=358139042]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, 0.4, -0.75, -0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="wheel4" type="MeshInstance3D" parent="Enemy/chassis" unique_id=176892507]
+transform = Transform3D(0.2, -1.5046326e-37, -3.1554436e-30, 9.403955e-37, 1.25, 0, -3.1554436e-30, 0, 0.2, -0.4, -0.75, -0.4)
+mesh = SubResource("SphereMesh_fq2p7")
+
+[node name="duo1" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1586471647]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, 0.4, 1.125, 0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo3" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1257509974]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, 0.4, 1.125, -0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo2" type="MeshInstance3D" parent="Enemy/chassis" unique_id=7633461]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, -0.4, 1.125, 0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="duo4" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1099014941]
+transform = Transform3D(0.2, -7.523163e-38, -3.1554436e-30, 9.403955e-37, 0.625, 0, -3.1554436e-30, 0, 0.2, -0.4, 1.125, -0.4)
+mesh = SubResource("CylinderMesh_k1qk3")
+
+[node name="ban1" type="MeshInstance3D" parent="Enemy/chassis" unique_id=329014101]
+transform = Transform3D(0.7, -7.523163e-38, -1.5777218e-30, 3.2913842e-36, 0.625, 0, 0, 0, 0.1, -2.1175835e-23, 1.125, 0.4)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia1" type="MeshInstance3D" parent="Enemy/chassis/ban1" unique_id=189893944]
+transform = Transform3D(0.35, -6.029561e-29, 3.3132164e-29, 1.8431748e-36, 1.8793852, 0.13680804, -3.0851198e-29, -0.6840402, 0.37587705, 1.1797959e-22, 1.2, 0.39999986)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban2" type="MeshInstance3D" parent="Enemy/chassis" unique_id=553705054]
+transform = Transform3D(0.7, -7.523163e-38, -1.5777218e-30, 3.2913842e-36, 0.625, 0, 0, 0, 0.1, 2.1175835e-23, 1.125, -0.4)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia3" type="MeshInstance3D" parent="Enemy/chassis/ban2" unique_id=1743471262]
+transform = Transform3D(-0.2857143, 8.542957e-09, -4.694316e-09, -1.9765971e-22, 1.8793852, 0.13680804, 1.7484554e-07, 0.6840402, -0.37587696, 9.377865e-23, 1.2, -0.39999986)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban3" type="MeshInstance3D" parent="Enemy/chassis" unique_id=896440495]
+transform = Transform3D(-3.059797e-08, -7.523163e-38, 0.1, -1.6940659e-21, 0.625, -1.1469945e-22, -0.7, 0, -4.371139e-09, 0.4, 1.125, 0)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia4" type="MeshInstance3D" parent="Enemy/chassis/ban3" unique_id=1228538780]
+transform = Transform3D(0.28571433, 4.440892e-16, 0, 8.4703295e-22, 1.8793855, 0.13680805, 7.1054274e-15, -0.68404025, 0.375877, -2.4977922e-09, 1.2000004, 0.4000001)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="ban4" type="MeshInstance3D" parent="Enemy/chassis" unique_id=1651694655]
+transform = Transform3D(-3.059797e-08, -7.523163e-38, 0.1, -1.6940659e-21, 0.625, -1.1469945e-22, -0.7, 0, -4.371139e-09, -0.4, 1.125, 0)
+mesh = SubResource("BoxMesh_rwmqo")
+
+[node name="zhuangjia2" type="MeshInstance3D" parent="Enemy/chassis/ban4" unique_id=1227369877]
+transform = Transform3D(-0.28571433, -8.542958e-09, 4.694316e-09, -2.5410988e-21, 1.8793855, 0.13680805, -1.7484555e-07, 0.68404025, -0.375877, 2.4977922e-09, 1.2000004, -0.4000001)
+material_override = SubResource("StandardMaterial3D_rwmqo")
+mesh = SubResource("BoxMesh_fq2p7")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="Enemy" unique_id=1794877453]
+transform = Transform3D(1, -7.523164e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0.195, 0)
+shape = SubResource("BoxShape3D_k1qk3")
+
+[node name="gimbal" type="MeshInstance3D" parent="Enemy" unique_id=2020032932]
+transform = Transform3D(0.24999656, -3.1058808e-23, 0.0013089908, -1.8611564e-23, 0.099999994, -5.293956e-23, -0.0013089908, -2.646978e-23, 0.24999656, 0.0013093948, 0.15170148, -7.6293945e-05)
+material_override = SubResource("StandardMaterial3D_vblny")
+mesh = SubResource("CylinderMesh_vblny")
+
+[node name="top_yaw" type="MeshInstance3D" parent="Enemy/gimbal" unique_id=1800830162]
+transform = Transform3D(0.24999657, -5.5462123e-25, -0.0013089909, 4.701977e-37, 1, -2.6481335e-23, 0.0013089909, 1.0592389e-22, 0.24999657, 0.2, 1.8, 0.002)
+material_override = SubResource("StandardMaterial3D_6icyb")
+mesh = SubResource("CylinderMesh_w3u4r")
+
+[node name="pitch_pivot" type="Node3D" parent="Enemy/gimbal/top_yaw" unique_id=1717250831]
+
+[node name="shooter" type="MeshInstance3D" parent="Enemy/gimbal/top_yaw/pitch_pivot" unique_id=1518917445]
+transform = Transform3D(-2.1855694e-08, -1, 0, 0.5, -4.371139e-08, 0, 0, 0, 1, 0.7, 0.8, 0)
+material_override = SubResource("StandardMaterial3D_s7v34")
+mesh = SubResource("CapsuleMesh_q2vgn")
+
+[node name="Camera3D" type="Camera3D" parent="Enemy/gimbal/top_yaw/pitch_pivot" unique_id=1268832185]
+transform = Transform3D(-6.9938227e-07, 0, -15.428147, 0, 10.861508, 0, 16.000002, 0, -6.743857e-07, 0.2, 2.35, 0.002)
+keep_aspect = 0
+
+[node name="NavigationRegion3D" type="NavigationRegion3D" parent="." unique_id=51013653]
+transform = Transform3D(1.1924881e-08, 0, -1, 0, 1, 0, 1, 0, 1.1924881e-08, 8, 0, 4.4)
+navigation_mesh = SubResource("NavigationMesh_rwmqo")
+
+[node name="RMUC" parent="NavigationRegion3D" unique_id=698774227 instance=ExtResource("5_fq2p7")]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 0, 0, 1.648)
+
+[node name="RMUC2026" parent="NavigationRegion3D/RMUC" index="0" unique_id=545208053]
+transform = Transform3D(0.001, 0, 0, 0, 0, -0.001, 0, 0.001, 0, 10.151, 1.536, 0)
+
+[node name="CollisionShape3D" parent="NavigationRegion3D/RMUC/RMUC2026/StaticBody3D" parent_id_path=PackedInt32Array(698774227, 1144434124) index="0" unique_id=490313683]
+transform = Transform3D(1, 0, 0, 0, 1, 4.2365687e-23, 0, 4.2365687e-23, 1, 3.959961, -28.354492, 0)
+
+[node name="NavigationObstacle3D" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1055745221]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 10.5, 0, 0.25)
+vertices = PackedVector3Array(-1.4408627, 0, 1.3039565, 0.539402, 0, 1.9603705, 1.749608, 0, 1.0291481, 1.903347, 0, -0.66905785, 0.9657097, 0, -1.76125)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D2" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=448538712]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 12, -2.4868996e-14, 7)
+vertices = PackedVector3Array(1.8024263, 0, -0.65430546, 1.5943489, 0, 0.46744537, -1.3701124, 0, 0.48092413, -1.3852577, 0, -0.510571)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D3" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1850042305]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, -8.470329e-22, 1.4210855e-14, -4)
+vertices = PackedVector3Array(-0.9631338, 0, 1.7836473, -1.197648, 0, -0.5748253, 1.861629, 0, -0.6497083, 1.3873281, 0, 1.8640118)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D4" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1011828085]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 6, 0, 0)
+vertices = PackedVector3Array(0.49421358, 0, -2.34516, 0.42330074, 0, 2.0900168, -0.20495653, 0, 1.3996189, -0.40433168, 0, -1.1225183)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D5" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1957002206]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 14.5, 0, 0)
+vertices = PackedVector3Array(-0.78390884, 0, 1.8293462, -0.76187706, 0, -3.075325, -0.0067214966, 0, -1.6018763, 0.3204174, 0, -0.6930895, 0.32405758, 0, 0.6135206)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D6" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=708580516]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, -2, 0, -6)
+vertices = PackedVector3Array(1.1882963, 0, -1.5941181, 1.1911917, 0, 1.3439622, -1.4995584, 0, 1.4661622, -1.432008, 0, -1.3718367)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D7" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=2026956625]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 8, 0, -7)
+vertices = PackedVector3Array(-1.3482428, 0, 0.5999403, -1.4668894, 0, -0.4036374, 2.8120651, 0, -0.39567184, 2.9096794, 0, 0.68608904)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D8" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1497781929]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 21.5, 0, -7)
+vertices = PackedVector3Array(-0.7093849, 0, 2.9916444, 1.5970879, 0, 2.9476948, 1.5447845, 0, -0.7513323, -0.81090546, 0, -0.7159705)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D9" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1153428625]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 22, 0, 5.5)
+vertices = PackedVector3Array(-1.3580322, 0, 1.636344, -1.290348, 0, -1.4906049, 1.1020145, 0, -1.3882055, 0.9726753, 0, 1.568049)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationObstacle3D10" type="NavigationObstacle3D" parent="NavigationRegion3D" unique_id=1880402920]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 20, 0, 4)
+vertices = PackedVector3Array(-1.0992756, 0, -1.9357076, 1.3942451, 0, -1.8368711, 1.1669044, 0, 0.51805353, -1.8777905, 0, 0.55597544)
+affect_navigation_mesh = true
+carve_navigation_mesh = true
+
+[node name="NavigationLink3D" type="NavigationLink3D" parent="NavigationRegion3D" unique_id=627531415]
+bidirectional = false
+start_position = Vector3(4.4, 0.3, 5.9)
+end_position = Vector3(4.4, 0, 4.9)
+
+[node name="wall1" type="StaticBody3D" parent="NavigationRegion3D" unique_id=1797024284]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/wall1" unique_id=1890350700]
+transform = Transform3D(1, -7.523164e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 10.2, 2.4, 7.75)
+shape = SubResource("BoxShape3D_fq2p7")
+
+[node name="wall2" type="StaticBody3D" parent="NavigationRegion3D" unique_id=408700258]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/wall2" unique_id=1979641143]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 10.2, 2.4, -7.75)
+shape = SubResource("BoxShape3D_rwmqo")
+
+[node name="wall3" type="StaticBody3D" parent="NavigationRegion3D" unique_id=193417028]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/wall3" unique_id=588185280]
+transform = Transform3D(-4.371139e-08, -7.5231634e-37, 1, 2.1175824e-22, 1, -5.646419e-23, -1, 0, -4.371139e-08, 24.3, 2.4, 0)
+shape = SubResource("BoxShape3D_vblny")
+
+[node name="wall4" type="StaticBody3D" parent="NavigationRegion3D" unique_id=424012949]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/wall4" unique_id=1172197456]
+transform = Transform3D(-4.371139e-08, -7.5231634e-37, 1, 2.1175824e-22, 1, -5.646419e-23, -1, 0, -4.371139e-08, -4.1, 2.4, 0)
+shape = SubResource("BoxShape3D_vblny")
+
+[node name="NavigationLink3D2" type="NavigationLink3D" parent="NavigationRegion3D" unique_id=608468896]
+bidirectional = false
+start_position = Vector3(16, 0.3, -5.9)
+end_position = Vector3(16, 0, -4.8)
+
+[node name="fluentgtround1" type="StaticBody3D" parent="NavigationRegion3D" unique_id=1957484968]
+transform = Transform3D(1, 0, 0, 0, 1, 0, 0, 0, 1, 0, -0.07, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1" unique_id=1363651962]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 2.55, 0.17, 6.45)
+mesh = SubResource("PlaneMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1" unique_id=864143506]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 2.55, 0.17, 6.45)
+shape = SubResource("BoxShape3D_6icyb")
+
+[node name="fluent1" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=1978099758]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent1" unique_id=1812210897]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 1.5, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent1" unique_id=1939592135]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 1.5, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent2" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=1830563561]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent2" unique_id=684398208]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 1.8, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent2" unique_id=1663631442]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 1.8, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent3" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=1512979435]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent3" unique_id=130544606]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.1, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent3" unique_id=1298610969]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.1, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent4" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=398753244]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent4" unique_id=1186578141]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.4, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent4" unique_id=72517108]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.4, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent5" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=469409719]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent5" unique_id=988480075]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.7, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent5" unique_id=1252217022]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.7, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent6" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=984106198]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent6" unique_id=690177691]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent6" unique_id=442043700]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent7" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=1924664725]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent7" unique_id=2044984050]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3.3, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent7" unique_id=1786762555]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3.3, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent8" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround1" unique_id=280742671]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround1/fluent8" unique_id=900643072]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3.6, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround1/fluent8" unique_id=1320093292]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3.6, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluentgtround2" type="StaticBody3D" parent="NavigationRegion3D" unique_id=1754602679]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 15.2, -0.07, -12.9)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2" unique_id=364469498]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 2.55, 0.17, 6.45)
+mesh = SubResource("PlaneMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2" unique_id=1833325326]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 2.55, 0.17, 6.45)
+shape = SubResource("BoxShape3D_6icyb")
+
+[node name="fluent1" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=2144671649]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent1" unique_id=1983047536]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 1.5, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent1" unique_id=1607025953]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 1.5, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent2" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=946552567]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent2" unique_id=935686135]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 1.8, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent2" unique_id=405444451]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 1.8, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent3" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=2078234005]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent3" unique_id=22633297]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.1, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent3" unique_id=1438686737]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.1, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent4" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=1014910255]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent4" unique_id=280279916]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.4, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent4" unique_id=1047055287]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.4, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent5" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=957413672]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent5" unique_id=1691698711]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 2.7, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent5" unique_id=269191305]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 2.7, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent6" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=596860875]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent6" unique_id=554785927]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent6" unique_id=1826595874]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent7" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=1373325675]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent7" unique_id=317417286]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3.3, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent7" unique_id=301637523]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3.3, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="fluent8" type="StaticBody3D" parent="NavigationRegion3D/fluentgtround2" unique_id=1993093023]
+transform = Transform3D(1, -7.5231634e-37, 0, 7.523164e-37, 1, 0, 0, 0, 1, 0, 0, 0)
+
+[node name="MeshInstance3D" type="MeshInstance3D" parent="NavigationRegion3D/fluentgtround2/fluent8" unique_id=2013380378]
+transform = Transform3D(0.2, 0, 0, 0, -4.371139e-08, -0.2, 0, 1, -8.742278e-09, 3.6, 0.1, 6.45)
+mesh = SubResource("CylinderMesh_rwmqo")
+
+[node name="CollisionShape3D" type="CollisionShape3D" parent="NavigationRegion3D/fluentgtround2/fluent8" unique_id=1394624354]
+transform = Transform3D(1, 0, -9.256245e-30, 7.523164e-37, -4.371139e-08, -1, 0, 1, -4.371139e-08, 3.6, 0.1, 6.45)
+shape = SubResource("CylinderShape3D_fq2p7")
+
+[node name="BaseCube" parent="." unique_id=1477399072 instance=ExtResource("6_vblny")]
+transform = Transform3D(1, 3.5527137e-15, 2.1175822e-22, -3.5527137e-15, 1, -3.5527137e-15, 2.1175822e-22, 3.5527137e-15, 1, 7.9666595, 1.0475693, 3)
+cube_size = Vector3(0.5, 0.5, 0.5)
+hitbox_size = Vector3(0.5, 0.5, 0.5)
+
+[node name="OutpostCube" parent="." unique_id=1345649340 instance=ExtResource("7_6icyb")]
+transform = Transform3D(1.1924881e-08, -7.5231634e-37, -1, 0, 1, -4.2365687e-23, 1, 0, 1.1924881e-08, 4.1800375, 1.5934836, 11.460511)
+cube_size = Vector3(0.5, 0.5, 0.5)
+hitbox_size = Vector3(0.5, 0.5, 0.5)
+
+[editable path="NavigationRegion3D/RMUC"]
diff --git a/godot-mock/scene/character_body_3d.gd b/godot-mock/scene/character_body_3d.gd
new file mode 100644
index 0000000..1ae6773
--- /dev/null
+++ b/godot-mock/scene/character_body_3d.gd
@@ -0,0 +1,693 @@
+extends CharacterBody3D
+## AI 控制的我方机器人。
+## 通过 NavigationAgent3D 沿 navmesh 导航到目标点(由 Lua 决策端通过 TCP 下发),
+## 搭载可扫描/自动瞄准的云台、四块装甲板受击判定、死亡/复活循环。
+
+## 导航目标 Node3D(由 SimSidecarClient 根据 Lua nav_target 消息移动)。
+@export var target_node: Node3D
+## 底盘最大水平移动速度 (m/s)。
+@export var move_speed := 2.5
+## 底盘水平加速度 (m/s^2)。
+@export var move_accel := 5.5
+## 目标速度为零时的水平减速度(阻力)。
+@export var move_drag := 4.0
+## 底盘自旋最大速度 (rad/s,"spin" 模式使用)。
+@export var chassis_spin_speed_max := 4.5
+## 底盘自旋加速度 (rad/s^2)。
+@export var chassis_spin_accel := 10.0
+## 云台扫描最大转速 (rad/s)。
+@export var gimbal_scan_speed_max := 2.8
+## 云台旋转加速度 (rad/s^2)。
+@export var gimbal_scan_accel := 8.0
+## 云台锁定敌人后的追踪转速 (rad/s)。
+@export var gimbal_track_turn_rate := 4.5
+## 自动射击冷却时间 (s)。
+@export var auto_fire_cooldown := 0.12
+## 子弹飞行速度 (m/s)。
+@export var bullet_speed := 25.0
+## 子弹最大存活时间 (s)。
+@export var bullet_lifetime := 2.0
+## 单发子弹伤害。
+@export var bullet_damage := 20
+## 云台扫描射线长度。
+@export var scan_range := 30.0
+## 初始/最大血量。
+@export var max_health := 400
+## 初始子弹数。
+@export var spawn_bullet := 100
+## 初始金币数。
+@export var spawn_gold := 0
+## 死亡后到复活的时间间隔 (s)。
+@export var respawn_delay := 5.0
+## 复活时恢复的血量。
+@export var respawn_health := 25
+## 复活后护盾持续时间 (s)。
+@export var respawn_shield_duration := 3.0
+## 外部速度超控的有效持有时长 (s)。
+@export var control_hold_seconds := 0.2
+
+const TEAM := "ally"
+const BULLET_SCRIPT := preload("res://scene/sim_bullet.gd")
+const ARMOR_SCRIPT := preload("res://scene/sim_armor.gd")
+const DEATH_FX_DURATION := 0.6
+const SHIELD_PULSE_SPEED := 0.006
+const SHIELD_PULSE_SCALE := 0.06
+const HEALTH_BAR_ANCHOR_NAME := "HealthBarAnchor"
+const HEALTH_BAR_BACK_NAME := "HealthBarBack"
+const HEALTH_BAR_FILL_NAME := "HealthBarFill"
+const HEALTH_BAR_HEIGHT := 1.0
+const HEALTH_BAR_BACK_SIZE := Vector2(1.1, 0.14)
+const HEALTH_BAR_FILL_SIZE := Vector2(1.0, 0.10)
+const HEALTH_BAR_BACK_PRIORITY := 10
+const HEALTH_BAR_FILL_PRIORITY := 11
+const HEALTH_BAR_FILL_Z_OFFSET := -0.02
+## 四块装甲板的子节点路径(用于挂载受击判定 Area)。
+const ARMOR_NODE_PATHS := [
+ "chassis/ban1/zhuangjia1",
+ "chassis/ban4/zhuangjia2",
+ "chassis/ban2/zhuangjia3",
+ "chassis/ban3/zhuangjia4",
+]
+
+var gravity :float = ProjectSettings.get_setting("physics/3d/default_gravity")
+## 底盘行为模式: "idle" 静止 / "spin" 自旋。
+var chassis_mode := "idle"
+## 云台控制来源: "manual" 手动 / "scan" 扫描 / "auto" 自动瞄准。
+var gimbal_dominator := "manual"
+## 外部速度超控向量 (X=前, Y=右),由 Lua 遥控指令设置。
+var external_chassis_vel := Vector2.ZERO
+## 外部速度超控的剩余有效期 (s)。
+var external_chassis_vel_ttl := 0.0
+
+var current_chassis_spin_speed := 0.0
+var current_scan_speed := 0.0
+var fire_cooldown_left := 0.0
+
+var hp := max_health
+var bullet := spawn_bullet
+var gold := spawn_gold
+var is_dead := false
+var dead_left := 0.0
+var respawn_shield_left := 0.0
+
+## 敌方机器人引用,供云台自动瞄准使用。
+var enemy_target: Node3D = null
+
+## 云台扫描视线 RayCast3D。
+var scan_ray: RayCast3D = null
+## 扫描射线的调试可视化线条(动态 ImmediateMesh)。
+var scan_line: MeshInstance3D = null
+## 死亡特效 Tween。
+var death_fx_tween: Tween = null
+## 护盾效果基准缩放。
+var shield_fx_base_scale := Vector3.ONE
+## 死亡特效基准缩放。
+var death_burst_fx_base_scale := Vector3.ONE
+## 头顶血条锚点。
+var health_bar_anchor: Node3D = null
+## 头顶血条背景。
+var health_bar_back: MeshInstance3D = null
+## 头顶血条红条。
+var health_bar_fill: MeshInstance3D = null
+
+@onready var nav_agent: NavigationAgent3D = $NavigationAgent3D
+@onready var chassis_node: Node3D = $chassis
+@onready var gimbal_top_yaw: Node3D = $gimbal/top_yaw
+@onready var shooter_node: Node3D = $gimbal/top_yaw/shooter
+@onready var shield_fx: MeshInstance3D = $ShieldFX
+@onready var death_burst_fx: MeshInstance3D = $DeathBurstFX
+
+
+func _ready() -> void:
+ _setup_scan_tools()
+ _setup_armor_hitboxes()
+ _setup_health_bar()
+ shield_fx_base_scale = shield_fx.scale
+ death_burst_fx_base_scale = death_burst_fx.scale
+ _set_shield_fx_active(false)
+ _reset_death_fx()
+ _update_health_bar()
+ _face_health_bar_to_camera()
+
+
+func _physics_process(delta: float) -> void:
+ _tick_death(delta)
+ _tick_respawn_shield(delta)
+
+ fire_cooldown_left = max(fire_cooldown_left - delta, 0.0)
+ if external_chassis_vel_ttl > 0.0:
+ external_chassis_vel_ttl = max(external_chassis_vel_ttl - delta, 0.0)
+
+ if is_dead:
+ # 死亡时停止水平移动,但重力仍然作用。
+ velocity.x = 0.0
+ velocity.z = 0.0
+ else:
+ var desired_planar := _compute_desired_planar_velocity()
+ _apply_planar_inertia(desired_planar, delta)
+ _tick_chassis_spin(delta)
+ _tick_gimbal(delta)
+
+ # Gravity: only applied when not on floor (walk-off edges, stairs, etc.).
+ if not is_on_floor():
+ velocity.y -= gravity * delta
+
+ move_and_slide()
+
+ if is_dead:
+ _hide_scan_line()
+
+ _face_health_bar_to_camera()
+
+
+## 设置敌方目标引用,供云台自动瞄准使用。
+func set_enemy_target(target: Node3D) -> void:
+ enemy_target = target
+
+
+## 设置底盘模式 ("idle"/"spin"),由 Lua 控制指令调用。
+func set_chassis_mode(mode: String) -> void:
+ if is_dead:
+ return
+ chassis_mode = mode
+
+
+## 设置云台控制源 ("manual"/"scan"/"auto"),由 Lua 控制指令调用。
+func set_gimbal_dominator(dominator_name: String) -> void:
+ if is_dead:
+ return
+ gimbal_dominator = dominator_name
+
+
+## 手动设置云台 yaw 角度,仅在 gimbal_dominator == "manual" 时生效。
+func set_gimbal_direction(angle: float) -> void:
+ if is_dead or gimbal_dominator != "manual":
+ return
+ gimbal_top_yaw.rotation.y = angle
+
+
+## 设置外部速度超控(Lua 遥控),超控持续 control_hold_seconds 秒后自动失效。
+func set_external_chassis_velocity(x: float, y: float) -> void:
+ if is_dead:
+ return
+ external_chassis_vel = Vector2(x, y)
+ external_chassis_vel_ttl = control_hold_seconds
+
+
+## 返回当前模拟资源状态,供 sidecar 上报给 Lua 决策端。
+func get_sim_resource_state() -> Dictionary:
+ return {
+ "health": hp,
+ "bullet": bullet,
+ "gold": gold,
+ "dead": is_dead,
+ }
+
+
+## 用 blackboard 传来的生命/子弹/金币值同步本机资源。
+func sync_resources_from_blackboard(
+ health: Variant,
+ bullet_value: Variant,
+ gold_value: Variant = null
+) -> void:
+ if health != null:
+ hp = clampi(int(round(float(health))), 0, max_health)
+ if bullet_value != null:
+ bullet = maxi(0, int(round(float(bullet_value))))
+ if gold_value != null:
+ gold = maxi(0, int(round(float(gold_value))))
+ _update_health_bar()
+
+
+## 受到子弹伤害,血量归零时进入死亡状态。
+func apply_damage(amount: int, _armor_name: String = "") -> void:
+ if is_dead or _has_respawn_shield():
+ return
+ var next_hp : int= hp - max(amount, 0)
+ hp = maxi(0, next_hp)
+ _update_health_bar()
+ if hp <= 0:
+ _enter_death_state()
+
+
+func is_alive() -> bool:
+ return hp > 0 and not is_dead
+
+
+func get_team() -> String:
+ return TEAM
+
+
+func get_armor_target_nodes() -> Array[Node3D]:
+ var result: Array[Node3D] = []
+ for path in ARMOR_NODE_PATHS:
+ var node := get_node_or_null(path)
+ if node is Node3D:
+ result.append(node)
+ return result
+
+func _compute_desired_planar_velocity() -> Vector3:
+
+ if external_chassis_vel_ttl > 0.0:
+
+ return Vector3(external_chassis_vel.x, 0.0, external_chassis_vel.y)
+
+
+ if target_node:
+
+ nav_agent.target_position = target_node.global_position
+
+
+
+ if nav_agent.is_navigation_finished():
+
+ return Vector3.ZERO
+
+
+ var next_path_pos := nav_agent.get_next_path_position()
+
+ var current_pos := global_position
+
+ var flat := next_path_pos - current_pos
+
+ flat.y = 0.0
+
+ if flat.length() <= 0.001:
+
+ return Vector3.ZERO
+
+ look_at_target(next_path_pos, 8.0)
+
+ return flat.normalized() * move_speed
+
+
+func _apply_planar_inertia(desired: Vector3, delta: float) -> void:
+ var current := Vector3(velocity.x, 0.0, velocity.z)
+ var dv := desired - current
+ var max_step := move_accel * delta
+ if dv.length() > max_step and max_step > 0.0:
+ dv = dv.normalized() * max_step
+ var next := current + dv
+ if desired.length() < 0.01:
+ next = next.move_toward(Vector3.ZERO, move_drag * delta)
+ velocity.x = next.x
+ velocity.z = next.z
+
+
+func _tick_chassis_spin(delta: float) -> void:
+ var target_spin := 0.0
+ if chassis_mode == "spin":
+ target_spin = chassis_spin_speed_max
+ current_chassis_spin_speed = move_toward(
+ current_chassis_spin_speed, target_spin, chassis_spin_accel * delta
+ )
+ chassis_node.rotate_y(current_chassis_spin_speed * delta)
+
+
+func _tick_gimbal(delta: float) -> void:
+ match gimbal_dominator:
+ "scan":
+ _tick_scan_mode(delta)
+ "auto":
+ _tick_auto_mode(delta)
+ _:
+ current_scan_speed = move_toward(
+ current_scan_speed, 0.0, gimbal_scan_accel * delta
+ )
+ _hide_scan_line()
+
+
+func _tick_scan_mode(delta: float) -> void:
+ current_scan_speed = move_toward(
+ current_scan_speed, gimbal_scan_speed_max, gimbal_scan_accel * delta
+ )
+ gimbal_top_yaw.rotate_y(current_scan_speed * delta)
+ _update_scan_ray_visual(true)
+
+
+func _tick_auto_mode(delta: float) -> void:
+ current_scan_speed = move_toward(current_scan_speed, 0.0, gimbal_scan_accel * delta)
+ var lock := _track_enemy(delta)
+ _update_scan_ray_visual(false)
+ if lock and _can_fire():
+ _fire_bullet(TEAM)
+ bullet -= 1
+ fire_cooldown_left = auto_fire_cooldown
+
+
+func _track_enemy(delta: float) -> bool:
+ if enemy_target == null:
+ return false
+ if enemy_target.has_method("is_alive") and not bool(enemy_target.call("is_alive")):
+ return false
+
+ var target := _pick_enemy_armor_target()
+ if target == null:
+ return false
+
+ var shooter_pos := shooter_node.global_position
+ var to_target := target.global_position - shooter_pos
+ to_target.y = 0.0
+ if to_target.length() < 0.05:
+ return false
+
+ var forward := _shooter_forward()
+ forward.y = 0.0
+ if forward.length() < 0.001:
+ forward = Vector3.FORWARD
+ else:
+ forward = forward.normalized()
+
+ var target_dir := to_target.normalized()
+ var angle_error := atan2(forward.cross(target_dir).y, forward.dot(target_dir))
+ var step : float = clamp(angle_error, -gimbal_track_turn_rate * delta, gimbal_track_turn_rate * delta)
+ gimbal_top_yaw.rotate_y(step)
+
+ return absf(angle_error) <= 0.08
+
+
+func _pick_enemy_armor_target() -> Node3D:
+ if enemy_target == null:
+ return null
+ if enemy_target.has_method("get_armor_target_nodes"):
+ var armors: Array = enemy_target.call("get_armor_target_nodes")
+ var best: Node3D = null
+ var best_d2 := INF
+ for item in armors:
+ if item is Node3D:
+ var n: Node3D = item
+ var d2 := shooter_node.global_position.distance_squared_to(n.global_position)
+ if d2 < best_d2:
+ best_d2 = d2
+ best = n
+ return best
+ return null
+
+
+func _fire_bullet(team: String) -> void:
+ var bullet_node := BULLET_SCRIPT.new()
+ bullet_node.set("team", team)
+ bullet_node.set("speed", bullet_speed)
+ bullet_node.set("damage", bullet_damage)
+ bullet_node.set("lifetime", bullet_lifetime)
+ bullet_node.global_position = shooter_node.global_position + _shooter_forward() * 0.35
+ bullet_node.look_at(bullet_node.global_position + _shooter_forward(), Vector3.UP)
+ bullet_node.set("travel_direction", _shooter_forward())
+ get_tree().current_scene.add_child(bullet_node)
+
+
+func _shooter_forward() -> Vector3:
+ var forward := -shooter_node.global_basis.y
+ if forward.length() < 0.001:
+ return Vector3.FORWARD
+ return forward.normalized()
+
+
+func _setup_scan_tools() -> void:
+ scan_ray = RayCast3D.new()
+ scan_ray.name = "ScanRay"
+ scan_ray.target_position = Vector3(0.0, -scan_range, 0.0)
+ scan_ray.enabled = true
+ scan_ray.collide_with_areas = true
+ scan_ray.collide_with_bodies = true
+ shooter_node.add_child(scan_ray)
+
+ scan_line = MeshInstance3D.new()
+ scan_line.name = "ScanRayLine"
+ var mat := StandardMaterial3D.new()
+ mat.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ mat.albedo_color = Color(0.2, 1.0, 0.2, 0.95)
+ scan_line.material_override = mat
+ shooter_node.add_child(scan_line)
+ _hide_scan_line()
+
+
+func _update_scan_ray_visual(force_visible: bool) -> void:
+ if scan_ray == null or scan_line == null:
+ return
+
+ var end_local := Vector3(0.0, -scan_range, 0.0)
+ if scan_ray.is_colliding():
+ var hit_global := scan_ray.get_collision_point()
+ end_local = shooter_node.to_local(hit_global)
+
+ var mesh := ImmediateMesh.new()
+ mesh.clear_surfaces()
+ mesh.surface_begin(Mesh.PRIMITIVE_LINES)
+ mesh.surface_add_vertex(Vector3.ZERO)
+ mesh.surface_add_vertex(end_local)
+ mesh.surface_end()
+ scan_line.mesh = mesh
+ scan_line.visible = force_visible
+
+
+func _hide_scan_line() -> void:
+ if scan_line != null:
+ scan_line.visible = false
+
+
+func _has_respawn_shield() -> bool:
+ return respawn_shield_left > 0.0
+
+
+func _tick_respawn_shield(delta: float) -> void:
+ if is_dead:
+ if respawn_shield_left > 0.0:
+ respawn_shield_left = 0.0
+ _set_shield_fx_active(false)
+ return
+
+ if respawn_shield_left <= 0.0:
+ _set_shield_fx_active(false)
+ return
+
+ respawn_shield_left = max(respawn_shield_left - delta, 0.0)
+ if respawn_shield_left <= 0.0:
+ _set_shield_fx_active(false)
+ return
+
+ _set_shield_fx_active(true)
+ _update_shield_fx_visual()
+
+
+func _can_fire() -> bool:
+ return not is_dead and not _has_respawn_shield() and fire_cooldown_left <= 0.0 and bullet > 0
+
+
+func _setup_armor_hitboxes() -> void:
+ for path in ARMOR_NODE_PATHS:
+ var armor_mesh := get_node_or_null(path)
+ if armor_mesh == null:
+ continue
+ var area := ARMOR_SCRIPT.new()
+ area.set("team", TEAM)
+ area.set("armor_name", str(path.get_file()))
+ armor_mesh.add_child(area)
+ area.set("owner_robot_path", area.get_path_to(self))
+
+
+func _setup_health_bar() -> void:
+ health_bar_anchor = get_node_or_null(HEALTH_BAR_ANCHOR_NAME) as Node3D
+ if health_bar_anchor == null:
+ health_bar_anchor = Node3D.new()
+ health_bar_anchor.name = HEALTH_BAR_ANCHOR_NAME
+ health_bar_anchor.position = Vector3(0.0, HEALTH_BAR_HEIGHT, 0.0)
+ add_child(health_bar_anchor)
+
+ health_bar_back = health_bar_anchor.get_node_or_null(HEALTH_BAR_BACK_NAME) as MeshInstance3D
+ if health_bar_back == null:
+ health_bar_back = MeshInstance3D.new()
+ health_bar_back.name = HEALTH_BAR_BACK_NAME
+ var back_mesh := QuadMesh.new()
+ back_mesh.size = HEALTH_BAR_BACK_SIZE
+ health_bar_back.mesh = back_mesh
+ health_bar_back.material_override = _build_health_bar_material(
+ Color(0.08, 0.08, 0.08, 1.0),
+ HEALTH_BAR_BACK_PRIORITY
+ )
+ health_bar_anchor.add_child(health_bar_back)
+
+ health_bar_fill = health_bar_anchor.get_node_or_null(HEALTH_BAR_FILL_NAME) as MeshInstance3D
+ if health_bar_fill == null:
+ health_bar_fill = MeshInstance3D.new()
+ health_bar_fill.name = HEALTH_BAR_FILL_NAME
+ var fill_mesh := QuadMesh.new()
+ fill_mesh.size = HEALTH_BAR_FILL_SIZE
+ health_bar_fill.mesh = fill_mesh
+ health_bar_fill.material_override = _build_health_bar_material(
+ Color(0.92, 0.12, 0.12, 1.0),
+ HEALTH_BAR_FILL_PRIORITY
+ )
+ health_bar_fill.position = Vector3(0.0, 0.0, HEALTH_BAR_FILL_Z_OFFSET)
+ health_bar_anchor.add_child(health_bar_fill)
+
+
+func _build_health_bar_material(color: Color, priority: int) -> StandardMaterial3D:
+ var material := StandardMaterial3D.new()
+ material.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ material.transparency = BaseMaterial3D.TRANSPARENCY_ALPHA
+ material.no_depth_test = true
+ material.depth_draw_mode = BaseMaterial3D.DEPTH_DRAW_DISABLED
+ material.cull_mode = BaseMaterial3D.CULL_DISABLED
+ material.render_priority = priority
+ material.albedo_color = color
+ return material
+
+
+func _update_health_bar() -> void:
+ if health_bar_anchor == null or health_bar_back == null or health_bar_fill == null:
+ return
+
+ var ratio: float = 0.0
+ if max_health > 0:
+ ratio = clampf(float(hp) / float(max_health), 0.0, 1.0)
+
+ health_bar_fill.scale = Vector3(ratio, 1.0, 1.0)
+ health_bar_fill.position = Vector3(
+ -0.5 * HEALTH_BAR_FILL_SIZE.x * (1.0 - ratio),
+ 0.0,
+ HEALTH_BAR_FILL_Z_OFFSET
+ )
+
+
+func _face_health_bar_to_camera() -> void:
+ if health_bar_anchor == null:
+ return
+
+ var camera: Camera3D = get_viewport().get_camera_3d()
+ if camera == null:
+ return
+
+ health_bar_anchor.look_at(camera.global_position, Vector3.UP, true)
+
+
+func _tick_death(delta: float) -> void:
+ if not is_dead:
+ return
+ dead_left = max(dead_left - delta, 0.0)
+ if dead_left <= 0.0:
+ _respawn()
+
+
+func _enter_death_state() -> void:
+ is_dead = true
+ dead_left = respawn_delay
+ respawn_shield_left = 0.0
+ velocity = Vector3.ZERO
+ current_chassis_spin_speed = 0.0
+ current_scan_speed = 0.0
+ fire_cooldown_left = 0.0
+ chassis_mode = "idle"
+ gimbal_dominator = "manual"
+ _set_shield_fx_active(false)
+ _play_death_fx()
+
+
+func _respawn() -> void:
+ is_dead = false
+ hp = respawn_health
+ respawn_shield_left = respawn_shield_duration
+ velocity = Vector3.ZERO
+ chassis_mode = "idle"
+ gimbal_dominator = "manual"
+ current_chassis_spin_speed = 0.0
+ current_scan_speed = 0.0
+ _hide_scan_line()
+ _set_shield_fx_active(respawn_shield_left > 0.0)
+ _update_health_bar()
+
+
+func _set_shield_fx_active(active: bool) -> void:
+ if shield_fx == null:
+ return
+
+ shield_fx.visible = active
+ if active:
+ _update_shield_fx_visual()
+ return
+
+ shield_fx.scale = shield_fx_base_scale
+ var shield_mat: StandardMaterial3D = shield_fx.material_override as StandardMaterial3D
+ if shield_mat != null:
+ var shield_color: Color = shield_mat.albedo_color
+ shield_color.a = 0.24
+ shield_mat.albedo_color = shield_color
+ shield_mat.emission_energy_multiplier = 1.8
+
+
+func _update_shield_fx_visual() -> void:
+ if shield_fx == null or not shield_fx.visible:
+ return
+
+ var pulse_phase: float = float(Time.get_ticks_msec()) * SHIELD_PULSE_SPEED
+ var pulse: float = 0.5 + 0.5 * sin(pulse_phase)
+ shield_fx.scale = shield_fx_base_scale * (1.0 + SHIELD_PULSE_SCALE * pulse)
+
+ var shield_mat: StandardMaterial3D = shield_fx.material_override as StandardMaterial3D
+ if shield_mat != null:
+ var shield_color: Color = shield_mat.albedo_color
+ shield_color.a = lerpf(0.18, 0.34, pulse)
+ shield_mat.albedo_color = shield_color
+ shield_mat.emission_energy_multiplier = lerpf(1.4, 2.2, pulse)
+
+
+func _play_death_fx() -> void:
+ if death_burst_fx == null:
+ return
+
+ if death_fx_tween != null:
+ death_fx_tween.kill()
+ death_fx_tween = null
+
+ _reset_death_fx()
+ death_burst_fx.visible = true
+ var death_mat: StandardMaterial3D = death_burst_fx.material_override as StandardMaterial3D
+ if death_mat != null:
+ death_mat.emission_energy_multiplier = 2.6
+ _set_death_fx_alpha(0.9)
+
+ death_fx_tween = create_tween()
+ death_fx_tween.set_parallel(true)
+ death_fx_tween.tween_property(
+ death_burst_fx, "scale", death_burst_fx_base_scale * 3.0, DEATH_FX_DURATION
+ ).set_trans(Tween.TRANS_CUBIC).set_ease(Tween.EASE_OUT)
+ death_fx_tween.tween_method(_set_death_fx_alpha, 0.9, 0.0, DEATH_FX_DURATION)
+ death_fx_tween.chain().tween_callback(_reset_death_fx)
+
+
+func _set_death_fx_alpha(alpha: float) -> void:
+ if death_burst_fx == null:
+ return
+
+ var death_mat: StandardMaterial3D = death_burst_fx.material_override as StandardMaterial3D
+ if death_mat == null:
+ return
+
+ var death_color: Color = death_mat.albedo_color
+ death_color.a = alpha
+ death_mat.albedo_color = death_color
+ death_mat.emission_energy_multiplier = 2.6 * alpha
+
+
+func _reset_death_fx() -> void:
+ if death_burst_fx == null:
+ return
+
+ death_burst_fx.visible = false
+ death_burst_fx.scale = death_burst_fx_base_scale
+ var death_mat: StandardMaterial3D = death_burst_fx.material_override as StandardMaterial3D
+ if death_mat != null:
+ var death_color: Color = death_mat.albedo_color
+ death_color.a = 0.0
+ death_mat.albedo_color = death_color
+ death_mat.emission_energy_multiplier = 0.0
+ death_fx_tween = null
+
+
+func look_at_target(target_pos: Vector3, turn_speed: float) -> void:
+ var direction := target_pos - global_position
+ direction.y = 0.0
+ if direction.length() <= 0.1:
+ return
+ var target_basis := Basis.looking_at(direction).rotated(Vector3.UP, PI/2.0)
+ basis = basis.slerp(target_basis, clamp(turn_speed * get_physics_process_delta_time(), 0.0, 1.0))
diff --git a/godot-mock/scene/character_body_3d.gd.uid b/godot-mock/scene/character_body_3d.gd.uid
new file mode 100644
index 0000000..7f91fb9
--- /dev/null
+++ b/godot-mock/scene/character_body_3d.gd.uid
@@ -0,0 +1 @@
+uid://c88svvsnwlpo3
diff --git a/godot-mock/scene/enemy.gd b/godot-mock/scene/enemy.gd
new file mode 100644
index 0000000..8c2362a
--- /dev/null
+++ b/godot-mock/scene/enemy.gd
@@ -0,0 +1,653 @@
+extends CharacterBody3D
+## 敌方机器人,由键盘本地操控。
+## 支持 WASD 移动、空格跳跃、J 键射击,以及第一/第三人称相机切换。
+## 搭载四块装甲板受击判定,死亡后不可复活(仅停止运动)。
+
+@export var external_camera: Camera3D
+## 自瞄目标机器人。
+@export var auto_aim_target: Node3D
+## 底盘最大水平移动速度 (m/s)。
+@export var move_speed := 4.2
+## 底盘水平加速度 (m/s^2)。
+@export var move_accel := 9.0
+## 目标速度为零时的水平减速度(阻力)。
+@export var move_drag := 7.0
+## 跳跃初速度 (m/s)。
+@export var jump_velocity := 5.2
+## 射击冷却时间 (s)。
+@export var fire_cooldown := 0.2
+## 子弹飞行速度 (m/s)。
+@export var bullet_speed := 24.0
+## 子弹最大存活时间 (s)。
+@export var bullet_lifetime := 2.0
+## 子弹重力倍率,应与 sim_bullet.gd 中实际飞行参数一致。
+@export var bullet_gravity_scale := 1.0
+## 单发子弹伤害。
+@export var bullet_damage := 20
+## 初始/最大血量。
+@export var max_health := 400000
+## 初始子弹数量。
+@export var spawn_bullet := 10000000
+
+## 跳跃输入动作名称。
+@export var jump_action := "enemy_jump"
+## 射击输入动作名称。
+@export var fire_action := "enemy_fire"
+## 鼠标控制云台左右转动的灵敏度(弧度/像素)。
+@export var mouse_yaw_sensitivity := 0.003
+## 鼠标控制枪管上下俯仰的灵敏度(弧度/像素)。
+@export var mouse_pitch_sensitivity := 0.003
+## 枪管最大俯仰角(度)。
+@export var max_pitch_degrees := 30.0
+## 自瞄 yaw 跟踪速度(rad/s)。
+@export var auto_aim_yaw_rate := 10.0
+## 自瞄 pitch 跟踪速度(rad/s)。
+@export var auto_aim_pitch_rate := 10.0
+## 自瞄数值求解时允许的命中误差半径(米)。
+@export var auto_aim_hit_tolerance := 0.30
+
+const TEAM := "enemy"
+const BULLET_SCRIPT := preload("res://scene/sim_bullet.gd")
+const ARMOR_SCRIPT := preload("res://scene/sim_armor.gd")
+const MUZZLE_OFFSET := 0.35
+const AUTO_AIM_COARSE_PITCH_SAMPLES := 41
+const AUTO_AIM_REFINEMENT_ROUNDS := 2
+const AUTO_AIM_REFINEMENT_SAMPLES := 9
+const AUTO_AIM_SIM_FALLBACK_HZ := 60.0
+const HEALTH_BAR_ANCHOR_NAME := "HealthBarAnchor"
+const HEALTH_BAR_BACK_NAME := "HealthBarBack"
+const HEALTH_BAR_FILL_NAME := "HealthBarFill"
+const HEALTH_BAR_HEIGHT := 2.35
+const HEALTH_BAR_BACK_SIZE := Vector2(1.1, 0.14)
+const HEALTH_BAR_FILL_SIZE := Vector2(1.0, 0.10)
+const HEALTH_BAR_BACK_PRIORITY := 10
+const HEALTH_BAR_FILL_PRIORITY := 11
+const HEALTH_BAR_FILL_Z_OFFSET := -0.02
+## 四块装甲板的子节点路径(用于挂载受击判定 Area)。
+const ARMOR_NODE_PATHS := [
+ "chassis/ban1/zhuangjia1",
+ "chassis/ban4/zhuangjia2",
+ "chassis/ban2/zhuangjia3",
+ "chassis/ban3/zhuangjia4",
+]
+
+var gravity : float = ProjectSettings.get_setting("physics/3d/default_gravity")
+var hp := max_health
+var bullet := spawn_bullet
+## 是否处于死亡状态(死亡后不可移动/射击)。
+var dead := false
+## 射击冷却剩余时间 (s)。
+var fire_left := 0.0
+## 上一帧空格是否按下(用于 JUMP 动作缺失时的回退检测)。
+var jump_key_was_down := false
+## 当前云台 yaw 角度(弧度)。
+var yaw_angle := 0.0
+## 当前枪管 pitch 角度(弧度)。
+var pitch_angle := 0.0
+## 自瞄总开关。
+var auto_aim_enabled := false
+## 当前锁定的目标装甲板。
+var auto_aim_locked_target: Node3D = null
+## 当前帧为最佳候选目标求得的 local pitch 解(弧度)。
+var auto_aim_solution_pitch := 0.0
+## 数值求解使用的模拟步长(秒),与子弹物理步长保持一致。
+var auto_aim_sim_step_dt: float = 1.0 / AUTO_AIM_SIM_FALLBACK_HZ
+## 左键仅用于重新捕获鼠标时,阻止本次按下同时触发射击。
+var consume_left_click_fire_until_release := false
+## 头顶血条锚点。
+var health_bar_anchor: Node3D = null
+## 头顶血条背景。
+var health_bar_back: MeshInstance3D = null
+## 头顶血条红条。
+var health_bar_fill: MeshInstance3D = null
+
+@onready var gimbal_yaw_node: Node3D = $gimbal
+@onready var top_yaw_node: Node3D = $gimbal/top_yaw
+@onready var pitch_pivot: Node3D = $gimbal/top_yaw/pitch_pivot
+@onready var shooter_node: Node3D = $gimbal/top_yaw/pitch_pivot/shooter
+@onready var fpv_cam: Camera3D = $gimbal/top_yaw/pitch_pivot/Camera3D
+
+
+func _ready() -> void:
+ _setup_armor_hitboxes()
+ _setup_health_bar()
+ yaw_angle = gimbal_yaw_node.rotation.y
+ pitch_angle = pitch_pivot.rotation.z
+ var physics_ticks: float = float(ProjectSettings.get_setting("physics/common/physics_ticks_per_second"))
+ if physics_ticks > 0.0:
+ auto_aim_sim_step_dt = 1.0 / physics_ticks
+ _sync_mouse_capture()
+ _update_health_bar()
+ _face_health_bar_to_camera()
+
+
+func _physics_process(delta: float) -> void:
+ # 减少射击冷却时间。
+ fire_left = max(fire_left - delta, 0.0)
+
+ # 死亡状态:完全静止,不响应任何输入。
+ if dead:
+ velocity = Vector3.ZERO
+ move_and_slide()
+ _face_health_bar_to_camera()
+ return
+
+ _tick_movement(delta)
+ _tick_auto_aim(delta)
+ _tick_fire()
+ move_and_slide()
+ # 记录空格状态,用于下一帧检测"刚刚按下"。
+ jump_key_was_down = Input.is_key_pressed(KEY_SPACE)
+ _face_health_bar_to_camera()
+
+
+## 受到子弹伤害,血量归零时进入死亡状态。
+func apply_damage(amount: int, _armor_name: String = "") -> void:
+ if dead:
+ return
+ hp = maxi(0, hp - max(amount, 0))
+ _update_health_bar()
+ if hp <= 0:
+ dead = true
+ velocity = Vector3.ZERO
+
+
+func is_alive() -> bool:
+ return not dead and hp > 0
+
+
+func get_team() -> String:
+ return TEAM
+
+
+func get_armor_target_nodes() -> Array[Node3D]:
+ var result: Array[Node3D] = []
+ for path in ARMOR_NODE_PATHS:
+ var node := get_node_or_null(path)
+ if node is Node3D:
+ result.append(node)
+ return result
+
+
+## 第一人称下按相机水平朝向移动;外部相机下保持世界轴移动。
+func _compute_desired_planar_movement(input_forward: float, input_right: float) -> Vector3:
+ if fpv_cam.current:
+ var basis := fpv_cam.global_basis.orthonormalized()
+ var camera_forward := -basis.z
+ var camera_right := basis.x
+ camera_forward.y = 0.0
+ camera_right.y = 0.0
+ if camera_forward.length() < 0.001:
+ camera_forward = Vector3.FORWARD
+ else:
+ camera_forward = camera_forward.normalized()
+ if camera_right.length() < 0.001:
+ camera_right = Vector3.RIGHT
+ else:
+ camera_right = camera_right.normalized()
+ var desired := camera_forward * input_forward + camera_right * input_right
+ if desired.length() > 1.0:
+ desired = desired.normalized()
+ return desired * move_speed
+
+ var desired := Vector3(-input_forward, 0.0, -input_right)
+ if desired.length() > 1.0:
+ desired = desired.normalized()
+ return desired * move_speed
+
+
+## 处理键盘移动、跳跃和重力。
+## 移动输入由键盘方向键驱动,支持加速度/阻力平滑过渡。
+## 方向映射:key_up → -Z(前),key_right → +X(右)。
+func _tick_movement(delta: float) -> void:
+ # 读取键盘方向输入。
+ var input_forward := Input.get_action_strength("key_up") - Input.get_action_strength("key_down")
+ var input_right := Input.get_action_strength("key_right") - Input.get_action_strength("key_left")
+
+ # 计算期望水平速度:第一人称下跟随视角水平朝向,外部相机下保持世界轴。
+ var desired := _compute_desired_planar_movement(input_forward, input_right)
+
+ # 加速度限制:当前速度向期望速度平滑过渡。
+ var current := Vector3(velocity.x, 0.0, velocity.z)
+ var dv := desired - current
+ var step := move_accel * delta
+ if dv.length() > step and step > 0.0:
+ dv = dv.normalized() * step
+ var next := current + dv
+ # 无输入时施加阻力减速。
+ if desired.length() < 0.01:
+ next = next.move_toward(Vector3.ZERO, move_drag * delta)
+ velocity.x = next.x
+ velocity.z = next.z
+
+ # 跳跃:支持 InputMap 动作或直接空格键回退检测。
+ if _jump_just_pressed() and is_on_floor():
+ velocity.y = jump_velocity
+ elif not is_on_floor():
+ velocity.y -= gravity * delta
+ else:
+ velocity.y = 0.0
+
+
+func _tick_auto_aim(delta: float) -> void:
+ auto_aim_locked_target = null
+
+ if not auto_aim_enabled or not fpv_cam.current:
+ return
+ if auto_aim_target == null or not is_instance_valid(auto_aim_target):
+ return
+ if auto_aim_target.has_method("is_alive") and not bool(auto_aim_target.call("is_alive")):
+ return
+
+ auto_aim_solution_pitch = pitch_angle
+ var target := _pick_auto_aim_target()
+ if target == null:
+ return
+
+ if _track_auto_aim_target(target, auto_aim_solution_pitch, delta):
+ auto_aim_locked_target = target
+
+
+func _pick_auto_aim_target() -> Node3D:
+ if not auto_aim_target.has_method("get_armor_target_nodes"):
+ return null
+
+ var armors: Array = auto_aim_target.call("get_armor_target_nodes")
+ var visible_rect := get_viewport().get_visible_rect()
+ var screen_center := visible_rect.position + visible_rect.size * 0.5
+ var best: Node3D = null
+ var best_d2 := INF
+
+ for item in armors:
+ if not (item is Node3D):
+ continue
+ var armor := item as Node3D
+ if not _is_auto_aim_candidate_visible(armor, visible_rect):
+ continue
+ var solved_pitch: float = _solve_ballistic_pitch_local(armor.global_position)
+ if solved_pitch == INF:
+ continue
+ var screen_pos := fpv_cam.unproject_position(armor.global_position)
+ var d2 := screen_pos.distance_squared_to(screen_center)
+ if d2 < best_d2:
+ best_d2 = d2
+ best = armor
+ auto_aim_solution_pitch = solved_pitch
+
+ return best
+
+
+func _solve_ballistic_pitch_local(target_position: Vector3) -> float:
+ if bullet_speed <= 0.001 or bullet_lifetime <= 0.0 or auto_aim_hit_tolerance <= 0.0:
+ return INF
+
+ var min_pitch: float = -deg_to_rad(max_pitch_degrees)
+ var max_pitch: float = deg_to_rad(max_pitch_degrees)
+ var best_pitch: float = 0.0
+ var best_distance_sq: float = INF
+ var pitch_span: float = max_pitch - min_pitch
+
+ for i in range(AUTO_AIM_COARSE_PITCH_SAMPLES):
+ var t: float = float(i) / float(AUTO_AIM_COARSE_PITCH_SAMPLES - 1)
+ var candidate_pitch: float = lerpf(min_pitch, max_pitch, t)
+ var candidate_distance_sq: float = _evaluate_ballistic_pitch_candidate_distance_sq(
+ target_position,
+ candidate_pitch
+ )
+ if candidate_distance_sq < best_distance_sq:
+ best_distance_sq = candidate_distance_sq
+ best_pitch = candidate_pitch
+
+ if best_distance_sq == INF:
+ return INF
+
+ var coarse_step: float = pitch_span / float(AUTO_AIM_COARSE_PITCH_SAMPLES - 1)
+ var refine_min: float = maxf(min_pitch, best_pitch - coarse_step)
+ var refine_max: float = minf(max_pitch, best_pitch + coarse_step)
+
+ for _round in range(AUTO_AIM_REFINEMENT_ROUNDS):
+ var refine_best_pitch: float = best_pitch
+ var refine_best_distance_sq: float = best_distance_sq
+ for sample_idx in range(AUTO_AIM_REFINEMENT_SAMPLES):
+ var t: float = float(sample_idx) / float(AUTO_AIM_REFINEMENT_SAMPLES - 1)
+ var candidate_pitch: float = lerpf(refine_min, refine_max, t)
+ var candidate_distance_sq: float = _evaluate_ballistic_pitch_candidate_distance_sq(
+ target_position,
+ candidate_pitch
+ )
+ if candidate_distance_sq < refine_best_distance_sq:
+ refine_best_distance_sq = candidate_distance_sq
+ refine_best_pitch = candidate_pitch
+
+ best_pitch = refine_best_pitch
+ best_distance_sq = refine_best_distance_sq
+ var refine_step: float = (refine_max - refine_min) / float(AUTO_AIM_REFINEMENT_SAMPLES - 1)
+ refine_min = maxf(min_pitch, best_pitch - refine_step)
+ refine_max = minf(max_pitch, best_pitch + refine_step)
+
+ var tolerance_sq: float = auto_aim_hit_tolerance * auto_aim_hit_tolerance
+ if best_distance_sq > tolerance_sq:
+ return INF
+ return best_pitch
+
+
+func _evaluate_ballistic_pitch_candidate_distance_sq(target_position: Vector3, local_pitch: float) -> float:
+ var shooter_transform: Transform3D = _compute_candidate_shooter_transform(local_pitch)
+ var forward: Vector3 = _forward_from_basis(shooter_transform.basis)
+ var position: Vector3 = shooter_transform.origin + forward * MUZZLE_OFFSET
+ var velocity: Vector3 = forward * bullet_speed
+ var effective_gravity: float = gravity * bullet_gravity_scale
+ var tolerance_sq: float = auto_aim_hit_tolerance * auto_aim_hit_tolerance
+ var best_distance_sq: float = position.distance_squared_to(target_position)
+ var step_count: int = maxi(1, int(ceil(bullet_lifetime / auto_aim_sim_step_dt)))
+
+ for _step in range(step_count):
+ var previous_position: Vector3 = position
+ velocity.y -= effective_gravity * auto_aim_sim_step_dt
+ position += velocity * auto_aim_sim_step_dt
+ var candidate_distance_sq: float = _distance_sq_point_to_segment(
+ target_position,
+ previous_position,
+ position
+ )
+ if candidate_distance_sq < best_distance_sq:
+ best_distance_sq = candidate_distance_sq
+ if best_distance_sq <= tolerance_sq:
+ return best_distance_sq
+
+ return best_distance_sq
+
+
+func _compute_candidate_shooter_transform(local_pitch: float) -> Transform3D:
+ var pitch_local: Transform3D = pitch_pivot.transform
+ var local_scale: Vector3 = pitch_local.basis.get_scale()
+ pitch_local.basis = Basis(Vector3(0.0, 0.0, 1.0), local_pitch).scaled(local_scale)
+ return top_yaw_node.global_transform * pitch_local * shooter_node.transform
+
+
+func _forward_from_basis(basis: Basis) -> Vector3:
+ var forward: Vector3 = -basis.y
+ if forward.length() < 0.001:
+ return Vector3.FORWARD
+ return forward.normalized()
+
+
+func _distance_sq_point_to_segment(point: Vector3, segment_start: Vector3, segment_end: Vector3) -> float:
+ var segment: Vector3 = segment_end - segment_start
+ var segment_length_sq: float = segment.length_squared()
+ if segment_length_sq < 0.000001:
+ return point.distance_squared_to(segment_start)
+
+ var t: float = clampf((point - segment_start).dot(segment) / segment_length_sq, 0.0, 1.0)
+ var closest_point: Vector3 = segment_start + segment * t
+ return point.distance_squared_to(closest_point)
+
+
+func _is_auto_aim_candidate_visible(armor: Node3D, visible_rect: Rect2) -> bool:
+ if fpv_cam.is_position_behind(armor.global_position):
+ return false
+
+ var screen_pos := fpv_cam.unproject_position(armor.global_position)
+ if not visible_rect.has_point(screen_pos):
+ return false
+
+ var query := PhysicsRayQueryParameters3D.create(fpv_cam.global_position, armor.global_position)
+ query.collide_with_areas = true
+ query.exclude = [get_rid()]
+ var result := get_world_3d().direct_space_state.intersect_ray(query)
+ if result.is_empty():
+ return true
+
+ return _is_auto_aim_hit_target(result.get("collider"), armor)
+
+
+func _is_auto_aim_hit_target(collider: Variant, armor: Node3D) -> bool:
+ if not (collider is Node):
+ return false
+
+ var collider_node := collider as Node
+ if collider_node == auto_aim_target or collider_node == armor:
+ return true
+ if auto_aim_target.is_ancestor_of(collider_node):
+ return true
+ if armor.is_ancestor_of(collider_node):
+ return true
+ if collider_node.is_ancestor_of(armor):
+ return true
+ return false
+
+
+func _track_auto_aim_target(target: Node3D, desired_pitch: float, delta: float) -> bool:
+ if desired_pitch == INF:
+ return false
+
+ var shooter_pos := shooter_node.global_position
+ var to_target := target.global_position - shooter_pos
+ var horizontal := Vector3(to_target.x, 0.0, to_target.z)
+
+ if horizontal.length() >= 0.05:
+ var forward := _shooter_forward()
+ forward.y = 0.0
+ if forward.length() < 0.001:
+ forward = Vector3.FORWARD
+ else:
+ forward = forward.normalized()
+
+ var target_dir := horizontal.normalized()
+ var angle_error := atan2(forward.cross(target_dir).y, forward.dot(target_dir))
+ var yaw_step: float = clampf(angle_error, -auto_aim_yaw_rate * delta, auto_aim_yaw_rate * delta)
+ yaw_angle += yaw_step
+ gimbal_yaw_node.rotation.y = yaw_angle
+
+ pitch_angle = move_toward(pitch_angle, desired_pitch, auto_aim_pitch_rate * delta)
+ pitch_pivot.rotation.z = pitch_angle
+ return true
+
+
+## 射击逻辑:检查冷却和子弹余量,沿 shooter 朝向生成子弹。
+func _tick_fire() -> void:
+ if not _fire_pressed():
+ return
+ if fire_left > 0.0 or bullet <= 0:
+ return
+
+ # 实例化并初始化子弹。
+ var bullet_node := BULLET_SCRIPT.new()
+ bullet_node.set("team", TEAM)
+ bullet_node.set("speed", bullet_speed)
+ bullet_node.set("damage", bullet_damage)
+ bullet_node.set("lifetime", bullet_lifetime)
+ bullet_node.set("gravity_scale", bullet_gravity_scale)
+
+ var forward := _shooter_forward()
+ bullet_node.set("travel_direction", forward)
+ get_tree().current_scene.add_child(bullet_node)
+ bullet_node.global_position = shooter_node.global_position + forward * MUZZLE_OFFSET
+ bullet_node.look_at(bullet_node.global_position + forward, Vector3.UP)
+
+ bullet -= 1
+ fire_left = fire_cooldown
+
+
+## 检测跳跃"刚刚按下":优先使用 InputMap 动作,回退到空格键状态变化。
+func _jump_just_pressed() -> bool:
+ if InputMap.has_action(jump_action):
+ return Input.is_action_just_pressed(jump_action)
+ var down := Input.is_key_pressed(KEY_SPACE)
+ return down and not jump_key_was_down
+
+
+## 检测射击按键:优先 InputMap 动作,回退到 J 键。
+func _fire_pressed() -> bool:
+ if not consume_left_click_fire_until_release and Input.is_mouse_button_pressed(MOUSE_BUTTON_LEFT):
+ return true
+ if InputMap.has_action(fire_action):
+ return Input.is_action_pressed(fire_action)
+ return Input.is_key_pressed(KEY_J)
+
+
+## 计算 shooter 节点的世界空间前方向量。
+## shooter 的局部 -Y 轴指向世界空间前方。
+func _shooter_forward() -> Vector3:
+ var forward := -shooter_node.global_basis.y
+ if forward.length() < 0.001:
+ return Vector3.FORWARD
+ return forward.normalized()
+
+
+## 为四块装甲板子节点挂载受击判定 Area3D。
+func _setup_armor_hitboxes() -> void:
+ for path in ARMOR_NODE_PATHS:
+ var armor_mesh := get_node_or_null(path)
+ if armor_mesh == null:
+ continue
+ var area := ARMOR_SCRIPT.new()
+ area.set("team", TEAM)
+ area.set("armor_name", str(path.get_file()))
+ armor_mesh.add_child(area)
+ area.set("owner_robot_path", area.get_path_to(self))
+
+
+func _setup_health_bar() -> void:
+ health_bar_anchor = get_node_or_null(HEALTH_BAR_ANCHOR_NAME) as Node3D
+ if health_bar_anchor == null:
+ health_bar_anchor = Node3D.new()
+ health_bar_anchor.name = HEALTH_BAR_ANCHOR_NAME
+ health_bar_anchor.position = Vector3(0.0, HEALTH_BAR_HEIGHT, 0.0)
+ add_child(health_bar_anchor)
+
+ health_bar_back = health_bar_anchor.get_node_or_null(HEALTH_BAR_BACK_NAME) as MeshInstance3D
+ if health_bar_back == null:
+ health_bar_back = MeshInstance3D.new()
+ health_bar_back.name = HEALTH_BAR_BACK_NAME
+ var back_mesh := QuadMesh.new()
+ back_mesh.size = HEALTH_BAR_BACK_SIZE
+ health_bar_back.mesh = back_mesh
+ health_bar_back.material_override = _build_health_bar_material(
+ Color(0.08, 0.08, 0.08, 1.0),
+ HEALTH_BAR_BACK_PRIORITY
+ )
+ health_bar_anchor.add_child(health_bar_back)
+
+ health_bar_fill = health_bar_anchor.get_node_or_null(HEALTH_BAR_FILL_NAME) as MeshInstance3D
+ if health_bar_fill == null:
+ health_bar_fill = MeshInstance3D.new()
+ health_bar_fill.name = HEALTH_BAR_FILL_NAME
+ var fill_mesh := QuadMesh.new()
+ fill_mesh.size = HEALTH_BAR_FILL_SIZE
+ health_bar_fill.mesh = fill_mesh
+ health_bar_fill.material_override = _build_health_bar_material(
+ Color(0.92, 0.12, 0.12, 1.0),
+ HEALTH_BAR_FILL_PRIORITY
+ )
+ health_bar_fill.position = Vector3(0.0, 0.0, HEALTH_BAR_FILL_Z_OFFSET)
+ health_bar_anchor.add_child(health_bar_fill)
+
+
+func _build_health_bar_material(color: Color, priority: int) -> StandardMaterial3D:
+ var material := StandardMaterial3D.new()
+ material.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ material.transparency = BaseMaterial3D.TRANSPARENCY_ALPHA
+ material.no_depth_test = true
+ material.depth_draw_mode = BaseMaterial3D.DEPTH_DRAW_DISABLED
+ material.cull_mode = BaseMaterial3D.CULL_DISABLED
+ material.render_priority = priority
+ material.albedo_color = color
+ return material
+
+
+func _update_health_bar() -> void:
+ if health_bar_anchor == null or health_bar_back == null or health_bar_fill == null:
+ return
+
+ var ratio: float = 0.0
+ if max_health > 0:
+ ratio = clampf(float(hp) / float(max_health), 0.0, 1.0)
+
+ health_bar_fill.scale = Vector3(ratio, 1.0, 1.0)
+ health_bar_fill.position = Vector3(
+ -0.5 * HEALTH_BAR_FILL_SIZE.x * (1.0 - ratio),
+ 0.0,
+ HEALTH_BAR_FILL_Z_OFFSET
+ )
+
+
+func _face_health_bar_to_camera() -> void:
+ if health_bar_anchor == null:
+ return
+
+ var camera: Camera3D = get_viewport().get_camera_3d()
+ if camera == null:
+ return
+
+ health_bar_anchor.look_at(camera.global_position, Vector3.UP, true)
+
+
+## 输入处理:检测相机切换动作。
+func _input(event: InputEvent) -> void:
+ if event.is_action_pressed("switch-camera"):
+ _toggle_camera()
+ return
+
+ if event is InputEventKey and event.pressed and not event.echo and event.keycode == KEY_ESCAPE:
+ Input.mouse_mode = Input.MOUSE_MODE_VISIBLE
+ return
+
+ if event is InputEventMouseButton:
+ var mouse_button := event as InputEventMouseButton
+ if mouse_button.button_index == MOUSE_BUTTON_RIGHT and mouse_button.pressed:
+ auto_aim_enabled = not auto_aim_enabled
+ if not auto_aim_enabled:
+ auto_aim_locked_target = null
+ return
+
+ if mouse_button.button_index == MOUSE_BUTTON_LEFT:
+ if not mouse_button.pressed:
+ consume_left_click_fire_until_release = false
+ return
+ if fpv_cam.current and Input.mouse_mode != Input.MOUSE_MODE_CAPTURED:
+ Input.mouse_mode = Input.MOUSE_MODE_CAPTURED
+ consume_left_click_fire_until_release = true
+ return
+
+ if event is InputEventMouseMotion and _can_control_gimbal_with_mouse():
+ var motion := event as InputEventMouseMotion
+ _apply_mouse_aim(motion.relative)
+
+## 在第一人称(shooter 上的相机)和上帝视角(外部相机)之间切换。
+func _toggle_camera() -> void:
+ if not fpv_cam:
+ print("未找到第一人称相机!")
+ return
+
+ if fpv_cam.current:
+ if external_camera:
+ external_camera.make_current()
+ print("已切换至:上帝视角")
+ else:
+ fpv_cam.make_current()
+ print("已切换至:第一人称视角")
+ _sync_mouse_capture()
+
+
+func _can_control_gimbal_with_mouse() -> bool:
+ return fpv_cam.current and Input.mouse_mode == Input.MOUSE_MODE_CAPTURED and auto_aim_locked_target == null
+
+
+func _apply_mouse_aim(relative: Vector2) -> void:
+ yaw_angle -= relative.x * mouse_yaw_sensitivity
+ pitch_angle -= relative.y * mouse_pitch_sensitivity
+ pitch_angle = clampf(
+ pitch_angle,
+ -deg_to_rad(max_pitch_degrees),
+ deg_to_rad(max_pitch_degrees)
+ )
+ gimbal_yaw_node.rotation.y = yaw_angle
+ pitch_pivot.rotation.z = pitch_angle
+
+
+func _sync_mouse_capture() -> void:
+ if fpv_cam.current:
+ Input.mouse_mode = Input.MOUSE_MODE_CAPTURED
+ else:
+ Input.mouse_mode = Input.MOUSE_MODE_VISIBLE
diff --git a/godot-mock/scene/enemy.gd.uid b/godot-mock/scene/enemy.gd.uid
new file mode 100644
index 0000000..a072008
--- /dev/null
+++ b/godot-mock/scene/enemy.gd.uid
@@ -0,0 +1 @@
+uid://biptn8maovcqt
diff --git a/godot-mock/scene/outpost_cube.tscn b/godot-mock/scene/outpost_cube.tscn
new file mode 100644
index 0000000..100d4c6
--- /dev/null
+++ b/godot-mock/scene/outpost_cube.tscn
@@ -0,0 +1,12 @@
+[gd_scene load_steps=2 format=3]
+
+[ext_resource type="Script" path="res://scene/sim_structure_target.gd" id="1_struct"]
+
+[node name="OutpostCube" type="Node3D"]
+script = ExtResource("1_struct")
+structure_kind = "outpost"
+max_health = 1500
+team = "ally"
+cube_size = Vector3(1.5, 1.5, 1.5)
+hitbox_size = Vector3(1.6, 1.6, 1.6)
+display_height = 1.9
diff --git a/godot-mock/scene/sim_armor.gd b/godot-mock/scene/sim_armor.gd
new file mode 100644
index 0000000..6be48f0
--- /dev/null
+++ b/godot-mock/scene/sim_armor.gd
@@ -0,0 +1,71 @@
+extends Area3D
+## 模拟装甲板受击判定区域。
+## 子弹通过碰撞层检测命中后,调用 owner_robot 的 apply_damage 方法造成伤害。
+## 友军子弹不造成伤害(by from_team == team 过滤)。
+
+## 所属队伍 ("ally" / "enemy"),用于友军伤害过滤。
+@export var team := ""
+## 装甲板名称(用于伤害回调标识)。
+@export var armor_name := ""
+## 装甲板所属机器人路径。
+@export var owner_robot_path: NodePath
+## 受击判定盒子尺寸。
+@export var hitbox_size := Vector3(0.48, 0.42, 0.12)
+
+## 装甲板独立碰撞层(第 5 bit)。
+const ARMOR_LAYER := 1 << 5
+
+## 装甲板所属机器人引用。
+var owner_robot: Node = null
+
+
+func _ready() -> void:
+ # 启用区域检测,仅属于 ARMOR 碰撞层,不检测任何对象。
+ monitoring = true
+ monitorable = true
+ collision_layer = ARMOR_LAYER
+ collision_mask = 0
+ add_to_group("sim_armor")
+
+ # 解析所有者机器人引用。
+ if owner_robot_path != NodePath():
+ owner_robot = get_node_or_null(owner_robot_path)
+
+ if owner_robot == null:
+ # 沿父节点链向上查找 CharacterBody3D 作为所有者。
+ owner_robot = _find_owner_robot()
+
+ # 如果场景中没有预置碰撞形状,自动创建一个 BoxShape。
+ if get_child_count() == 0:
+ _create_default_shape()
+
+
+## 子弹命中回调,由 sim_bullet.gd 的 area_entered 信号触发。
+## 过滤友军子弹,然后向 owner_robot 转发伤害。
+## @return: true 表示命中有效,子弹应销毁。
+func on_bullet_hit(damage: int, from_team: String) -> bool:
+ if from_team == team:
+ return false
+ if owner_robot != null and owner_robot.has_method("apply_damage"):
+ owner_robot.call("apply_damage", damage, armor_name)
+ return true
+ return false
+
+
+## 沿父节点链向上查找第一个 CharacterBody3D 节点作为所有者。
+func _find_owner_robot() -> Node:
+ var node: Node = self
+ while node != null:
+ if node is CharacterBody3D:
+ return node
+ node = node.get_parent()
+ return null
+
+
+## 创建默认碰撞形状(BoxShape3D)。
+func _create_default_shape() -> void:
+ var shape := CollisionShape3D.new()
+ var box := BoxShape3D.new()
+ box.size = hitbox_size
+ shape.shape = box
+ add_child(shape)
diff --git a/godot-mock/scene/sim_armor.gd.uid b/godot-mock/scene/sim_armor.gd.uid
new file mode 100644
index 0000000..c08d25e
--- /dev/null
+++ b/godot-mock/scene/sim_armor.gd.uid
@@ -0,0 +1 @@
+uid://hucot3ru2osc
diff --git a/godot-mock/scene/sim_bullet.gd b/godot-mock/scene/sim_bullet.gd
new file mode 100644
index 0000000..a9ccd29
--- /dev/null
+++ b/godot-mock/scene/sim_bullet.gd
@@ -0,0 +1,104 @@
+extends Area3D
+## 模拟子弹,由 robots 射击生成。
+## 沿 travel_direction 匀速运动,受重力影响下坠,碰撞到装甲板后造成伤害并自毁。
+## 超过 lifetime 后自动销毁。
+
+## 所属队伍 ("ally" / "enemy")。
+@export var team := ""
+## 飞行速度 (m/s)。
+@export var speed := 25.0
+## 最大存活时间 (s),超时自动 queue_free。
+@export var lifetime := 2.0
+## 单发伤害值。
+@export var damage := 20
+## 飞行方向(世界空间单位向量)。
+@export var travel_direction := Vector3.FORWARD
+## 碰撞/渲染球体半径。
+@export var radius := 0.1
+## 重力倍率(1.0 = 标准重力加速度)。
+@export var gravity_scale := 1.0
+
+## 子弹独立碰撞层(第 4 bit)。
+const BULLET_LAYER := 1 << 4
+## 装甲板碰撞层(第 5 bit),子弹只检测此层。
+const ARMOR_LAYER := 1 << 5
+
+# 注意:变量名避免与 Area3D 内置 gravity 属性冲突,故使用 gravity_accel。
+## 当前重力加速度值。
+var gravity_accel : float = ProjectSettings.get_setting("physics/3d/default_gravity")
+## 剩余存活时间 (s)。
+var left_life := 0.0
+## 当前飞行速度向量(含重力下坠分量)。
+var current_velocity := Vector3.ZERO
+
+
+func _ready() -> void:
+ # 子弹作为检测体:monitoring 为 true 以接收 area_entered 信号。
+ monitoring = true
+ monitorable = false
+ collision_layer = BULLET_LAYER
+ collision_mask = ARMOR_LAYER
+ left_life = lifetime
+ area_entered.connect(_on_area_entered)
+
+ # 无预制子节点时自动创建碰撞形状和网格。
+ if get_child_count() == 0:
+ _create_default_shape_and_mesh()
+
+ # 归一化飞行方向,保证速度量级正确。
+ travel_direction = travel_direction.normalized()
+ if travel_direction.length() < 0.001:
+ travel_direction = Vector3.FORWARD
+
+ current_velocity = travel_direction * speed
+
+
+func _physics_process(delta: float) -> void:
+ left_life -= delta
+ if left_life <= 0.0:
+ queue_free()
+ return
+
+ # 重力影响:每个物理帧向下加速。
+ current_velocity.y -= gravity_accel * gravity_scale * delta
+
+ global_position += current_velocity * delta
+
+ # 保持子弹朝向与运动方向一致。
+ if current_velocity.length() > 0.1:
+ look_at(global_position + current_velocity.normalized(), Vector3.UP)
+
+
+## 碰撞回调:连接到 area_entered 信号。
+## 进入装甲板碰撞体积时,调用其 on_bullet_hit 方法。
+## 若返回 true(有效伤害),则销毁子弹。
+func _on_area_entered(area: Area3D) -> void:
+ if area == null or not is_instance_valid(area):
+ return
+
+ if area.has_method("on_bullet_hit"):
+ var hit := bool(area.call("on_bullet_hit", damage, team))
+ if hit:
+ queue_free()
+
+
+## 创建默认的 SphereShape 碰撞体和球体网格。
+func _create_default_shape_and_mesh() -> void:
+ var shape := CollisionShape3D.new()
+ var sphere := SphereShape3D.new()
+ sphere.radius = radius
+ shape.shape = sphere
+ add_child(shape)
+
+ var mesh := MeshInstance3D.new()
+ var bullet_mesh := SphereMesh.new()
+ bullet_mesh.radius = radius
+ bullet_mesh.height = radius * 2.0
+ mesh.mesh = bullet_mesh
+
+ var mat := StandardMaterial3D.new()
+ mat.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ mat.albedo_color = Color(1.0, 0.86, 0.25, 1.0)
+ mesh.material_override = mat
+ add_child(mesh)
+
diff --git a/godot-mock/scene/sim_bullet.gd.uid b/godot-mock/scene/sim_bullet.gd.uid
new file mode 100644
index 0000000..e57a08b
--- /dev/null
+++ b/godot-mock/scene/sim_bullet.gd.uid
@@ -0,0 +1 @@
+uid://1txisw4bs7ya
diff --git a/godot-mock/scene/sim_sidecar_client.gd b/godot-mock/scene/sim_sidecar_client.gd
new file mode 100644
index 0000000..6dc54b3
--- /dev/null
+++ b/godot-mock/scene/sim_sidecar_client.gd
@@ -0,0 +1,1669 @@
+extends Node
+## Lua 决策端 TCP sidecar 客户端。
+## 负责与 C++ 模拟器进程(sim_sidecar)建立 TCP 长连接,完成:
+## 1. 上行:周期性发送机器人位姿/资源状态 (sim.input)
+## 2. 下行:接收 blackboard、decision_state、nav_target 及各种遥控指令
+## 3. 超控面板:手动编辑 blackboard 的 HP/Bullet/Stage/Switch 值
+## 4. 自动补给:机器人进入补给区时自动回血/回弹
+## 5. 将 Lua 指令转发到 AI 机器人(底盘模式、云台控制、速度超控等)
+
+## TCP 服务器地址。
+@export var host := "127.0.0.1"
+## TCP 服务器端口。
+@export var port := 34567
+## 上行状态推送频率 (Hz)。
+@export var send_hz := 60.0
+## 是否优先使用矩形补给区判定。
+@export var use_resupply_rect := true
+## 矩形补给区左下角坐标。
+@export var resupply_rect_min := Vector2(0.0, 0.0)
+## 矩形补给区右上角坐标。
+@export var resupply_rect_max := Vector2(4.0, 4.0)
+## 旧补给点回退半径。
+@export var resupply_radius := 0.8
+## 每秒回复血量。
+@export var resupply_health_rate := 100.0
+## 每秒回复子弹数。
+@export var resupply_bullet_rate := 150.0
+## 被动金币发放间隔(秒)。
+@export var passive_gold_interval := 30.0
+## 每次被动发放的金币数量。
+@export var passive_gold_amount := 50
+## 基地初始血量。
+@export var initial_base_health := 5000
+## 前哨站初始血量。
+@export var initial_outpost_health := 1500
+## 比赛初始倒计时(秒,7分钟)。
+@export var initial_remaining_time := 420.0
+## AI 机器人节点路径。
+@export var robot_path: NodePath
+## 导航目标点节点路径。
+@export var target_point_path: NodePath
+## 敌方机器人节点路径。
+@export var enemy_path: NodePath
+
+@onready var robot: CharacterBody3D = get_node(robot_path)
+@onready var target_point: Node3D = get_node(target_point_path)
+
+## 调试面板尺寸。
+const DEBUG_PANEL_SIZE := Vector2(620, 760)
+## 调试面板边距。
+const DEBUG_PANEL_MARGIN := Vector2(16, 16)
+## blackboard 的顶层分节名称。
+const BLACKBOARD_SECTIONS := ["user", "game", "play", "meta", "rule", "result"]
+## 游戏阶段枚举值。
+const STAGE_VALUES := ["UNKNOWN", "NOT_START", "STARTED", "ENDED"]
+## 拨杆开关枚举值。
+const SWITCH_VALUES := ["UNKNOWN", "UP", "MID", "DOWN"]
+
+## TCP 连接对象。
+var tcp := StreamPeerTCP.new()
+## 当前是否已连接。
+var connected := false
+## 接收缓冲区(行协议:\n 分隔的 JSON)。
+var rx_buffer := ""
+## 本地模拟时间 (自连接起累计,秒)。
+var sim_time := 0.0
+## 上行发送累计时间 (秒)。
+var send_accum := 0.0
+
+## 本地缓存的 blackboard 副本。
+var blackboard: Dictionary = {}
+## 最近一次决策状态快照。
+var decision_state: Dictionary = {}
+## blackboard 是否已完成首次接收。
+var blackboard_ready := false
+## blackboard 版本号(去重/乱序过滤)。
+var blackboard_rev := -1
+
+## 超控模式是否激活(手动或自动补给)。
+var override_enabled := false
+## 手动超控面板是否开启。
+var manual_override_enabled := false
+## 自动补给超控是否激活。
+var auto_resupply_override_enabled := false
+## 被动金币同步时使用的临时超控状态。
+var auto_gold_override_enabled := false
+## 超控补丁的序号。
+var override_rev := 0
+## UI 控件防递归更新标志。
+var ui_updating := false
+## 机器人是否在补给区内。
+var in_resupply_zone := false
+## 自动补给是否正在执行。
+var auto_resupply_active := false
+## 到补给点的距离(米)。
+var resupply_distance: Variant = null
+## 血量回复累计缓冲区。
+var auto_resupply_health_buffer := 0.0
+## 子弹回复累计缓冲区。
+var auto_resupply_bullet_buffer := 0.0
+## 距离下一次被动金币发放的剩余时间。
+var passive_gold_left := passive_gold_interval
+## 是否已从 blackboard 初始化机器人资源。
+var robot_resource_initialized := false
+## 本地维护的基地血量(通过 sim.input 同步到 Lua)。
+var sim_base_health := initial_base_health
+## 本地维护的前哨站血量(通过 sim.input 同步到 Lua)。
+var sim_outpost_health := initial_outpost_health
+## 本地维护的比赛剩余时间(秒)。
+var sim_remaining_time := initial_remaining_time
+## 本地维护的可兑换弹药量。
+var sim_exchangeable_ammunition_quantity := 0
+## 本地维护的己方飞镖命中次数。
+var sim_our_dart_nmber_of_hits := 0
+## 本地维护的堡垒占领状态。
+var sim_fortress_occupied := false
+## 本地维护的大能量机关激活状态。
+var sim_big_energy_mechanism_activated := false
+## 本地维护的小能量机关激活状态。
+var sim_small_energy_mechanism_activated := false
+## 比赛是否已进入 STARTED,用于驱动倒计时。
+var competition_started := false
+
+## 调试 UI 控件引用。
+var decision_label: RichTextLabel
+var blackboard_label: RichTextLabel
+var override_toggle: CheckButton
+var edit_box: VBoxContainer
+var hp_spin: SpinBox
+var bullet_spin: SpinBox
+var gold_spin: SpinBox
+var base_hp_spin: SpinBox
+var outpost_hp_spin: SpinBox
+var remaining_time_spin: SpinBox
+var exchangeable_ammo_spin: SpinBox
+var dart_hits_spin: SpinBox
+var fortress_occupied_toggle: CheckButton
+var big_energy_mechanism_toggle: CheckButton
+var small_energy_mechanism_toggle: CheckButton
+var stage_select: OptionButton
+var rswitch_select: OptionButton
+var lswitch_select: OptionButton
+var gold_badge_value_label: Label
+var base_badge_value_label: Label
+var outpost_badge_value_label: Label
+
+
+func _ready() -> void:
+ # 将敌方节点注入 AI 机器人作为跟踪目标。
+ _bind_enemy_target()
+ # 构建调试 UI 面板。
+ _build_debug_ui()
+ _refresh_display()
+
+ # 发起 TCP 连接(异步)。
+ var err := tcp.connect_to_host(host, port)
+ if err != OK:
+ push_error("connect_to_host failed: %s" % err)
+
+
+func _process(_delta: float) -> void:
+ # 轮询 TCP 状态机,处理连接/断开/接收事件。
+ tcp.poll()
+ var status := tcp.get_status()
+
+ # --- 首次建立连接 ---
+ if status == StreamPeerTCP.STATUS_CONNECTED and not connected:
+ connected = true
+ rx_buffer = ""
+ send_accum = 0.0
+ sim_time = 0.0
+ blackboard = {}
+ decision_state = {}
+ blackboard_ready = false
+ blackboard_rev = -1
+ override_enabled = false
+ manual_override_enabled = false
+ auto_resupply_override_enabled = false
+ auto_gold_override_enabled = false
+ override_rev = 0
+ in_resupply_zone = false
+ auto_resupply_active = false
+ resupply_distance = null
+ auto_resupply_health_buffer = 0.0
+ auto_resupply_bullet_buffer = 0.0
+ passive_gold_left = passive_gold_interval
+ robot_resource_initialized = false
+ sim_base_health = initial_base_health
+ sim_outpost_health = initial_outpost_health
+ sim_remaining_time = initial_remaining_time
+ sim_exchangeable_ammunition_quantity = 0
+ sim_our_dart_nmber_of_hits = 0
+ sim_fortress_occupied = false
+ sim_big_energy_mechanism_activated = false
+ sim_small_energy_mechanism_activated = false
+ competition_started = false
+ if override_toggle != null:
+ override_toggle.set_pressed_no_signal(false)
+ if edit_box != null:
+ edit_box.visible = false
+ # 发送 sim.hello 握手消息,声明协议和模式。
+ _send_json({
+ "type": "sim.hello",
+ "protocol": 1,
+ "mode": "lua_sim_v1"
+ })
+ _sync_override_mode(true)
+ _refresh_display()
+ print("sim sidecar connected")
+
+ # --- 连接断开 ---
+ if status != StreamPeerTCP.STATUS_CONNECTED:
+ if connected:
+ connected = false
+ blackboard = {}
+ decision_state = {}
+ blackboard_ready = false
+ override_enabled = false
+ manual_override_enabled = false
+ auto_resupply_override_enabled = false
+ auto_gold_override_enabled = false
+ override_rev = 0
+ in_resupply_zone = false
+ auto_resupply_active = false
+ resupply_distance = null
+ auto_resupply_health_buffer = 0.0
+ auto_resupply_bullet_buffer = 0.0
+ passive_gold_left = passive_gold_interval
+ robot_resource_initialized = false
+ sim_base_health = initial_base_health
+ sim_outpost_health = initial_outpost_health
+ sim_remaining_time = initial_remaining_time
+ sim_exchangeable_ammunition_quantity = 0
+ sim_our_dart_nmber_of_hits = 0
+ sim_fortress_occupied = false
+ sim_big_energy_mechanism_activated = false
+ sim_small_energy_mechanism_activated = false
+ competition_started = false
+ if override_toggle != null:
+ override_toggle.set_pressed_no_signal(false)
+ if edit_box != null:
+ edit_box.visible = false
+ rx_buffer = ""
+ _refresh_display()
+ print("sim sidecar disconnected")
+ return
+
+ # --- 接收消息:行协议(\n 分隔的 JSON 行)---
+ var available := tcp.get_available_bytes()
+ if available <= 0:
+ return
+
+ rx_buffer += tcp.get_utf8_string(available)
+ while true:
+ var pos := rx_buffer.find("\n")
+ if pos < 0:
+ break
+
+ var line := rx_buffer.substr(0, pos).strip_edges()
+ rx_buffer = rx_buffer.substr(pos + 1)
+ if line.is_empty():
+ continue
+
+ var msg = JSON.parse_string(line)
+ if typeof(msg) != TYPE_DICTIONARY:
+ push_warning("invalid message line: %s" % line)
+ continue
+
+ _handle_message(msg)
+
+
+## 物理帧:更新模拟时间、自动补给状态,并按固定频率发送 input 状态。
+func _physics_process(delta: float) -> void:
+ if not connected:
+ return
+
+ sim_time += delta
+ send_accum += delta
+ _tick_competition_clock(delta)
+ _tick_passive_gold(delta)
+ _update_auto_resupply(delta)
+
+ if send_accum >= 1.0 / send_hz:
+ send_accum = 0.0
+ _send_input()
+
+
+func _tick_passive_gold(delta: float) -> void:
+ if not blackboard_ready or passive_gold_interval <= 0.0 or passive_gold_amount <= 0:
+ return
+
+ passive_gold_left -= delta
+ if passive_gold_left > 0.0:
+ return
+
+ var period_count: int = int(floor(-passive_gold_left / passive_gold_interval)) + 1
+ passive_gold_left += passive_gold_interval * float(period_count)
+
+ var user: Dictionary = _get_dict_value(blackboard, "user")
+ var current_gold: int = int(round(_get_numeric_value(user.get("gold", 0), 0.0)))
+ var next_gold: int = current_gold + passive_gold_amount * period_count
+ var patch_user: Dictionary = {"gold": next_gold}
+ var patch: Dictionary = {"user": patch_user}
+ _apply_local_patch(patch)
+ _apply_local_patch({"game": {"gold_coin": next_gold}})
+ _apply_robot_user_patch(patch_user)
+ _refresh_display()
+
+
+func _tick_competition_clock(delta: float) -> void:
+ if not competition_started:
+ return
+ sim_remaining_time = max(sim_remaining_time - delta, 0.0)
+ _apply_local_patch({"game": {"remaining_time": sim_remaining_time}})
+
+
+## 输入处理:检测"开始决策"动作 (sim_start_decision) 或回车键。
+func _unhandled_input(event: InputEvent) -> void:
+ if not connected:
+ return
+
+ var start_pressed := InputMap.has_action("sim_start_decision") and event.is_action_pressed("sim_start_decision")
+ if not start_pressed and event is InputEventKey:
+ var key_event := event as InputEventKey
+ start_pressed = key_event.pressed and key_event.keycode == KEY_ENTER
+
+ if start_pressed:
+ _send_start_decision()
+
+
+## 消息分发:根据 type 字段路由到对应处理器。
+func _handle_message(msg: Dictionary) -> void:
+ var t := str(msg.get("type", ""))
+
+ # blackboard 全量同步(带版本号去重)。
+ if t == "sim.blackboard":
+ var rev := int(msg.get("bb_rev", -1))
+ if rev <= blackboard_rev:
+ return
+
+ var payload = msg.get("blackboard", {})
+ if typeof(payload) != TYPE_DICTIONARY:
+ push_warning("sim.blackboard missing dictionary payload")
+ return
+
+ blackboard_rev = rev
+ blackboard = payload.duplicate(true)
+ blackboard_ready = true
+ _ensure_gold_field_initialized()
+ # 首次收到 blackboard 时初始化机器人资源。
+ _sync_robot_resources_from_blackboard_once()
+ # 将 blackboard 控制字段同步到 UI 控件。
+ _sync_controls_from_blackboard()
+ _refresh_display()
+ return
+
+ # 决策层状态快照。
+ if t == "sim.decision_state":
+ var payload = msg.get("state", {})
+ if typeof(payload) == TYPE_DICTIONARY:
+ decision_state = payload.duplicate(true)
+ _refresh_display()
+ return
+
+ # 导航目标点更新(Lua 下发)。
+ if t == "sim.nav_target":
+ var x := float(msg.get("x", target_point.global_position.z))
+ var y := float(msg.get("y", target_point.global_position.x))
+ var p := target_point.global_position
+ p.x = y
+ p.z = x
+ target_point.global_position = p
+ _refresh_display()
+ return
+
+ # Lua 日志透传。
+ if t == "sim.log":
+ print("[lua/%s] %s" % [str(msg.get("level", "info")), str(msg.get("message", ""))])
+ return
+
+ # 底盘模式切换 (idle / spin)。
+ if t == "sim.chassis_mode":
+ _apply_robot_chassis_mode(str(msg.get("mode", "")))
+ return
+
+ # 云台控制源切换 (manual / scan / auto)。
+ if t == "sim.gimbal_dominator":
+ _apply_robot_gimbal_dominator(str(msg.get("name", "")))
+ return
+
+ # 云台手动朝向设定。
+ if t == "sim.gimbal_direction":
+ _apply_robot_gimbal_direction(float(msg.get("angle", 0.0)))
+ return
+
+ # 底盘速度超控(遥控)。
+ if t == "sim.chassis_vel":
+ _apply_robot_chassis_vel(float(msg.get("x", 0.0)), float(msg.get("y", 0.0)))
+ return
+
+ print("unknown msg: ", msg)
+
+
+## 上行:发送 sim.input,包含机器人位姿和资源状态。
+func _send_input() -> void:
+ var resource := _get_robot_resource_state()
+ var input_payload := {
+ "user": {
+ "x": robot.global_position.z,
+ "y": robot.global_position.x,
+ "yaw": robot.global_rotation.y,
+ "health": int(resource.get("health", 0)),
+ "bullet": int(resource.get("bullet", 0)),
+ "gold": int(resource.get("gold", 0)),
+ },
+ "game": {
+ "base_health": sim_base_health,
+ "outpost_health": sim_outpost_health,
+ "gold_coin": _get_current_gold_value(),
+ "remaining_time": sim_remaining_time,
+ "exchangeable_ammunition_quantity": sim_exchangeable_ammunition_quantity,
+ "our_dart_nmber_of_hits": sim_our_dart_nmber_of_hits,
+ "fortress_occupied": sim_fortress_occupied,
+ "big_energy_mechanism_activated": sim_big_energy_mechanism_activated,
+ "small_energy_mechanism_activated": sim_small_energy_mechanism_activated,
+ },
+ "meta": {
+ "timestamp": sim_time,
+ },
+ }
+
+ _send_json({
+ "type": "sim.input",
+ "input": input_payload,
+ })
+
+
+## 下行:发送 sim.command (start_decision),触发 Lua 决策开始运行。
+func _send_start_decision() -> void:
+ if not connected:
+ return
+
+ _begin_competition_session()
+
+ _send_json({
+ "type": "sim.command",
+ "command": "start_decision",
+ })
+
+
+## 下行:发送 sim.override_mode 切换超控状态。
+func _send_override_mode(enabled: bool) -> void:
+ _send_json({
+ "type": "sim.override_mode",
+ "enabled": enabled,
+ })
+
+
+## 合并手动超控和自动补给超控的状态,仅在变化时发送。
+func _sync_override_mode(force: bool = false) -> void:
+ var enabled := manual_override_enabled or auto_resupply_override_enabled or auto_gold_override_enabled
+ if not force and override_enabled == enabled:
+ return
+
+ override_enabled = enabled
+ _send_override_mode(enabled)
+
+
+## 切换手动超控状态(由 UI 复选框驱动)。
+func _set_manual_override_enabled(enabled: bool) -> void:
+ if manual_override_enabled == enabled:
+ return
+
+ manual_override_enabled = enabled
+ _sync_override_mode()
+
+
+## 切换自动补给超控状态。
+## 关闭时清空累计缓冲区。
+func _set_auto_resupply_override_enabled(enabled: bool) -> void:
+ if auto_resupply_override_enabled == enabled:
+ return
+
+ auto_resupply_override_enabled = enabled
+ if not enabled:
+ auto_resupply_health_buffer = 0.0
+ auto_resupply_bullet_buffer = 0.0
+ _sync_override_mode()
+
+
+## 切换金币同步使用的临时超控状态。
+func _set_auto_gold_override_enabled(enabled: bool) -> void:
+ if auto_gold_override_enabled == enabled:
+ return
+
+ auto_gold_override_enabled = enabled
+ _sync_override_mode()
+
+
+## 发送超控补丁:将 Godot 端对 blackboard 的修改推送到 Lua 端。
+## patch 格式:{"section": {"key": value}, ...}
+func _send_override_patch(patch: Dictionary) -> void:
+ if not connected or not override_enabled:
+ return
+
+ override_rev += 1
+ _send_json({
+ "type": "sim.override_patch",
+ "rev": override_rev,
+ "patch": patch,
+ })
+
+
+## 将补丁合并到本地 blackboard 缓存(乐观更新)。
+## 支持多层嵌套 (section.key = value)。
+func _apply_local_patch(patch: Dictionary) -> void:
+ for key in patch.keys():
+ var value = patch[key]
+ if typeof(value) == TYPE_DICTIONARY:
+ var target = blackboard.get(key, {})
+ if typeof(target) != TYPE_DICTIONARY:
+ target = {}
+ for child_key in value.keys():
+ target[child_key] = value[child_key]
+ blackboard[key] = target
+ else:
+ blackboard[key] = value
+
+
+## 安全获取 blackboard 中的子字典。
+func _get_dict_value(source: Dictionary, key: String) -> Dictionary:
+ var value = source.get(key, {})
+ if typeof(value) == TYPE_DICTIONARY:
+ return value
+ return {}
+
+
+## 安全将 Variant 转换为数值类型。
+func _get_numeric_value(value: Variant, fallback: float = 0.0) -> float:
+ if typeof(value) == TYPE_INT or typeof(value) == TYPE_FLOAT:
+ return float(value)
+ return fallback
+
+
+## 安全将 Variant 转换为布尔值。
+func _get_boolean_value(value: Variant, fallback: bool = false) -> bool:
+ if typeof(value) == TYPE_BOOL:
+ return bool(value)
+ if typeof(value) == TYPE_INT or typeof(value) == TYPE_FLOAT:
+ return float(value) != 0.0
+ return fallback
+
+
+## 获取 blackboard 中指定分节的非负整数值。
+func _get_positive_target_value(section: String, key: String) -> int:
+ var data := _get_dict_value(blackboard, section)
+ var target := int(round(_get_numeric_value(data.get(key, 0), 0.0)))
+ if target < 0:
+ return 0
+ return target
+
+
+## 从 blackboard rule 分节解析己方补给点坐标。
+## @return: Vector2 补给点坐标,无效时返回 null。
+func _get_resupply_point() -> Variant:
+ var rule := _get_dict_value(blackboard, "rule")
+ var resupply_zone := _get_dict_value(rule, "resupply_zone")
+ var ours := _get_dict_value(resupply_zone, "ours")
+ if not ours.has("x") or not ours.has("y"):
+ return null
+
+ var x := _get_numeric_value(ours.get("x", null), NAN)
+ var y := _get_numeric_value(ours.get("y", null), NAN)
+ if is_nan(x) or is_nan(y):
+ return null
+
+ return Vector2(x, y)
+
+
+## 返回当前启用的矩形补给区;无效时返回 null。
+func _get_resupply_rect() -> Variant:
+ if not use_resupply_rect:
+ return null
+
+ var min_x := minf(resupply_rect_min.x, resupply_rect_max.x)
+ var min_y := minf(resupply_rect_min.y, resupply_rect_max.y)
+ var max_x := maxf(resupply_rect_min.x, resupply_rect_max.x)
+ var max_y := maxf(resupply_rect_min.y, resupply_rect_max.y)
+ if max_x <= min_x or max_y <= min_y:
+ return null
+
+ return {
+ "min": Vector2(min_x, min_y),
+ "max": Vector2(max_x, max_y),
+ }
+
+
+## 检查点是否落在矩形补给区内,边界视为在区内。
+func _is_point_in_resupply_rect(point: Vector2, rect: Dictionary) -> bool:
+ var rect_min: Vector2 = rect["min"]
+ var rect_max: Vector2 = rect["max"]
+ return point.x >= rect_min.x and point.x <= rect_max.x and point.y >= rect_min.y and point.y <= rect_max.y
+
+
+## 计算点到矩形补给区的最短距离;区内返回 0。
+func _distance_to_resupply_rect(point: Vector2, rect: Dictionary) -> float:
+ var rect_min: Vector2 = rect["min"]
+ var rect_max: Vector2 = rect["max"]
+ var clamped_x := clampf(point.x, rect_min.x, rect_max.x)
+ var clamped_y := clampf(point.y, rect_min.y, rect_max.y)
+ return point.distance_to(Vector2(clamped_x, clamped_y))
+
+
+## 按速率线性推进资源值(血量或子弹),通过 buffer 累积分整数值变化。
+## @param current: 当前资源值。
+## @param target: 目标值。
+## @param rate: 回复速率 (每秒)。
+## @param delta: 帧时间。
+## @param buffer: 累计浮点缓冲区。
+## @return: {next_value, buffer, changed}。
+func _advance_resupply_resource(
+ current: int, target: int, rate: float, delta: float, buffer: float
+) -> Dictionary:
+ var result := {
+ "next_value": current,
+ "buffer": 0.0,
+ "changed": false,
+ }
+ if target <= 0 or current >= target:
+ return result
+
+ # 无限大速率(类 rate <= 0):直接跳到目标值。
+ if rate <= 0.0:
+ result.next_value = target
+ result.changed = current != target
+ return result
+
+ buffer += rate * delta
+ var gain := int(floor(buffer))
+ if gain <= 0:
+ result.buffer = buffer
+ return result
+
+ buffer -= float(gain)
+ var next_value: int = current + gain
+ if next_value > target:
+ next_value = target
+ if next_value >= target:
+ buffer = 0.0
+
+ result.next_value = next_value
+ result.buffer = buffer
+ result.changed = next_value != current
+ return result
+
+
+## 自动补给主逻辑:检测是否进入补给区,按速率回复血量/子弹。
+## 当机器人进入补给区时激活超控,退出时取消超控。
+func _update_auto_resupply(delta: float) -> void:
+ var previous_in_zone := in_resupply_zone
+ var previous_active := auto_resupply_active
+
+ in_resupply_zone = false
+ auto_resupply_active = false
+ resupply_distance = null
+
+ # blackboard 未就绪时退出。
+ if not blackboard_ready:
+ _set_auto_resupply_override_enabled(false)
+ if previous_in_zone or previous_active:
+ _refresh_display()
+ return
+
+ var robot_position := Vector2(robot.global_position.x, robot.global_position.z)
+ var resupply_rect_value: Variant = _get_resupply_rect()
+ if resupply_rect_value != null:
+ var resupply_rect: Dictionary = resupply_rect_value
+ resupply_distance = _distance_to_resupply_rect(robot_position, resupply_rect)
+ in_resupply_zone = _is_point_in_resupply_rect(robot_position, resupply_rect)
+ else:
+ # 矩形补给区关闭或无效时,回退到旧补给点半径判定。
+ var resupply_point_value: Variant = _get_resupply_point()
+ if resupply_point_value == null:
+ _set_auto_resupply_override_enabled(false)
+ if previous_in_zone or previous_active:
+ _refresh_display()
+ return
+
+ var resupply_point: Vector2 = resupply_point_value
+ var distance := robot_position.distance_to(resupply_point)
+ resupply_distance = distance
+ in_resupply_zone = distance <= resupply_radius
+
+ # 读取期望回复的目标值。
+ var target_health := _get_positive_target_value("rule", "health_ready")
+ var target_bullet := _get_positive_target_value("rule", "bullet_ready")
+ auto_resupply_active = in_resupply_zone and (target_health > 0 or target_bullet > 0)
+ _set_auto_resupply_override_enabled(auto_resupply_active)
+
+ if not auto_resupply_active:
+ if previous_in_zone != in_resupply_zone or previous_active:
+ _refresh_display()
+ return
+
+ var user := _get_dict_value(blackboard, "user")
+ var patch_user := {}
+
+ # 按速率回复血量。
+ if target_health > 0:
+ var current_health := int(round(_get_numeric_value(user.get("health", 0), 0.0)))
+ var health_result := _advance_resupply_resource(
+ current_health,
+ target_health,
+ resupply_health_rate,
+ delta,
+ auto_resupply_health_buffer
+ )
+ auto_resupply_health_buffer = float(health_result.get("buffer", 0.0))
+ if bool(health_result.get("changed", false)):
+ patch_user["health"] = int(health_result.get("next_value", current_health))
+ else:
+ auto_resupply_health_buffer = 0.0
+
+ # 按速率回复子弹。
+ if target_bullet > 0:
+ var current_bullet := int(round(_get_numeric_value(user.get("bullet", 0), 0.0)))
+ var bullet_result := _advance_resupply_resource(
+ current_bullet,
+ target_bullet,
+ resupply_bullet_rate,
+ delta,
+ auto_resupply_bullet_buffer
+ )
+ auto_resupply_bullet_buffer = float(bullet_result.get("buffer", 0.0))
+ if bool(bullet_result.get("changed", false)):
+ patch_user["bullet"] = int(bullet_result.get("next_value", current_bullet))
+ else:
+ auto_resupply_bullet_buffer = 0.0
+
+ if patch_user.is_empty():
+ if previous_in_zone != in_resupply_zone or previous_active != auto_resupply_active:
+ _refresh_display()
+ return
+
+ # 有变化的资源:同时更新本地缓存、机器人状态、并推送超控补丁。
+ var patch := {"user": patch_user}
+ _apply_local_patch(patch)
+ var applied_user_patch: Dictionary = patch_user
+ _apply_robot_user_patch(applied_user_patch)
+ _sync_controls_from_blackboard()
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## 发送 JSON 行到 TCP 对端 (\n 分隔)。
+func _send_json(data: Dictionary) -> void:
+ if tcp.get_status() != StreamPeerTCP.STATUS_CONNECTED:
+ return
+
+ var line := JSON.stringify(data) + "\n"
+ var err := tcp.put_data(line.to_utf8_buffer())
+ if err != OK:
+ push_warning("tcp put_data failed: %s" % err)
+
+
+## 构建调试 UI 面板:CanvasLayer + Panel + 控件布局。
+## 包含:标题、开始决策按钮、超控复选框、编辑面板 (HP/Bullet/Stage/Switch)、
+## Decision State 和 Blackboard 显示。
+func _build_debug_ui() -> void:
+ var canvas := CanvasLayer.new()
+ canvas.name = "LuaSimCanvas"
+ add_child(canvas)
+
+ var panel := Panel.new()
+ panel.name = "LuaSimPanel"
+ panel.position = DEBUG_PANEL_MARGIN
+ panel.size = DEBUG_PANEL_SIZE
+ canvas.add_child(panel)
+
+ var root := VBoxContainer.new()
+ root.name = "Root"
+ root.set_anchors_preset(Control.PRESET_FULL_RECT)
+ root.offset_left = 10
+ root.offset_top = 10
+ root.offset_right = -10
+ root.offset_bottom = -10
+ root.add_theme_constant_override("separation", 8)
+ panel.add_child(root)
+
+ var title := Label.new()
+ title.text = "Lua Sim v1"
+ title.horizontal_alignment = HORIZONTAL_ALIGNMENT_CENTER
+ root.add_child(title)
+
+ var start_btn := Button.new()
+ start_btn.text = "Start Decision"
+ start_btn.pressed.connect(_on_start_pressed)
+ root.add_child(start_btn)
+
+ override_toggle = CheckButton.new()
+ override_toggle.text = "Open Edit Panel (Godot Override)"
+ override_toggle.toggled.connect(_on_override_toggled)
+ root.add_child(override_toggle)
+
+ var gold_badge := PanelContainer.new()
+ gold_badge.name = "GoldBadge"
+ gold_badge.anchor_left = 1.0
+ gold_badge.anchor_right = 1.0
+ gold_badge.anchor_top = 0.0
+ gold_badge.anchor_bottom = 0.0
+ gold_badge.offset_left = -220
+ gold_badge.offset_top = 16
+ gold_badge.offset_right = -16
+ gold_badge.offset_bottom = 78
+ var gold_badge_style := StyleBoxFlat.new()
+ gold_badge_style.bg_color = Color(0.14, 0.11, 0.03, 0.94)
+ gold_badge_style.border_width_left = 2
+ gold_badge_style.border_width_top = 2
+ gold_badge_style.border_width_right = 2
+ gold_badge_style.border_width_bottom = 2
+ gold_badge_style.border_color = Color(1.0, 0.82, 0.16, 1.0)
+ gold_badge_style.corner_radius_top_left = 16
+ gold_badge_style.corner_radius_top_right = 16
+ gold_badge_style.corner_radius_bottom_right = 16
+ gold_badge_style.corner_radius_bottom_left = 16
+ gold_badge.add_theme_stylebox_override("panel", gold_badge_style)
+ canvas.add_child(gold_badge)
+
+ var gold_badge_margin := MarginContainer.new()
+ gold_badge_margin.add_theme_constant_override("margin_left", 14)
+ gold_badge_margin.add_theme_constant_override("margin_top", 10)
+ gold_badge_margin.add_theme_constant_override("margin_right", 14)
+ gold_badge_margin.add_theme_constant_override("margin_bottom", 10)
+ gold_badge.add_child(gold_badge_margin)
+
+ var gold_badge_row := HBoxContainer.new()
+ gold_badge_row.add_theme_constant_override("separation", 12)
+ gold_badge_margin.add_child(gold_badge_row)
+
+ var coin_mark := Panel.new()
+ coin_mark.custom_minimum_size = Vector2(28, 28)
+ var coin_mark_style := StyleBoxFlat.new()
+ coin_mark_style.bg_color = Color(1.0, 0.83, 0.18, 1.0)
+ coin_mark_style.border_width_left = 2
+ coin_mark_style.border_width_top = 2
+ coin_mark_style.border_width_right = 2
+ coin_mark_style.border_width_bottom = 2
+ coin_mark_style.border_color = Color(1.0, 0.94, 0.56, 1.0)
+ coin_mark_style.corner_radius_top_left = 14
+ coin_mark_style.corner_radius_top_right = 14
+ coin_mark_style.corner_radius_bottom_right = 14
+ coin_mark_style.corner_radius_bottom_left = 14
+ coin_mark.add_theme_stylebox_override("panel", coin_mark_style)
+ gold_badge_row.add_child(coin_mark)
+
+ var gold_badge_text := VBoxContainer.new()
+ gold_badge_text.add_theme_constant_override("separation", 0)
+ gold_badge_row.add_child(gold_badge_text)
+
+ var gold_title := Label.new()
+ gold_title.text = "GOLD"
+ gold_title.add_theme_font_size_override("font_size", 12)
+ gold_title.add_theme_color_override("font_color", Color(1.0, 0.86, 0.34, 0.95))
+ gold_badge_text.add_child(gold_title)
+
+ gold_badge_value_label = Label.new()
+ gold_badge_value_label.text = "0"
+ gold_badge_value_label.add_theme_font_size_override("font_size", 24)
+ gold_badge_value_label.add_theme_color_override("font_color", Color(1.0, 0.95, 0.74, 1.0))
+ gold_badge_text.add_child(gold_badge_value_label)
+
+ var base_badge := PanelContainer.new()
+ base_badge.name = "BaseBadge"
+ base_badge.anchor_left = 1.0
+ base_badge.anchor_right = 1.0
+ base_badge.anchor_top = 0.0
+ base_badge.anchor_bottom = 0.0
+ base_badge.offset_left = -424
+ base_badge.offset_top = 16
+ base_badge.offset_right = -240
+ base_badge.offset_bottom = 78
+ var base_badge_style := StyleBoxFlat.new()
+ base_badge_style.bg_color = Color(0.12, 0.08, 0.08, 0.94)
+ base_badge_style.border_width_left = 2
+ base_badge_style.border_width_top = 2
+ base_badge_style.border_width_right = 2
+ base_badge_style.border_width_bottom = 2
+ base_badge_style.border_color = Color(0.97, 0.42, 0.32, 1.0)
+ base_badge_style.corner_radius_top_left = 16
+ base_badge_style.corner_radius_top_right = 16
+ base_badge_style.corner_radius_bottom_right = 16
+ base_badge_style.corner_radius_bottom_left = 16
+ base_badge.add_theme_stylebox_override("panel", base_badge_style)
+ canvas.add_child(base_badge)
+
+ var base_badge_margin := MarginContainer.new()
+ base_badge_margin.add_theme_constant_override("margin_left", 14)
+ base_badge_margin.add_theme_constant_override("margin_top", 10)
+ base_badge_margin.add_theme_constant_override("margin_right", 14)
+ base_badge_margin.add_theme_constant_override("margin_bottom", 10)
+ base_badge.add_child(base_badge_margin)
+
+ var base_badge_row := HBoxContainer.new()
+ base_badge_row.add_theme_constant_override("separation", 12)
+ base_badge_margin.add_child(base_badge_row)
+
+ var base_mark := Panel.new()
+ base_mark.custom_minimum_size = Vector2(28, 28)
+ var base_mark_style := StyleBoxFlat.new()
+ base_mark_style.bg_color = Color(0.93, 0.32, 0.28, 1.0)
+ base_mark_style.border_width_left = 2
+ base_mark_style.border_width_top = 2
+ base_mark_style.border_width_right = 2
+ base_mark_style.border_width_bottom = 2
+ base_mark_style.border_color = Color(1.0, 0.67, 0.60, 1.0)
+ base_mark_style.corner_radius_top_left = 14
+ base_mark_style.corner_radius_top_right = 14
+ base_mark_style.corner_radius_bottom_right = 14
+ base_mark_style.corner_radius_bottom_left = 14
+ base_mark.add_theme_stylebox_override("panel", base_mark_style)
+ base_badge_row.add_child(base_mark)
+
+ var base_badge_text := VBoxContainer.new()
+ base_badge_text.add_theme_constant_override("separation", 0)
+ base_badge_row.add_child(base_badge_text)
+
+ var base_title := Label.new()
+ base_title.text = "BASE"
+ base_title.add_theme_font_size_override("font_size", 12)
+ base_title.add_theme_color_override("font_color", Color(1.0, 0.69, 0.62, 0.95))
+ base_badge_text.add_child(base_title)
+
+ base_badge_value_label = Label.new()
+ base_badge_value_label.text = str(initial_base_health)
+ base_badge_value_label.add_theme_font_size_override("font_size", 24)
+ base_badge_value_label.add_theme_color_override("font_color", Color(1.0, 0.90, 0.88, 1.0))
+ base_badge_text.add_child(base_badge_value_label)
+
+ var outpost_badge := PanelContainer.new()
+ outpost_badge.name = "OutpostBadge"
+ outpost_badge.anchor_left = 1.0
+ outpost_badge.anchor_right = 1.0
+ outpost_badge.anchor_top = 0.0
+ outpost_badge.anchor_bottom = 0.0
+ outpost_badge.offset_left = -628
+ outpost_badge.offset_top = 16
+ outpost_badge.offset_right = -444
+ outpost_badge.offset_bottom = 78
+ var outpost_badge_style := StyleBoxFlat.new()
+ outpost_badge_style.bg_color = Color(0.08, 0.11, 0.14, 0.94)
+ outpost_badge_style.border_width_left = 2
+ outpost_badge_style.border_width_top = 2
+ outpost_badge_style.border_width_right = 2
+ outpost_badge_style.border_width_bottom = 2
+ outpost_badge_style.border_color = Color(0.34, 0.74, 1.0, 1.0)
+ outpost_badge_style.corner_radius_top_left = 16
+ outpost_badge_style.corner_radius_top_right = 16
+ outpost_badge_style.corner_radius_bottom_right = 16
+ outpost_badge_style.corner_radius_bottom_left = 16
+ outpost_badge.add_theme_stylebox_override("panel", outpost_badge_style)
+ canvas.add_child(outpost_badge)
+
+ var outpost_badge_margin := MarginContainer.new()
+ outpost_badge_margin.add_theme_constant_override("margin_left", 14)
+ outpost_badge_margin.add_theme_constant_override("margin_top", 10)
+ outpost_badge_margin.add_theme_constant_override("margin_right", 14)
+ outpost_badge_margin.add_theme_constant_override("margin_bottom", 10)
+ outpost_badge.add_child(outpost_badge_margin)
+
+ var outpost_badge_row := HBoxContainer.new()
+ outpost_badge_row.add_theme_constant_override("separation", 12)
+ outpost_badge_margin.add_child(outpost_badge_row)
+
+ var outpost_mark := Panel.new()
+ outpost_mark.custom_minimum_size = Vector2(28, 28)
+ var outpost_mark_style := StyleBoxFlat.new()
+ outpost_mark_style.bg_color = Color(0.22, 0.67, 0.94, 1.0)
+ outpost_mark_style.border_width_left = 2
+ outpost_mark_style.border_width_top = 2
+ outpost_mark_style.border_width_right = 2
+ outpost_mark_style.border_width_bottom = 2
+ outpost_mark_style.border_color = Color(0.70, 0.90, 1.0, 1.0)
+ outpost_mark_style.corner_radius_top_left = 14
+ outpost_mark_style.corner_radius_top_right = 14
+ outpost_mark_style.corner_radius_bottom_right = 14
+ outpost_mark_style.corner_radius_bottom_left = 14
+ outpost_mark.add_theme_stylebox_override("panel", outpost_mark_style)
+ outpost_badge_row.add_child(outpost_mark)
+
+ var outpost_badge_text := VBoxContainer.new()
+ outpost_badge_text.add_theme_constant_override("separation", 0)
+ outpost_badge_row.add_child(outpost_badge_text)
+
+ var outpost_title := Label.new()
+ outpost_title.text = "OUTPOST"
+ outpost_title.add_theme_font_size_override("font_size", 12)
+ outpost_title.add_theme_color_override("font_color", Color(0.72, 0.92, 1.0, 0.95))
+ outpost_badge_text.add_child(outpost_title)
+
+ outpost_badge_value_label = Label.new()
+ outpost_badge_value_label.text = str(initial_outpost_health)
+ outpost_badge_value_label.add_theme_font_size_override("font_size", 24)
+ outpost_badge_value_label.add_theme_color_override("font_color", Color(0.90, 0.98, 1.0, 1.0))
+ outpost_badge_text.add_child(outpost_badge_value_label)
+
+ edit_box = VBoxContainer.new()
+ edit_box.visible = false
+ edit_box.add_theme_constant_override("separation", 6)
+ root.add_child(edit_box)
+
+ hp_spin = _add_spin_row(edit_box, "HP", 0.0, 800.0, 1.0)
+ hp_spin.value_changed.connect(_on_hp_changed)
+
+ bullet_spin = _add_spin_row(edit_box, "Bullet", 0.0, 500.0, 1.0)
+ bullet_spin.value_changed.connect(_on_bullet_changed)
+
+ gold_spin = _add_spin_row(edit_box, "Gold", 0.0, 99999.0, 1.0)
+ gold_spin.value_changed.connect(_on_gold_changed)
+
+ base_hp_spin = _add_spin_row(edit_box, "Base HP", 0.0, 99999.0, 1.0)
+ base_hp_spin.value_changed.connect(_on_base_hp_changed)
+
+ outpost_hp_spin = _add_spin_row(edit_box, "Outpost HP", 0.0, 99999.0, 1.0)
+ outpost_hp_spin.value_changed.connect(_on_outpost_hp_changed)
+
+ remaining_time_spin = _add_spin_row(edit_box, "Remain Time", 0.0, 420.0, 1.0)
+ remaining_time_spin.value_changed.connect(_on_remaining_time_changed)
+
+ exchangeable_ammo_spin = _add_spin_row(edit_box, "Ammo Bank", 0.0, 99999.0, 1.0)
+ exchangeable_ammo_spin.value_changed.connect(_on_exchangeable_ammo_changed)
+
+ dart_hits_spin = _add_spin_row(edit_box, "Dart Hits", 0.0, 999.0, 1.0)
+ dart_hits_spin.value_changed.connect(_on_dart_hits_changed)
+
+ fortress_occupied_toggle = _add_check_row(edit_box, "Fortress")
+ fortress_occupied_toggle.toggled.connect(_on_fortress_occupied_toggled)
+
+ big_energy_mechanism_toggle = _add_check_row(edit_box, "Big Energy")
+ big_energy_mechanism_toggle.toggled.connect(_on_big_energy_mechanism_toggled)
+
+ small_energy_mechanism_toggle = _add_check_row(edit_box, "Small Energy")
+ small_energy_mechanism_toggle.toggled.connect(_on_small_energy_mechanism_toggled)
+
+ stage_select = _add_option_row(edit_box, "Stage", STAGE_VALUES)
+ stage_select.item_selected.connect(_on_stage_selected)
+
+ rswitch_select = _add_option_row(edit_box, "R Switch", SWITCH_VALUES)
+ rswitch_select.item_selected.connect(_on_rswitch_selected)
+
+ lswitch_select = _add_option_row(edit_box, "L Switch", SWITCH_VALUES)
+ lswitch_select.item_selected.connect(_on_lswitch_selected)
+
+ var decision_title := Label.new()
+ decision_title.text = "Decision State"
+ root.add_child(decision_title)
+
+ decision_label = RichTextLabel.new()
+ decision_label.fit_content = false
+ decision_label.custom_minimum_size = Vector2(0, 120)
+ decision_label.scroll_active = true
+ decision_label.selection_enabled = true
+ root.add_child(decision_label)
+
+ var bb_title := Label.new()
+ bb_title.text = "Blackboard"
+ root.add_child(bb_title)
+
+ blackboard_label = RichTextLabel.new()
+ blackboard_label.fit_content = false
+ blackboard_label.custom_minimum_size = Vector2(0, 360)
+ blackboard_label.scroll_active = true
+ blackboard_label.selection_enabled = true
+ root.add_child(blackboard_label)
+
+
+## 创建一行 SpinBox 控件(标签 + 数值输入),返回 SpinBox 引用。
+func _add_spin_row(parent: VBoxContainer, label_text: String, min_v: float, max_v: float, step_v: float) -> SpinBox:
+ var row := HBoxContainer.new()
+ parent.add_child(row)
+
+ var label := Label.new()
+ label.text = label_text
+ label.custom_minimum_size = Vector2(90, 0)
+ row.add_child(label)
+
+ var spin := SpinBox.new()
+ spin.min_value = min_v
+ spin.max_value = max_v
+ spin.step = step_v
+ spin.size_flags_horizontal = Control.SIZE_EXPAND_FILL
+ row.add_child(spin)
+ return spin
+
+
+## 创建一行 OptionButton 控件(标签 + 下拉选择),返回 OptionButton 引用。
+func _add_option_row(parent: VBoxContainer, label_text: String, values: Array) -> OptionButton:
+ var row := HBoxContainer.new()
+ parent.add_child(row)
+
+ var label := Label.new()
+ label.text = label_text
+ label.custom_minimum_size = Vector2(90, 0)
+ row.add_child(label)
+
+ var option := OptionButton.new()
+ option.size_flags_horizontal = Control.SIZE_EXPAND_FILL
+ for entry in values:
+ option.add_item(str(entry))
+ row.add_child(option)
+ return option
+
+
+## 创建一行布尔开关控件(标签 + 勾选框),返回 CheckButton 引用。
+func _add_check_row(parent: VBoxContainer, label_text: String) -> CheckButton:
+ var row := HBoxContainer.new()
+ parent.add_child(row)
+
+ var label := Label.new()
+ label.text = label_text
+ label.custom_minimum_size = Vector2(90, 0)
+ row.add_child(label)
+
+ var toggle := CheckButton.new()
+ toggle.size_flags_horizontal = Control.SIZE_EXPAND_FILL
+ row.add_child(toggle)
+ return toggle
+
+
+## UI 回调:开始决策按钮。
+func _on_start_pressed() -> void:
+ _send_start_decision()
+
+
+## UI 回调:超控复选框切换,显示/隐藏编辑面板并更新超控状态。
+func _on_override_toggled(enabled: bool) -> void:
+ if edit_box != null:
+ edit_box.visible = enabled
+ _set_manual_override_enabled(enabled)
+ _refresh_display()
+
+
+## UI 回调:HP 数值改变 → 推送超控补丁。
+func _on_hp_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ var patch := {"user": {"health": int(round(value))}}
+ _apply_local_patch(patch)
+ var user_patch: Dictionary = patch["user"]
+ _apply_robot_user_patch(user_patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:子弹数值改变 → 推送超控补丁。
+func _on_bullet_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ var patch := {"user": {"bullet": int(round(value))}}
+ _apply_local_patch(patch)
+ var user_patch: Dictionary = patch["user"]
+ _apply_robot_user_patch(user_patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:金币数值改变 → 推送超控补丁。
+func _on_gold_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ var patch: Dictionary = {"user": {"gold": int(round(value))}}
+ _apply_local_patch(patch)
+ _apply_local_patch({"game": {"gold_coin": int(round(value))}})
+ var user_patch: Dictionary = patch["user"]
+ _apply_robot_user_patch(user_patch)
+ _refresh_display()
+
+
+## UI 回调:基地血量改变 → 更新本地比赛状态,后续通过 sim.input 同步。
+func _on_base_hp_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ sim_base_health = maxi(0, int(round(value)))
+ _apply_local_patch({"game": {"base_health": sim_base_health}})
+ _refresh_display()
+
+
+## UI 回调:前哨站血量改变 → 更新本地比赛状态,后续通过 sim.input 同步。
+func _on_outpost_hp_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ sim_outpost_health = maxi(0, int(round(value)))
+ _apply_local_patch({"game": {"outpost_health": sim_outpost_health}})
+ _refresh_display()
+
+
+## UI 回调:比赛剩余时间改变 → 更新本地比赛状态,后续通过 sim.input 同步。
+func _on_remaining_time_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ sim_remaining_time = clampf(value, 0.0, initial_remaining_time)
+ _apply_local_patch({"game": {"remaining_time": sim_remaining_time}})
+ _refresh_display()
+
+
+## UI 回调:可兑换弹药量改变 → 更新本地比赛状态,后续通过 sim.input 同步。
+func _on_exchangeable_ammo_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ sim_exchangeable_ammunition_quantity = maxi(0, int(round(value)))
+ _apply_local_patch({
+ "game": {
+ "exchangeable_ammunition_quantity": sim_exchangeable_ammunition_quantity
+ }
+ })
+ _refresh_display()
+
+
+## UI 回调:己方飞镖命中次数改变。
+func _on_dart_hits_changed(value: float) -> void:
+ if ui_updating:
+ return
+
+ sim_our_dart_nmber_of_hits = maxi(0, int(round(value)))
+ var patch := {
+ "game": {
+ "our_dart_nmber_of_hits": sim_our_dart_nmber_of_hits,
+ }
+ }
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:堡垒占领状态改变。
+func _on_fortress_occupied_toggled(enabled: bool) -> void:
+ if ui_updating:
+ return
+
+ sim_fortress_occupied = enabled
+ var patch := {
+ "game": {
+ "fortress_occupied": sim_fortress_occupied,
+ }
+ }
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:大能量机关激活状态改变。
+func _on_big_energy_mechanism_toggled(enabled: bool) -> void:
+ if ui_updating:
+ return
+
+ sim_big_energy_mechanism_activated = enabled
+ var patch := {
+ "game": {
+ "big_energy_mechanism_activated": sim_big_energy_mechanism_activated,
+ }
+ }
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:小能量机关激活状态改变。
+func _on_small_energy_mechanism_toggled(enabled: bool) -> void:
+ if ui_updating:
+ return
+
+ sim_small_energy_mechanism_activated = enabled
+ var patch := {
+ "game": {
+ "small_energy_mechanism_activated": sim_small_energy_mechanism_activated,
+ }
+ }
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:Stage 选择改变 → 推送 game.stage。
+func _on_stage_selected(index: int) -> void:
+ if ui_updating:
+ return
+
+ var stage : String = STAGE_VALUES[clamp(index, 0, STAGE_VALUES.size() - 1)]
+ if stage == "STARTED":
+ _begin_competition_session()
+ else:
+ competition_started = false
+ var patch := {"game": {"stage": stage, "remaining_time": sim_remaining_time}}
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:R Switch 选择改变 → 推送 play.rswitch。
+func _on_rswitch_selected(index: int) -> void:
+ if ui_updating:
+ return
+
+ var value : String = SWITCH_VALUES[clamp(index, 0, SWITCH_VALUES.size() - 1)]
+ var patch := {"play": {"rswitch": value}}
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## UI 回调:L Switch 选择改变 → 推送 play.lswitch。
+func _on_lswitch_selected(index: int) -> void:
+ if ui_updating:
+ return
+
+ var value : String = SWITCH_VALUES[clamp(index, 0, SWITCH_VALUES.size() - 1)]
+ var patch := {"play": {"lswitch": value}}
+ _apply_local_patch(patch)
+ _send_override_patch(patch)
+ _refresh_display()
+
+
+## 从 blackboard 同步 UI 控件显示值(仅更新显示,不触发回调)。
+func _sync_controls_from_blackboard() -> void:
+ if hp_spin == null:
+ return
+
+ ui_updating = true
+ var user: Dictionary = blackboard.get("user", {})
+ var game: Dictionary = blackboard.get("game", {})
+ var play: Dictionary = blackboard.get("play", {})
+
+ hp_spin.value = float(user.get("health", hp_spin.value))
+ bullet_spin.value = float(user.get("bullet", bullet_spin.value))
+ gold_spin.value = float(user.get("gold", gold_spin.value))
+ sim_base_health = int(round(_get_numeric_value(game.get("base_health", sim_base_health), 0.0)))
+ sim_outpost_health = int(round(_get_numeric_value(game.get("outpost_health", sim_outpost_health), 0.0)))
+ sim_remaining_time = _get_numeric_value(game.get("remaining_time", sim_remaining_time), 0.0)
+ sim_exchangeable_ammunition_quantity = int(round(
+ _get_numeric_value(
+ game.get("exchangeable_ammunition_quantity", sim_exchangeable_ammunition_quantity),
+ 0.0
+ )
+ ))
+ sim_our_dart_nmber_of_hits = int(round(
+ _get_numeric_value(game.get("our_dart_nmber_of_hits", sim_our_dart_nmber_of_hits), 0.0)
+ ))
+ sim_fortress_occupied = _get_boolean_value(
+ game.get("fortress_occupied", sim_fortress_occupied),
+ sim_fortress_occupied
+ )
+ sim_big_energy_mechanism_activated = _get_boolean_value(
+ game.get("big_energy_mechanism_activated", sim_big_energy_mechanism_activated),
+ sim_big_energy_mechanism_activated
+ )
+ sim_small_energy_mechanism_activated = _get_boolean_value(
+ game.get("small_energy_mechanism_activated", sim_small_energy_mechanism_activated),
+ sim_small_energy_mechanism_activated
+ )
+ if base_hp_spin != null:
+ base_hp_spin.value = float(sim_base_health)
+ if outpost_hp_spin != null:
+ outpost_hp_spin.value = float(sim_outpost_health)
+ if remaining_time_spin != null:
+ remaining_time_spin.value = sim_remaining_time
+ if exchangeable_ammo_spin != null:
+ exchangeable_ammo_spin.value = float(sim_exchangeable_ammunition_quantity)
+ if dart_hits_spin != null:
+ dart_hits_spin.value = float(sim_our_dart_nmber_of_hits)
+ if fortress_occupied_toggle != null:
+ fortress_occupied_toggle.set_pressed_no_signal(sim_fortress_occupied)
+ if big_energy_mechanism_toggle != null:
+ big_energy_mechanism_toggle.set_pressed_no_signal(sim_big_energy_mechanism_activated)
+ if small_energy_mechanism_toggle != null:
+ small_energy_mechanism_toggle.set_pressed_no_signal(
+ sim_small_energy_mechanism_activated
+ )
+
+ _select_option_value(stage_select, STAGE_VALUES, str(game.get("stage", "UNKNOWN")))
+ _select_option_value(rswitch_select, SWITCH_VALUES, str(play.get("rswitch", "UNKNOWN")))
+ _select_option_value(lswitch_select, SWITCH_VALUES, str(play.get("lswitch", "UNKNOWN")))
+ competition_started = str(game.get("stage", "UNKNOWN")) == "STARTED"
+ ui_updating = false
+
+
+func _begin_competition_session() -> void:
+ sim_remaining_time = initial_remaining_time
+ competition_started = true
+ _apply_local_patch({
+ "game": {
+ "stage": "STARTED",
+ "remaining_time": sim_remaining_time,
+ }
+ })
+
+
+## 在 OptionButton 中选中匹配的枚举值。
+func _select_option_value(button: OptionButton, values: Array, value: String) -> void:
+ var target := values.find(value)
+ if target < 0:
+ target = 0
+ button.select(target)
+
+
+## 刷新调试面板显示(决策状态 + blackboard)。
+func _refresh_display() -> void:
+ if decision_label != null:
+ decision_label.text = _format_decision_text()
+ if blackboard_label != null:
+ blackboard_label.text = _format_blackboard_text()
+ _refresh_gold_badge()
+ _refresh_competition_badges()
+
+
+func _refresh_gold_badge() -> void:
+ if gold_badge_value_label == null:
+ return
+
+ gold_badge_value_label.text = str(_get_current_gold_value())
+
+
+func _get_current_gold_value() -> int:
+ var user: Dictionary = _get_dict_value(blackboard, "user")
+ if user.has("gold"):
+ return int(round(_get_numeric_value(user.get("gold", 0), 0.0)))
+
+ var resource: Dictionary = _get_robot_resource_state()
+ return int(round(_get_numeric_value(resource.get("gold", 0), 0.0)))
+
+
+func _refresh_competition_badges() -> void:
+ if base_badge_value_label != null:
+ base_badge_value_label.text = str(_get_current_base_health_value())
+ if outpost_badge_value_label != null:
+ outpost_badge_value_label.text = str(_get_current_outpost_health_value())
+
+
+func _get_current_base_health_value() -> int:
+ var game: Dictionary = _get_dict_value(blackboard, "game")
+ if game.has("base_health"):
+ return int(round(_get_numeric_value(game.get("base_health", sim_base_health), 0.0)))
+ return sim_base_health
+
+
+func _get_current_outpost_health_value() -> int:
+ var game: Dictionary = _get_dict_value(blackboard, "game")
+ if game.has("outpost_health"):
+ return int(round(_get_numeric_value(game.get("outpost_health", sim_outpost_health), 0.0)))
+ return sim_outpost_health
+
+
+func get_structure_health(kind: String) -> int:
+ if kind == "base":
+ return sim_base_health
+ if kind == "outpost":
+ return sim_outpost_health
+ return 0
+
+
+func sync_structure_health(kind: String, value: int) -> void:
+ var next_value := maxi(0, value)
+ match kind:
+ "base":
+ sim_base_health = next_value
+ _apply_local_patch({"game": {"base_health": sim_base_health}})
+ if base_hp_spin != null:
+ base_hp_spin.value = float(sim_base_health)
+ "outpost":
+ sim_outpost_health = next_value
+ _apply_local_patch({"game": {"outpost_health": sim_outpost_health}})
+ if outpost_hp_spin != null:
+ outpost_hp_spin.value = float(sim_outpost_health)
+ _:
+ return
+ _refresh_display()
+
+
+func apply_structure_damage(kind: String, damage: int) -> bool:
+ if damage <= 0:
+ return false
+
+ if kind == "outpost":
+ sync_structure_health("outpost", sim_outpost_health - damage)
+ return true
+
+ if kind == "base":
+ if sim_outpost_health > 0:
+ return false
+ sync_structure_health("base", sim_base_health - damage)
+ return true
+
+ return false
+
+
+## 格式化决策状态文本(JSON 美观输出)。
+func _format_decision_text() -> String:
+ var view := {
+ "connected": connected,
+ "blackboard_ready": blackboard_ready,
+ "bb_rev": blackboard_rev,
+ "override_enabled": override_enabled,
+ "manual_override_enabled": manual_override_enabled,
+ "auto_resupply_override_enabled": auto_resupply_override_enabled,
+ "override_rev": override_rev,
+ "in_resupply_zone": in_resupply_zone,
+ "auto_resupply_active": auto_resupply_active,
+ "resupply_distance": resupply_distance,
+ "sim_time": _round_float(sim_time),
+ "target": {
+ "x": _round_float(target_point.global_position.x),
+ "y": _round_float(target_point.global_position.z),
+ },
+ "decision": decision_state,
+ }
+ return JSON.stringify(_prepare_display_value(view), " ", true)
+
+
+## 格式化 blackboard 文本(按分节标注)。
+func _format_blackboard_text() -> String:
+ var blocks: Array[String] = []
+ for section in BLACKBOARD_SECTIONS:
+ var value = blackboard.get(section, {})
+ blocks.append("[%s]\n%s" % [section, _stringify_pretty(value)])
+ return "\n\n".join(blocks)
+
+
+## 将 Variant 格式化为美观字符串(字典/数组用 JSON)。
+func _stringify_pretty(value: Variant) -> String:
+ var prepared = _prepare_display_value(value)
+ if typeof(prepared) == TYPE_DICTIONARY or typeof(prepared) == TYPE_ARRAY:
+ return JSON.stringify(prepared, " ", true)
+ return str(prepared)
+
+
+## 递归准备显示值:浮点四舍五入、字典按键排序、限深防展平。
+func _prepare_display_value(value: Variant, depth: int = 0) -> Variant:
+ if depth >= 6:
+ return "..."
+
+ match typeof(value):
+ TYPE_FLOAT:
+ return _round_float(value)
+ TYPE_DICTIONARY:
+ var source: Dictionary = value
+ var result := {}
+ var keys := source.keys()
+ keys.sort_custom(func(a, b): return str(a) < str(b))
+ for key in keys:
+ result[key] = _prepare_display_value(source[key], depth + 1)
+ return result
+ TYPE_ARRAY:
+ var source: Array = value
+ var result: Array = []
+ for entry in source:
+ result.append(_prepare_display_value(entry, depth + 1))
+ return result
+ _:
+ return value
+
+
+## 浮点数四舍五入到三位小数。
+func _round_float(value: float) -> float:
+ return round(value * 1000.0) / 1000.0
+
+
+## 将敌方机器人节点绑定为 AI 机器人的跟踪目标。
+func _bind_enemy_target() -> void:
+ var enemy_node := _resolve_enemy_node()
+ if enemy_node != null and robot.has_method("set_enemy_target"):
+ robot.call("set_enemy_target", enemy_node)
+
+
+## 解析敌方节点:优先使用 enemy_path,回退到 ../Enemy。
+func _resolve_enemy_node() -> Node3D:
+ if enemy_path != NodePath():
+ var explicit_node := get_node_or_null(enemy_path)
+ if explicit_node is Node3D:
+ return explicit_node
+ var fallback := get_node_or_null("../Enemy")
+ if fallback is Node3D:
+ return fallback
+ return null
+
+
+## 将 Lua 底盘模式指令转发到 AI 机器人。
+func _apply_robot_chassis_mode(mode: String) -> void:
+ if robot.has_method("set_chassis_mode"):
+ robot.call("set_chassis_mode", mode)
+
+
+## 将 Lua 云台控制源指令转发到 AI 机器人。
+func _apply_robot_gimbal_dominator(dominator_name: String) -> void:
+ if robot.has_method("set_gimbal_dominator"):
+ robot.call("set_gimbal_dominator", dominator_name)
+
+
+## 将 Lua 云台方向指令转发到 AI 机器人。
+func _apply_robot_gimbal_direction(angle: float) -> void:
+ if robot.has_method("set_gimbal_direction"):
+ robot.call("set_gimbal_direction", angle)
+
+
+## 将 Lua 底盘速度超控指令转发到 AI 机器人。
+func _apply_robot_chassis_vel(x: float, y: float) -> void:
+ if robot.has_method("set_external_chassis_velocity"):
+ robot.call("set_external_chassis_velocity", x, y)
+
+
+## 从 AI 机器人获取当前模拟资源状态(血量、子弹、金币、死亡状态)。
+func _get_robot_resource_state() -> Dictionary:
+ if robot.has_method("get_sim_resource_state"):
+ var resource = robot.call("get_sim_resource_state")
+ if typeof(resource) == TYPE_DICTIONARY:
+ return resource
+ return {
+ "health": 0,
+ "bullet": 0,
+ "gold": 0,
+ }
+
+
+func _ensure_gold_field_initialized() -> void:
+ var user: Dictionary = _get_dict_value(blackboard, "user")
+ if user.has("gold"):
+ return
+
+ var resource: Dictionary = _get_robot_resource_state()
+ var initial_gold: int = int(round(_get_numeric_value(resource.get("gold", 0), 0.0)))
+ var patch_user: Dictionary = {"gold": initial_gold}
+ var patch: Dictionary = {"user": patch_user}
+ _apply_local_patch(patch)
+ _apply_robot_user_patch(patch_user)
+
+
+## 首次收到 blackboard 时,用其中的血量/子弹/金币值初始化机器人状态。
+func _sync_robot_resources_from_blackboard_once() -> void:
+ if robot_resource_initialized:
+ return
+
+ var user: Dictionary = _get_dict_value(blackboard, "user")
+ if not user.has("health") and not user.has("bullet") and not user.has("gold"):
+ return
+
+ if robot.has_method("sync_resources_from_blackboard"):
+ robot.call(
+ "sync_resources_from_blackboard",
+ user.get("health", null),
+ user.get("bullet", null),
+ user.get("gold", null)
+ )
+ robot_resource_initialized = true
+
+
+## 将超控补丁中的血量/子弹/金币值应用到 AI 机器人。
+func _apply_robot_user_patch(user_patch: Dictionary) -> void:
+ if robot.has_method("sync_resources_from_blackboard"):
+ robot.call(
+ "sync_resources_from_blackboard",
+ user_patch.get("health", null),
+ user_patch.get("bullet", null),
+ user_patch.get("gold", null)
+ )
+
diff --git a/godot-mock/scene/sim_sidecar_client.gd.uid b/godot-mock/scene/sim_sidecar_client.gd.uid
new file mode 100644
index 0000000..9b9ad6b
--- /dev/null
+++ b/godot-mock/scene/sim_sidecar_client.gd.uid
@@ -0,0 +1 @@
+uid://dkbfp0i2ppdrp
diff --git a/godot-mock/scene/sim_structure_hitbox.gd b/godot-mock/scene/sim_structure_hitbox.gd
new file mode 100644
index 0000000..deb0a9d
--- /dev/null
+++ b/godot-mock/scene/sim_structure_hitbox.gd
@@ -0,0 +1,44 @@
+extends Area3D
+## 比赛建筑受击区域。
+## 仿照机器人装甲板方案,子弹命中后将伤害转发给所属结构目标。
+
+@export var team := ""
+@export var owner_target_path: NodePath
+@export var hitbox_size := Vector3(1.5, 1.5, 1.5)
+
+const ARMOR_LAYER := 1 << 5
+
+var owner_target: Node = null
+
+
+func _ready() -> void:
+ monitoring = true
+ monitorable = true
+ collision_layer = ARMOR_LAYER
+ collision_mask = 0
+
+ if owner_target_path != NodePath():
+ owner_target = get_node_or_null(owner_target_path)
+
+ if owner_target == null:
+ owner_target = get_parent()
+
+ if get_child_count() == 0:
+ _create_default_shape()
+
+
+func on_bullet_hit(damage: int, from_team: String) -> bool:
+ if from_team == team:
+ return false
+
+ if owner_target != null and owner_target.has_method("apply_structure_damage"):
+ return bool(owner_target.call("apply_structure_damage", 100))
+ return false
+
+
+func _create_default_shape() -> void:
+ var shape := CollisionShape3D.new()
+ var box := BoxShape3D.new()
+ box.size = hitbox_size
+ shape.shape = box
+ add_child(shape)
diff --git a/godot-mock/scene/sim_structure_hitbox.gd.uid b/godot-mock/scene/sim_structure_hitbox.gd.uid
new file mode 100644
index 0000000..7db9865
--- /dev/null
+++ b/godot-mock/scene/sim_structure_hitbox.gd.uid
@@ -0,0 +1 @@
+uid://cmas0ib4rvy0n
diff --git a/godot-mock/scene/sim_structure_target.gd b/godot-mock/scene/sim_structure_target.gd
new file mode 100644
index 0000000..9cc0cf3
--- /dev/null
+++ b/godot-mock/scene/sim_structure_target.gd
@@ -0,0 +1,190 @@
+extends Node3D
+## 通用比赛建筑目标:基地 / 前哨站。
+## 半透明立方体,可被 enemy 子弹命中;头顶显示血条和数值。
+
+@export_enum("outpost", "base") var structure_kind := "outpost"
+@export var max_health := 1500
+@export var team := "ally"
+@export var cube_size := Vector3(1.4, 1.4, 1.4)
+@export var hitbox_size := Vector3(1.5, 1.5, 1.5)
+@export var display_height := 0.5
+
+const ARMOR_LAYER := 1 << 5
+const HEALTH_BAR_BACK_SIZE := Vector2(1.5, 0.16)
+const HEALTH_BAR_FILL_SIZE := Vector2(1.4, 0.12)
+const HEALTH_BAR_BACK_PRIORITY := 10
+const HEALTH_BAR_FILL_PRIORITY := 11
+const HEALTH_BAR_FILL_Z_OFFSET := -0.02
+const HITBOX_SCRIPT := preload("res://scene/sim_structure_hitbox.gd")
+
+var body_mesh: MeshInstance3D = null
+var hitbox_area: Area3D = null
+var health_bar_anchor: Node3D = null
+var health_bar_back: MeshInstance3D = null
+var health_bar_fill: MeshInstance3D = null
+var hp_label: Label3D = null
+
+
+func _ready() -> void:
+ _setup_body_mesh()
+ _setup_hitbox()
+ _setup_health_display()
+ _refresh_health_display()
+
+
+func _process(_delta: float) -> void:
+ _face_health_display_to_camera()
+ _refresh_health_display()
+
+
+func apply_structure_damage(damage: int) -> bool:
+ var client := _get_sim_sidecar_client()
+ if client == null:
+ return false
+ if not client.has_method("apply_structure_damage"):
+ return false
+
+ return bool(client.call("apply_structure_damage", structure_kind, damage))
+
+
+func get_team() -> String:
+ return team
+
+
+func get_armor_target_nodes() -> Array[Node3D]:
+ if hitbox_area != null:
+ return [hitbox_area]
+ return [self]
+
+
+func _get_sim_sidecar_client() -> Node:
+ var scene_root := get_tree().current_scene
+ if scene_root == null:
+ return null
+ return scene_root.get_node_or_null("SimSidecarClient")
+
+
+func _current_health() -> int:
+ var client := _get_sim_sidecar_client()
+ if client != null and client.has_method("get_structure_health"):
+ return int(client.call("get_structure_health", structure_kind))
+ return max_health
+
+
+func _setup_body_mesh() -> void:
+ body_mesh = MeshInstance3D.new()
+ body_mesh.name = "Body"
+ var mesh := BoxMesh.new()
+ mesh.size = cube_size
+ body_mesh.mesh = mesh
+ body_mesh.material_override = _build_body_material()
+ add_child(body_mesh)
+
+
+func _build_body_material() -> StandardMaterial3D:
+ var material := StandardMaterial3D.new()
+ material.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ material.transparency = BaseMaterial3D.TRANSPARENCY_ALPHA
+ material.cull_mode = BaseMaterial3D.CULL_DISABLED
+ material.albedo_color = _body_color()
+ return material
+
+
+func _body_color() -> Color:
+ if structure_kind == "base":
+ return Color(0.96, 0.26, 0.20, 0.28)
+ return Color(0.18, 0.62, 0.95, 0.28)
+
+
+func _setup_hitbox() -> void:
+ hitbox_area = HITBOX_SCRIPT.new()
+ hitbox_area.name = "Hitbox"
+ add_child(hitbox_area)
+ hitbox_area.set("team", team)
+ hitbox_area.set("hitbox_size", hitbox_size)
+ hitbox_area.set("owner_target_path", hitbox_area.get_path_to(self))
+
+
+func _setup_health_display() -> void:
+ health_bar_anchor = Node3D.new()
+ health_bar_anchor.name = "HealthBarAnchor"
+ health_bar_anchor.position = Vector3(0.0, display_height, 0.0)
+ add_child(health_bar_anchor)
+
+ health_bar_back = MeshInstance3D.new()
+ health_bar_back.name = "HealthBarBack"
+ var back_mesh := QuadMesh.new()
+ back_mesh.size = HEALTH_BAR_BACK_SIZE
+ health_bar_back.mesh = back_mesh
+ health_bar_back.material_override = _build_health_bar_material(
+ Color(0.08, 0.08, 0.08, 1.0),
+ HEALTH_BAR_BACK_PRIORITY
+ )
+ health_bar_anchor.add_child(health_bar_back)
+
+ health_bar_fill = MeshInstance3D.new()
+ health_bar_fill.name = "HealthBarFill"
+ var fill_mesh := QuadMesh.new()
+ fill_mesh.size = HEALTH_BAR_FILL_SIZE
+ health_bar_fill.mesh = fill_mesh
+ health_bar_fill.material_override = _build_health_bar_material(
+ _fill_color(),
+ HEALTH_BAR_FILL_PRIORITY
+ )
+ health_bar_fill.position = Vector3(0.0, 0.0, HEALTH_BAR_FILL_Z_OFFSET)
+ health_bar_anchor.add_child(health_bar_fill)
+
+ hp_label = Label3D.new()
+ hp_label.name = "HealthLabel"
+ hp_label.font_size = 28
+ hp_label.modulate = Color(1.0, 1.0, 1.0, 1.0)
+ hp_label.billboard = BaseMaterial3D.BILLBOARD_ENABLED
+ hp_label.position = Vector3(0.0, 0.22, 0.0)
+ health_bar_anchor.add_child(hp_label)
+
+
+func _fill_color() -> Color:
+ if structure_kind == "base":
+ return Color(0.95, 0.22, 0.18, 1.0)
+ return Color(0.22, 0.72, 0.98, 1.0)
+
+
+func _build_health_bar_material(color: Color, priority: int) -> StandardMaterial3D:
+ var material := StandardMaterial3D.new()
+ material.shading_mode = BaseMaterial3D.SHADING_MODE_UNSHADED
+ material.transparency = BaseMaterial3D.TRANSPARENCY_ALPHA
+ material.no_depth_test = true
+ material.depth_draw_mode = BaseMaterial3D.DEPTH_DRAW_DISABLED
+ material.cull_mode = BaseMaterial3D.CULL_DISABLED
+ material.render_priority = priority
+ material.albedo_color = color
+ return material
+
+
+func _refresh_health_display() -> void:
+ if health_bar_fill == null or hp_label == null:
+ return
+
+ var hp := _current_health()
+ var ratio := 0.0
+ if max_health > 0:
+ ratio = clampf(float(hp) / float(max_health), 0.0, 1.0)
+
+ health_bar_fill.scale = Vector3(ratio, 1.0, 1.0)
+ health_bar_fill.position = Vector3(
+ -0.5 * HEALTH_BAR_FILL_SIZE.x * (1.0 - ratio),
+ 0.0,
+ HEALTH_BAR_FILL_Z_OFFSET
+ )
+ hp_label.text = str(hp)
+
+
+func _face_health_display_to_camera() -> void:
+ if health_bar_anchor == null:
+ return
+
+ var camera := get_viewport().get_camera_3d()
+ if camera == null:
+ return
+
+ health_bar_anchor.look_at(camera.global_position, Vector3.UP, true)
diff --git a/godot-mock/scene/sim_structure_target.gd.uid b/godot-mock/scene/sim_structure_target.gd.uid
new file mode 100644
index 0000000..5bb399f
--- /dev/null
+++ b/godot-mock/scene/sim_structure_target.gd.uid
@@ -0,0 +1 @@
+uid://d2rwmafiytyde
diff --git a/launch/motion.launch.yaml b/launch/motion.launch.yaml
index a824cd3..8b0453d 100644
--- a/launch/motion.launch.yaml
+++ b/launch/motion.launch.yaml
@@ -5,6 +5,9 @@ launch:
- arg:
name: "use_sim_time"
default: "false"
+ - arg:
+ name: "static_local_map"
+ default: "false"
# 0. 生命周期管理器
- node:
@@ -51,5 +54,7 @@ launch:
name: "controller_server"
param:
- from: "$(var configuration)/motion.yaml"
+ - name: "local_costmap.local_costmap.static_layer.map_subscribe_transient_local"
+ value: "$(var static_local_map)"
- name: "use_sim_time"
value: "$(var use_sim_time)"
diff --git a/launch/static.launch.yaml b/launch/static.launch.yaml
index 710615f..408e7de 100644
--- a/launch/static.launch.yaml
+++ b/launch/static.launch.yaml
@@ -23,18 +23,19 @@
## - 进行不依赖外部感知输入的静态回归测试
launch:
+ - arg:
+ name: "use_sim_time"
+ default: "false"
+ - arg:
+ name: "global_map"
+ default: "map"
+
- arg:
name: "configuration"
default: "$(find-pkg-share rmcs-navigation)/config"
- arg:
name: "share_location"
default: "$(find-pkg-share rmcs-navigation)"
- - arg:
- name: "use_sim_time"
- default: "false"
- - arg:
- name: "global_map"
- default: "rmul"
# 0. 传感侧生命周期管理器(仅管理 map server)
- node:
@@ -98,3 +99,5 @@ launch:
value: "$(var configuration)"
- name: "use_sim_time"
value: "$(var use_sim_time)"
+ - name: "static_local_map"
+ value: "true"
diff --git a/maps/map.png b/maps/map.png
new file mode 100644
index 0000000..0b01710
Binary files /dev/null and b/maps/map.png differ
diff --git a/maps/map.yaml b/maps/map.yaml
new file mode 100644
index 0000000..8ce6b05
--- /dev/null
+++ b/maps/map.yaml
@@ -0,0 +1,7 @@
+image: map.png
+mode: trinary
+resolution: 0.100000
+origin: [-4.000000, -5.500000, 0.000000]
+negate: 0
+occupied_thresh: 0.650000
+free_thresh: 0.196000
diff --git a/maps/rmuc.lua b/maps/rmuc.lua
new file mode 100644
index 0000000..50228b4
--- /dev/null
+++ b/maps/rmuc.lua
@@ -0,0 +1,192 @@
+-- Generated by tools/region-editor
+return {
+ width = 292,
+ height = 161,
+ resolution = 0.1,
+ origin = {
+ x = 0,
+ y = 0,
+ },
+ names = {
+ [0] = "wall",
+ [1] = "ours_home",
+ [2] = "them_home",
+ [3] = "ours_fluctuant",
+ [4] = "them_fluctuant",
+ [5] = "ours_road_begin",
+ [6] = "thems_road_begin",
+ [7] = "ours_trapezoidal_highland",
+ [8] = "them_trapezoidal_highland",
+ [9] = "ours_road_waypoint_1",
+ [10] = "them_road_waypoint_1",
+ [13] = "ours_road_to_fluctuant",
+ [14] = "them_road_to_fluctuant",
+ [15] = "ours_road_to_highland",
+ [16] = "them_road_to_highland",
+ [17] = "ours_highland",
+ [18] = "them_highland",
+ },
+ rows = {
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 6, 6, 6, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 6, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 7, 7, 7, 7, 7, 7, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 7, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 17, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 18, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 0, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ },
+}
diff --git a/maps/rmuc.png b/maps/rmuc.png
index e69de29..7c30aa6 100644
Binary files a/maps/rmuc.png and b/maps/rmuc.png differ
diff --git a/maps/rmuc.region.json b/maps/rmuc.region.json
new file mode 100644
index 0000000..517a99a
--- /dev/null
+++ b/maps/rmuc.region.json
@@ -0,0 +1,6183 @@
+{
+ "version": 1,
+ "map": {
+ "name": "rmuc",
+ "image": "rmuc.png",
+ "width": 292,
+ "height": 161,
+ "resolution": 0.1,
+ "origin": {
+ "x": 0,
+ "y": 0
+ },
+ "protected_black_runs": [
+ [
+ 0,
+ 284,
+ 291
+ ],
+ [
+ 1,
+ 284,
+ 291
+ ],
+ [
+ 2,
+ 284,
+ 291
+ ],
+ [
+ 3,
+ 6,
+ 29
+ ],
+ [
+ 3,
+ 34,
+ 34
+ ],
+ [
+ 3,
+ 148,
+ 150
+ ],
+ [
+ 3,
+ 155,
+ 155
+ ],
+ [
+ 3,
+ 158,
+ 158
+ ],
+ [
+ 3,
+ 249,
+ 251
+ ],
+ [
+ 3,
+ 271,
+ 288
+ ],
+ [
+ 3,
+ 290,
+ 291
+ ],
+ [
+ 4,
+ 5,
+ 30
+ ],
+ [
+ 4,
+ 33,
+ 39
+ ],
+ [
+ 4,
+ 43,
+ 44
+ ],
+ [
+ 4,
+ 64,
+ 65
+ ],
+ [
+ 4,
+ 70,
+ 72
+ ],
+ [
+ 4,
+ 90,
+ 92
+ ],
+ [
+ 4,
+ 97,
+ 100
+ ],
+ [
+ 4,
+ 103,
+ 106
+ ],
+ [
+ 4,
+ 113,
+ 113
+ ],
+ [
+ 4,
+ 119,
+ 119
+ ],
+ [
+ 4,
+ 134,
+ 134
+ ],
+ [
+ 4,
+ 144,
+ 144
+ ],
+ [
+ 4,
+ 147,
+ 161
+ ],
+ [
+ 4,
+ 163,
+ 164
+ ],
+ [
+ 4,
+ 169,
+ 171
+ ],
+ [
+ 4,
+ 178,
+ 183
+ ],
+ [
+ 4,
+ 186,
+ 188
+ ],
+ [
+ 4,
+ 190,
+ 194
+ ],
+ [
+ 4,
+ 198,
+ 205
+ ],
+ [
+ 4,
+ 209,
+ 211
+ ],
+ [
+ 4,
+ 227,
+ 229
+ ],
+ [
+ 4,
+ 233,
+ 234
+ ],
+ [
+ 4,
+ 238,
+ 240
+ ],
+ [
+ 4,
+ 248,
+ 252
+ ],
+ [
+ 4,
+ 270,
+ 288
+ ],
+ [
+ 4,
+ 290,
+ 291
+ ],
+ [
+ 5,
+ 4,
+ 291
+ ],
+ [
+ 6,
+ 4,
+ 291
+ ],
+ [
+ 7,
+ 4,
+ 291
+ ],
+ [
+ 8,
+ 4,
+ 39
+ ],
+ [
+ 8,
+ 143,
+ 161
+ ],
+ [
+ 8,
+ 247,
+ 253
+ ],
+ [
+ 8,
+ 270,
+ 291
+ ],
+ [
+ 9,
+ 4,
+ 39
+ ],
+ [
+ 9,
+ 142,
+ 161
+ ],
+ [
+ 9,
+ 247,
+ 253
+ ],
+ [
+ 9,
+ 270,
+ 274
+ ],
+ [
+ 9,
+ 277,
+ 291
+ ],
+ [
+ 10,
+ 4,
+ 39
+ ],
+ [
+ 10,
+ 142,
+ 161
+ ],
+ [
+ 10,
+ 247,
+ 253
+ ],
+ [
+ 10,
+ 270,
+ 274
+ ],
+ [
+ 10,
+ 277,
+ 291
+ ],
+ [
+ 11,
+ 4,
+ 39
+ ],
+ [
+ 11,
+ 142,
+ 161
+ ],
+ [
+ 11,
+ 247,
+ 253
+ ],
+ [
+ 11,
+ 270,
+ 274
+ ],
+ [
+ 11,
+ 278,
+ 291
+ ],
+ [
+ 12,
+ 4,
+ 38
+ ],
+ [
+ 12,
+ 142,
+ 161
+ ],
+ [
+ 12,
+ 247,
+ 253
+ ],
+ [
+ 12,
+ 270,
+ 274
+ ],
+ [
+ 12,
+ 279,
+ 291
+ ],
+ [
+ 13,
+ 4,
+ 39
+ ],
+ [
+ 13,
+ 134,
+ 134
+ ],
+ [
+ 13,
+ 141,
+ 161
+ ],
+ [
+ 13,
+ 247,
+ 253
+ ],
+ [
+ 13,
+ 270,
+ 274
+ ],
+ [
+ 13,
+ 285,
+ 291
+ ],
+ [
+ 14,
+ 4,
+ 39
+ ],
+ [
+ 14,
+ 113,
+ 113
+ ],
+ [
+ 14,
+ 130,
+ 161
+ ],
+ [
+ 14,
+ 247,
+ 253
+ ],
+ [
+ 14,
+ 270,
+ 274
+ ],
+ [
+ 14,
+ 285,
+ 291
+ ],
+ [
+ 15,
+ 4,
+ 39
+ ],
+ [
+ 15,
+ 106,
+ 161
+ ],
+ [
+ 15,
+ 247,
+ 253
+ ],
+ [
+ 15,
+ 270,
+ 274
+ ],
+ [
+ 15,
+ 284,
+ 291
+ ],
+ [
+ 16,
+ 4,
+ 39
+ ],
+ [
+ 16,
+ 105,
+ 161
+ ],
+ [
+ 16,
+ 247,
+ 253
+ ],
+ [
+ 16,
+ 270,
+ 274
+ ],
+ [
+ 16,
+ 284,
+ 291
+ ],
+ [
+ 17,
+ 4,
+ 39
+ ],
+ [
+ 17,
+ 106,
+ 160
+ ],
+ [
+ 17,
+ 247,
+ 253
+ ],
+ [
+ 17,
+ 270,
+ 274
+ ],
+ [
+ 17,
+ 279,
+ 291
+ ],
+ [
+ 18,
+ 4,
+ 39
+ ],
+ [
+ 18,
+ 131,
+ 156
+ ],
+ [
+ 18,
+ 158,
+ 158
+ ],
+ [
+ 18,
+ 247,
+ 253
+ ],
+ [
+ 18,
+ 270,
+ 273
+ ],
+ [
+ 18,
+ 278,
+ 291
+ ],
+ [
+ 19,
+ 4,
+ 39
+ ],
+ [
+ 19,
+ 131,
+ 141
+ ],
+ [
+ 19,
+ 147,
+ 147
+ ],
+ [
+ 19,
+ 247,
+ 253
+ ],
+ [
+ 19,
+ 270,
+ 273
+ ],
+ [
+ 19,
+ 277,
+ 291
+ ],
+ [
+ 20,
+ 4,
+ 39
+ ],
+ [
+ 20,
+ 132,
+ 141
+ ],
+ [
+ 20,
+ 247,
+ 253
+ ],
+ [
+ 20,
+ 270,
+ 291
+ ],
+ [
+ 21,
+ 4,
+ 39
+ ],
+ [
+ 21,
+ 132,
+ 141
+ ],
+ [
+ 21,
+ 247,
+ 253
+ ],
+ [
+ 21,
+ 270,
+ 291
+ ],
+ [
+ 22,
+ 4,
+ 39
+ ],
+ [
+ 22,
+ 132,
+ 147
+ ],
+ [
+ 22,
+ 149,
+ 152
+ ],
+ [
+ 22,
+ 247,
+ 253
+ ],
+ [
+ 22,
+ 270,
+ 291
+ ],
+ [
+ 23,
+ 4,
+ 39
+ ],
+ [
+ 23,
+ 130,
+ 153
+ ],
+ [
+ 23,
+ 247,
+ 253
+ ],
+ [
+ 23,
+ 269,
+ 291
+ ],
+ [
+ 24,
+ 4,
+ 39
+ ],
+ [
+ 24,
+ 129,
+ 154
+ ],
+ [
+ 24,
+ 188,
+ 197
+ ],
+ [
+ 24,
+ 212,
+ 231
+ ],
+ [
+ 24,
+ 233,
+ 234
+ ],
+ [
+ 24,
+ 247,
+ 253
+ ],
+ [
+ 24,
+ 269,
+ 291
+ ],
+ [
+ 25,
+ 4,
+ 39
+ ],
+ [
+ 25,
+ 128,
+ 154
+ ],
+ [
+ 25,
+ 186,
+ 197
+ ],
+ [
+ 25,
+ 209,
+ 235
+ ],
+ [
+ 25,
+ 247,
+ 253
+ ],
+ [
+ 25,
+ 270,
+ 291
+ ],
+ [
+ 26,
+ 4,
+ 39
+ ],
+ [
+ 26,
+ 127,
+ 154
+ ],
+ [
+ 26,
+ 186,
+ 198
+ ],
+ [
+ 26,
+ 209,
+ 235
+ ],
+ [
+ 26,
+ 247,
+ 253
+ ],
+ [
+ 26,
+ 271,
+ 291
+ ],
+ [
+ 27,
+ 4,
+ 39
+ ],
+ [
+ 27,
+ 127,
+ 154
+ ],
+ [
+ 27,
+ 185,
+ 198
+ ],
+ [
+ 27,
+ 209,
+ 235
+ ],
+ [
+ 27,
+ 247,
+ 253
+ ],
+ [
+ 27,
+ 276,
+ 291
+ ],
+ [
+ 28,
+ 4,
+ 39
+ ],
+ [
+ 28,
+ 126,
+ 141
+ ],
+ [
+ 28,
+ 143,
+ 150
+ ],
+ [
+ 28,
+ 152,
+ 152
+ ],
+ [
+ 28,
+ 185,
+ 199
+ ],
+ [
+ 28,
+ 209,
+ 235
+ ],
+ [
+ 28,
+ 247,
+ 253
+ ],
+ [
+ 28,
+ 277,
+ 291
+ ],
+ [
+ 29,
+ 4,
+ 39
+ ],
+ [
+ 29,
+ 125,
+ 131
+ ],
+ [
+ 29,
+ 184,
+ 198
+ ],
+ [
+ 29,
+ 212,
+ 230
+ ],
+ [
+ 29,
+ 233,
+ 234
+ ],
+ [
+ 29,
+ 247,
+ 253
+ ],
+ [
+ 29,
+ 278,
+ 278
+ ],
+ [
+ 29,
+ 280,
+ 291
+ ],
+ [
+ 30,
+ 4,
+ 39
+ ],
+ [
+ 30,
+ 124,
+ 131
+ ],
+ [
+ 30,
+ 183,
+ 197
+ ],
+ [
+ 30,
+ 247,
+ 253
+ ],
+ [
+ 30,
+ 278,
+ 278
+ ],
+ [
+ 30,
+ 280,
+ 291
+ ],
+ [
+ 31,
+ 4,
+ 39
+ ],
+ [
+ 31,
+ 124,
+ 130
+ ],
+ [
+ 31,
+ 182,
+ 188
+ ],
+ [
+ 31,
+ 247,
+ 253
+ ],
+ [
+ 31,
+ 277,
+ 291
+ ],
+ [
+ 32,
+ 5,
+ 50
+ ],
+ [
+ 32,
+ 52,
+ 54
+ ],
+ [
+ 32,
+ 56,
+ 58
+ ],
+ [
+ 32,
+ 60,
+ 60
+ ],
+ [
+ 32,
+ 62,
+ 62
+ ],
+ [
+ 32,
+ 123,
+ 129
+ ],
+ [
+ 32,
+ 181,
+ 187
+ ],
+ [
+ 32,
+ 247,
+ 253
+ ],
+ [
+ 32,
+ 276,
+ 291
+ ],
+ [
+ 33,
+ 5,
+ 63
+ ],
+ [
+ 33,
+ 122,
+ 128
+ ],
+ [
+ 33,
+ 180,
+ 186
+ ],
+ [
+ 33,
+ 247,
+ 253
+ ],
+ [
+ 33,
+ 276,
+ 291
+ ],
+ [
+ 34,
+ 5,
+ 64
+ ],
+ [
+ 34,
+ 122,
+ 128
+ ],
+ [
+ 34,
+ 178,
+ 186
+ ],
+ [
+ 34,
+ 247,
+ 253
+ ],
+ [
+ 34,
+ 276,
+ 280
+ ],
+ [
+ 34,
+ 282,
+ 291
+ ],
+ [
+ 35,
+ 5,
+ 64
+ ],
+ [
+ 35,
+ 121,
+ 127
+ ],
+ [
+ 35,
+ 176,
+ 185
+ ],
+ [
+ 35,
+ 247,
+ 253
+ ],
+ [
+ 35,
+ 277,
+ 278
+ ],
+ [
+ 35,
+ 281,
+ 291
+ ],
+ [
+ 36,
+ 5,
+ 39
+ ],
+ [
+ 36,
+ 47,
+ 64
+ ],
+ [
+ 36,
+ 120,
+ 126
+ ],
+ [
+ 36,
+ 174,
+ 184
+ ],
+ [
+ 36,
+ 247,
+ 253
+ ],
+ [
+ 36,
+ 282,
+ 282
+ ],
+ [
+ 36,
+ 284,
+ 291
+ ],
+ [
+ 37,
+ 5,
+ 39
+ ],
+ [
+ 37,
+ 48,
+ 63
+ ],
+ [
+ 37,
+ 119,
+ 126
+ ],
+ [
+ 37,
+ 173,
+ 184
+ ],
+ [
+ 37,
+ 247,
+ 253
+ ],
+ [
+ 37,
+ 285,
+ 291
+ ],
+ [
+ 38,
+ 5,
+ 39
+ ],
+ [
+ 38,
+ 58,
+ 63
+ ],
+ [
+ 38,
+ 119,
+ 125
+ ],
+ [
+ 38,
+ 172,
+ 183
+ ],
+ [
+ 38,
+ 247,
+ 253
+ ],
+ [
+ 38,
+ 285,
+ 291
+ ],
+ [
+ 39,
+ 4,
+ 39
+ ],
+ [
+ 39,
+ 57,
+ 63
+ ],
+ [
+ 39,
+ 118,
+ 124
+ ],
+ [
+ 39,
+ 172,
+ 183
+ ],
+ [
+ 39,
+ 247,
+ 253
+ ],
+ [
+ 39,
+ 284,
+ 291
+ ],
+ [
+ 40,
+ 0,
+ 39
+ ],
+ [
+ 40,
+ 57,
+ 62
+ ],
+ [
+ 40,
+ 117,
+ 123
+ ],
+ [
+ 40,
+ 171,
+ 182
+ ],
+ [
+ 40,
+ 247,
+ 253
+ ],
+ [
+ 40,
+ 284,
+ 291
+ ],
+ [
+ 41,
+ 0,
+ 39
+ ],
+ [
+ 41,
+ 57,
+ 62
+ ],
+ [
+ 41,
+ 117,
+ 123
+ ],
+ [
+ 41,
+ 171,
+ 182
+ ],
+ [
+ 41,
+ 218,
+ 219
+ ],
+ [
+ 41,
+ 221,
+ 222
+ ],
+ [
+ 41,
+ 224,
+ 224
+ ],
+ [
+ 41,
+ 229,
+ 229
+ ],
+ [
+ 41,
+ 247,
+ 253
+ ],
+ [
+ 41,
+ 285,
+ 291
+ ],
+ [
+ 42,
+ 0,
+ 25
+ ],
+ [
+ 42,
+ 28,
+ 39
+ ],
+ [
+ 42,
+ 56,
+ 61
+ ],
+ [
+ 42,
+ 116,
+ 122
+ ],
+ [
+ 42,
+ 171,
+ 182
+ ],
+ [
+ 42,
+ 217,
+ 253
+ ],
+ [
+ 42,
+ 284,
+ 291
+ ],
+ [
+ 43,
+ 0,
+ 25
+ ],
+ [
+ 43,
+ 32,
+ 39
+ ],
+ [
+ 43,
+ 56,
+ 61
+ ],
+ [
+ 43,
+ 115,
+ 122
+ ],
+ [
+ 43,
+ 171,
+ 183
+ ],
+ [
+ 43,
+ 217,
+ 253
+ ],
+ [
+ 43,
+ 285,
+ 291
+ ],
+ [
+ 44,
+ 0,
+ 25
+ ],
+ [
+ 44,
+ 32,
+ 39
+ ],
+ [
+ 44,
+ 55,
+ 60
+ ],
+ [
+ 44,
+ 114,
+ 121
+ ],
+ [
+ 44,
+ 172,
+ 183
+ ],
+ [
+ 44,
+ 216,
+ 253
+ ],
+ [
+ 44,
+ 284,
+ 291
+ ],
+ [
+ 45,
+ 0,
+ 25
+ ],
+ [
+ 45,
+ 32,
+ 39
+ ],
+ [
+ 45,
+ 55,
+ 60
+ ],
+ [
+ 45,
+ 114,
+ 120
+ ],
+ [
+ 45,
+ 172,
+ 183
+ ],
+ [
+ 45,
+ 217,
+ 252
+ ],
+ [
+ 45,
+ 285,
+ 291
+ ],
+ [
+ 46,
+ 0,
+ 25
+ ],
+ [
+ 46,
+ 32,
+ 39
+ ],
+ [
+ 46,
+ 54,
+ 59
+ ],
+ [
+ 46,
+ 113,
+ 119
+ ],
+ [
+ 46,
+ 173,
+ 183
+ ],
+ [
+ 46,
+ 218,
+ 218
+ ],
+ [
+ 46,
+ 224,
+ 224
+ ],
+ [
+ 46,
+ 233,
+ 233
+ ],
+ [
+ 46,
+ 238,
+ 241
+ ],
+ [
+ 46,
+ 244,
+ 244
+ ],
+ [
+ 46,
+ 248,
+ 251
+ ],
+ [
+ 46,
+ 285,
+ 291
+ ],
+ [
+ 47,
+ 0,
+ 25
+ ],
+ [
+ 47,
+ 32,
+ 39
+ ],
+ [
+ 47,
+ 48,
+ 59
+ ],
+ [
+ 47,
+ 112,
+ 119
+ ],
+ [
+ 47,
+ 174,
+ 184
+ ],
+ [
+ 47,
+ 285,
+ 291
+ ],
+ [
+ 48,
+ 0,
+ 25
+ ],
+ [
+ 48,
+ 32,
+ 38
+ ],
+ [
+ 48,
+ 47,
+ 59
+ ],
+ [
+ 48,
+ 112,
+ 118
+ ],
+ [
+ 48,
+ 176,
+ 184
+ ],
+ [
+ 48,
+ 285,
+ 291
+ ],
+ [
+ 49,
+ 0,
+ 24
+ ],
+ [
+ 49,
+ 32,
+ 39
+ ],
+ [
+ 49,
+ 47,
+ 58
+ ],
+ [
+ 49,
+ 111,
+ 117
+ ],
+ [
+ 49,
+ 178,
+ 184
+ ],
+ [
+ 49,
+ 285,
+ 291
+ ],
+ [
+ 50,
+ 0,
+ 25
+ ],
+ [
+ 50,
+ 32,
+ 58
+ ],
+ [
+ 50,
+ 110,
+ 117
+ ],
+ [
+ 50,
+ 179,
+ 185
+ ],
+ [
+ 50,
+ 285,
+ 291
+ ],
+ [
+ 51,
+ 0,
+ 25
+ ],
+ [
+ 51,
+ 32,
+ 58
+ ],
+ [
+ 51,
+ 110,
+ 116
+ ],
+ [
+ 51,
+ 180,
+ 185
+ ],
+ [
+ 51,
+ 285,
+ 291
+ ],
+ [
+ 52,
+ 0,
+ 25
+ ],
+ [
+ 52,
+ 32,
+ 57
+ ],
+ [
+ 52,
+ 109,
+ 115
+ ],
+ [
+ 52,
+ 180,
+ 185
+ ],
+ [
+ 52,
+ 285,
+ 291
+ ],
+ [
+ 53,
+ 0,
+ 24
+ ],
+ [
+ 53,
+ 32,
+ 57
+ ],
+ [
+ 53,
+ 108,
+ 114
+ ],
+ [
+ 53,
+ 181,
+ 186
+ ],
+ [
+ 53,
+ 285,
+ 291
+ ],
+ [
+ 54,
+ 0,
+ 23
+ ],
+ [
+ 54,
+ 33,
+ 37
+ ],
+ [
+ 54,
+ 47,
+ 56
+ ],
+ [
+ 54,
+ 107,
+ 114
+ ],
+ [
+ 54,
+ 181,
+ 187
+ ],
+ [
+ 54,
+ 284,
+ 291
+ ],
+ [
+ 55,
+ 0,
+ 9
+ ],
+ [
+ 55,
+ 12,
+ 13
+ ],
+ [
+ 55,
+ 15,
+ 15
+ ],
+ [
+ 55,
+ 17,
+ 17
+ ],
+ [
+ 55,
+ 19,
+ 20
+ ],
+ [
+ 55,
+ 48,
+ 55
+ ],
+ [
+ 55,
+ 107,
+ 113
+ ],
+ [
+ 55,
+ 182,
+ 187
+ ],
+ [
+ 55,
+ 285,
+ 291
+ ],
+ [
+ 56,
+ 0,
+ 9
+ ],
+ [
+ 56,
+ 49,
+ 51
+ ],
+ [
+ 56,
+ 54,
+ 54
+ ],
+ [
+ 56,
+ 106,
+ 113
+ ],
+ [
+ 56,
+ 182,
+ 188
+ ],
+ [
+ 56,
+ 284,
+ 291
+ ],
+ [
+ 57,
+ 0,
+ 8
+ ],
+ [
+ 57,
+ 105,
+ 112
+ ],
+ [
+ 57,
+ 134,
+ 137
+ ],
+ [
+ 57,
+ 182,
+ 188
+ ],
+ [
+ 57,
+ 284,
+ 291
+ ],
+ [
+ 58,
+ 0,
+ 8
+ ],
+ [
+ 58,
+ 105,
+ 112
+ ],
+ [
+ 58,
+ 133,
+ 141
+ ],
+ [
+ 58,
+ 182,
+ 188
+ ],
+ [
+ 58,
+ 285,
+ 291
+ ],
+ [
+ 59,
+ 0,
+ 8
+ ],
+ [
+ 59,
+ 104,
+ 110
+ ],
+ [
+ 59,
+ 132,
+ 144
+ ],
+ [
+ 59,
+ 182,
+ 188
+ ],
+ [
+ 59,
+ 284,
+ 291
+ ],
+ [
+ 60,
+ 0,
+ 8
+ ],
+ [
+ 60,
+ 103,
+ 110
+ ],
+ [
+ 60,
+ 131,
+ 146
+ ],
+ [
+ 60,
+ 182,
+ 188
+ ],
+ [
+ 60,
+ 285,
+ 291
+ ],
+ [
+ 61,
+ 0,
+ 8
+ ],
+ [
+ 61,
+ 102,
+ 109
+ ],
+ [
+ 61,
+ 130,
+ 134
+ ],
+ [
+ 61,
+ 136,
+ 149
+ ],
+ [
+ 61,
+ 151,
+ 151
+ ],
+ [
+ 61,
+ 183,
+ 189
+ ],
+ [
+ 61,
+ 285,
+ 291
+ ],
+ [
+ 62,
+ 0,
+ 8
+ ],
+ [
+ 62,
+ 102,
+ 109
+ ],
+ [
+ 62,
+ 129,
+ 133
+ ],
+ [
+ 62,
+ 139,
+ 152
+ ],
+ [
+ 62,
+ 183,
+ 189
+ ],
+ [
+ 62,
+ 285,
+ 291
+ ],
+ [
+ 63,
+ 0,
+ 8
+ ],
+ [
+ 63,
+ 101,
+ 109
+ ],
+ [
+ 63,
+ 128,
+ 132
+ ],
+ [
+ 63,
+ 143,
+ 153
+ ],
+ [
+ 63,
+ 182,
+ 186
+ ],
+ [
+ 63,
+ 188,
+ 190
+ ],
+ [
+ 63,
+ 284,
+ 291
+ ],
+ [
+ 64,
+ 0,
+ 8
+ ],
+ [
+ 64,
+ 100,
+ 102
+ ],
+ [
+ 64,
+ 105,
+ 109
+ ],
+ [
+ 64,
+ 127,
+ 131
+ ],
+ [
+ 64,
+ 136,
+ 139
+ ],
+ [
+ 64,
+ 145,
+ 155
+ ],
+ [
+ 64,
+ 183,
+ 186
+ ],
+ [
+ 64,
+ 188,
+ 190
+ ],
+ [
+ 64,
+ 284,
+ 291
+ ],
+ [
+ 65,
+ 0,
+ 8
+ ],
+ [
+ 65,
+ 100,
+ 103
+ ],
+ [
+ 65,
+ 105,
+ 109
+ ],
+ [
+ 65,
+ 126,
+ 130
+ ],
+ [
+ 65,
+ 135,
+ 143
+ ],
+ [
+ 65,
+ 145,
+ 156
+ ],
+ [
+ 65,
+ 182,
+ 186
+ ],
+ [
+ 65,
+ 188,
+ 191
+ ],
+ [
+ 65,
+ 283,
+ 291
+ ],
+ [
+ 66,
+ 0,
+ 9
+ ],
+ [
+ 66,
+ 99,
+ 103
+ ],
+ [
+ 66,
+ 105,
+ 109
+ ],
+ [
+ 66,
+ 125,
+ 129
+ ],
+ [
+ 66,
+ 134,
+ 157
+ ],
+ [
+ 66,
+ 182,
+ 186
+ ],
+ [
+ 66,
+ 189,
+ 191
+ ],
+ [
+ 66,
+ 282,
+ 291
+ ],
+ [
+ 67,
+ 0,
+ 10
+ ],
+ [
+ 67,
+ 98,
+ 102
+ ],
+ [
+ 67,
+ 105,
+ 109
+ ],
+ [
+ 67,
+ 124,
+ 128
+ ],
+ [
+ 67,
+ 135,
+ 135
+ ],
+ [
+ 67,
+ 141,
+ 158
+ ],
+ [
+ 67,
+ 182,
+ 186
+ ],
+ [
+ 67,
+ 189,
+ 192
+ ],
+ [
+ 67,
+ 282,
+ 291
+ ],
+ [
+ 68,
+ 0,
+ 10
+ ],
+ [
+ 68,
+ 97,
+ 102
+ ],
+ [
+ 68,
+ 105,
+ 108
+ ],
+ [
+ 68,
+ 124,
+ 127
+ ],
+ [
+ 68,
+ 145,
+ 159
+ ],
+ [
+ 68,
+ 182,
+ 186
+ ],
+ [
+ 68,
+ 189,
+ 192
+ ],
+ [
+ 68,
+ 282,
+ 291
+ ],
+ [
+ 69,
+ 0,
+ 9
+ ],
+ [
+ 69,
+ 96,
+ 101
+ ],
+ [
+ 69,
+ 105,
+ 109
+ ],
+ [
+ 69,
+ 124,
+ 127
+ ],
+ [
+ 69,
+ 131,
+ 131
+ ],
+ [
+ 69,
+ 147,
+ 159
+ ],
+ [
+ 69,
+ 182,
+ 186
+ ],
+ [
+ 69,
+ 190,
+ 192
+ ],
+ [
+ 69,
+ 260,
+ 262
+ ],
+ [
+ 69,
+ 282,
+ 291
+ ],
+ [
+ 70,
+ 0,
+ 8
+ ],
+ [
+ 70,
+ 28,
+ 32
+ ],
+ [
+ 70,
+ 96,
+ 100
+ ],
+ [
+ 70,
+ 105,
+ 109
+ ],
+ [
+ 70,
+ 124,
+ 127
+ ],
+ [
+ 70,
+ 129,
+ 132
+ ],
+ [
+ 70,
+ 146,
+ 161
+ ],
+ [
+ 70,
+ 182,
+ 186
+ ],
+ [
+ 70,
+ 190,
+ 192
+ ],
+ [
+ 70,
+ 258,
+ 265
+ ],
+ [
+ 70,
+ 282,
+ 291
+ ],
+ [
+ 71,
+ 0,
+ 8
+ ],
+ [
+ 71,
+ 26,
+ 34
+ ],
+ [
+ 71,
+ 96,
+ 100
+ ],
+ [
+ 71,
+ 105,
+ 109
+ ],
+ [
+ 71,
+ 124,
+ 131
+ ],
+ [
+ 71,
+ 145,
+ 162
+ ],
+ [
+ 71,
+ 182,
+ 186
+ ],
+ [
+ 71,
+ 191,
+ 193
+ ],
+ [
+ 71,
+ 256,
+ 266
+ ],
+ [
+ 71,
+ 282,
+ 291
+ ],
+ [
+ 72,
+ 0,
+ 8
+ ],
+ [
+ 72,
+ 24,
+ 35
+ ],
+ [
+ 72,
+ 96,
+ 99
+ ],
+ [
+ 72,
+ 105,
+ 109
+ ],
+ [
+ 72,
+ 124,
+ 129
+ ],
+ [
+ 72,
+ 144,
+ 162
+ ],
+ [
+ 72,
+ 183,
+ 186
+ ],
+ [
+ 72,
+ 191,
+ 194
+ ],
+ [
+ 72,
+ 255,
+ 268
+ ],
+ [
+ 72,
+ 282,
+ 291
+ ],
+ [
+ 73,
+ 0,
+ 8
+ ],
+ [
+ 73,
+ 23,
+ 36
+ ],
+ [
+ 73,
+ 96,
+ 99
+ ],
+ [
+ 73,
+ 105,
+ 109
+ ],
+ [
+ 73,
+ 124,
+ 128
+ ],
+ [
+ 73,
+ 143,
+ 163
+ ],
+ [
+ 73,
+ 182,
+ 186
+ ],
+ [
+ 73,
+ 192,
+ 194
+ ],
+ [
+ 73,
+ 254,
+ 269
+ ],
+ [
+ 73,
+ 282,
+ 291
+ ],
+ [
+ 74,
+ 0,
+ 8
+ ],
+ [
+ 74,
+ 22,
+ 37
+ ],
+ [
+ 74,
+ 96,
+ 99
+ ],
+ [
+ 74,
+ 105,
+ 109
+ ],
+ [
+ 74,
+ 124,
+ 128
+ ],
+ [
+ 74,
+ 142,
+ 164
+ ],
+ [
+ 74,
+ 183,
+ 185
+ ],
+ [
+ 74,
+ 192,
+ 194
+ ],
+ [
+ 74,
+ 253,
+ 269
+ ],
+ [
+ 74,
+ 282,
+ 291
+ ],
+ [
+ 75,
+ 0,
+ 8
+ ],
+ [
+ 75,
+ 22,
+ 38
+ ],
+ [
+ 75,
+ 96,
+ 99
+ ],
+ [
+ 75,
+ 105,
+ 109
+ ],
+ [
+ 75,
+ 124,
+ 128
+ ],
+ [
+ 75,
+ 141,
+ 165
+ ],
+ [
+ 75,
+ 183,
+ 185
+ ],
+ [
+ 75,
+ 192,
+ 194
+ ],
+ [
+ 75,
+ 252,
+ 270
+ ],
+ [
+ 75,
+ 282,
+ 291
+ ],
+ [
+ 76,
+ 0,
+ 8
+ ],
+ [
+ 76,
+ 22,
+ 39
+ ],
+ [
+ 76,
+ 96,
+ 99
+ ],
+ [
+ 76,
+ 105,
+ 109
+ ],
+ [
+ 76,
+ 124,
+ 128
+ ],
+ [
+ 76,
+ 140,
+ 166
+ ],
+ [
+ 76,
+ 183,
+ 186
+ ],
+ [
+ 76,
+ 192,
+ 195
+ ],
+ [
+ 76,
+ 252,
+ 270
+ ],
+ [
+ 76,
+ 282,
+ 291
+ ],
+ [
+ 77,
+ 0,
+ 8
+ ],
+ [
+ 77,
+ 22,
+ 39
+ ],
+ [
+ 77,
+ 96,
+ 99
+ ],
+ [
+ 77,
+ 105,
+ 109
+ ],
+ [
+ 77,
+ 124,
+ 128
+ ],
+ [
+ 77,
+ 139,
+ 167
+ ],
+ [
+ 77,
+ 183,
+ 187
+ ],
+ [
+ 77,
+ 192,
+ 194
+ ],
+ [
+ 77,
+ 251,
+ 271
+ ],
+ [
+ 77,
+ 282,
+ 291
+ ],
+ [
+ 78,
+ 0,
+ 9
+ ],
+ [
+ 78,
+ 22,
+ 39
+ ],
+ [
+ 78,
+ 96,
+ 99
+ ],
+ [
+ 78,
+ 105,
+ 109
+ ],
+ [
+ 78,
+ 124,
+ 128
+ ],
+ [
+ 78,
+ 138,
+ 143
+ ],
+ [
+ 78,
+ 145,
+ 153
+ ],
+ [
+ 78,
+ 156,
+ 168
+ ],
+ [
+ 78,
+ 182,
+ 187
+ ],
+ [
+ 78,
+ 192,
+ 194
+ ],
+ [
+ 78,
+ 251,
+ 271
+ ],
+ [
+ 78,
+ 282,
+ 291
+ ],
+ [
+ 79,
+ 0,
+ 10
+ ],
+ [
+ 79,
+ 22,
+ 39
+ ],
+ [
+ 79,
+ 96,
+ 99
+ ],
+ [
+ 79,
+ 105,
+ 108
+ ],
+ [
+ 79,
+ 124,
+ 128
+ ],
+ [
+ 79,
+ 131,
+ 132
+ ],
+ [
+ 79,
+ 137,
+ 142
+ ],
+ [
+ 79,
+ 146,
+ 154
+ ],
+ [
+ 79,
+ 157,
+ 167
+ ],
+ [
+ 79,
+ 182,
+ 187
+ ],
+ [
+ 79,
+ 192,
+ 194
+ ],
+ [
+ 79,
+ 252,
+ 271
+ ],
+ [
+ 79,
+ 282,
+ 291
+ ],
+ [
+ 80,
+ 0,
+ 9
+ ],
+ [
+ 80,
+ 22,
+ 40
+ ],
+ [
+ 80,
+ 96,
+ 99
+ ],
+ [
+ 80,
+ 105,
+ 109
+ ],
+ [
+ 80,
+ 124,
+ 133
+ ],
+ [
+ 80,
+ 136,
+ 143
+ ],
+ [
+ 80,
+ 145,
+ 145
+ ],
+ [
+ 80,
+ 148,
+ 148
+ ],
+ [
+ 80,
+ 150,
+ 155
+ ],
+ [
+ 80,
+ 158,
+ 162
+ ],
+ [
+ 80,
+ 164,
+ 168
+ ],
+ [
+ 80,
+ 182,
+ 187
+ ],
+ [
+ 80,
+ 192,
+ 194
+ ],
+ [
+ 80,
+ 252,
+ 271
+ ],
+ [
+ 80,
+ 282,
+ 291
+ ],
+ [
+ 81,
+ 0,
+ 8
+ ],
+ [
+ 81,
+ 21,
+ 39
+ ],
+ [
+ 81,
+ 96,
+ 99
+ ],
+ [
+ 81,
+ 105,
+ 109
+ ],
+ [
+ 81,
+ 124,
+ 146
+ ],
+ [
+ 81,
+ 150,
+ 154
+ ],
+ [
+ 81,
+ 160,
+ 160
+ ],
+ [
+ 81,
+ 163,
+ 168
+ ],
+ [
+ 81,
+ 183,
+ 187
+ ],
+ [
+ 81,
+ 192,
+ 194
+ ],
+ [
+ 81,
+ 252,
+ 271
+ ],
+ [
+ 81,
+ 282,
+ 291
+ ],
+ [
+ 82,
+ 0,
+ 8
+ ],
+ [
+ 82,
+ 22,
+ 39
+ ],
+ [
+ 82,
+ 96,
+ 99
+ ],
+ [
+ 82,
+ 105,
+ 109
+ ],
+ [
+ 82,
+ 124,
+ 147
+ ],
+ [
+ 82,
+ 149,
+ 153
+ ],
+ [
+ 82,
+ 163,
+ 167
+ ],
+ [
+ 82,
+ 182,
+ 187
+ ],
+ [
+ 82,
+ 192,
+ 194
+ ],
+ [
+ 82,
+ 252,
+ 271
+ ],
+ [
+ 82,
+ 282,
+ 291
+ ],
+ [
+ 83,
+ 0,
+ 8
+ ],
+ [
+ 83,
+ 22,
+ 39
+ ],
+ [
+ 83,
+ 96,
+ 99
+ ],
+ [
+ 83,
+ 105,
+ 109
+ ],
+ [
+ 83,
+ 125,
+ 152
+ ],
+ [
+ 83,
+ 164,
+ 167
+ ],
+ [
+ 83,
+ 182,
+ 187
+ ],
+ [
+ 83,
+ 192,
+ 194
+ ],
+ [
+ 83,
+ 252,
+ 272
+ ],
+ [
+ 83,
+ 282,
+ 291
+ ],
+ [
+ 84,
+ 0,
+ 8
+ ],
+ [
+ 84,
+ 22,
+ 39
+ ],
+ [
+ 84,
+ 96,
+ 100
+ ],
+ [
+ 84,
+ 105,
+ 109
+ ],
+ [
+ 84,
+ 125,
+ 127
+ ],
+ [
+ 84,
+ 129,
+ 151
+ ],
+ [
+ 84,
+ 164,
+ 167
+ ],
+ [
+ 84,
+ 182,
+ 187
+ ],
+ [
+ 84,
+ 192,
+ 194
+ ],
+ [
+ 84,
+ 252,
+ 272
+ ],
+ [
+ 84,
+ 282,
+ 291
+ ],
+ [
+ 85,
+ 0,
+ 8
+ ],
+ [
+ 85,
+ 22,
+ 38
+ ],
+ [
+ 85,
+ 96,
+ 99
+ ],
+ [
+ 85,
+ 105,
+ 109
+ ],
+ [
+ 85,
+ 126,
+ 126
+ ],
+ [
+ 85,
+ 128,
+ 150
+ ],
+ [
+ 85,
+ 164,
+ 167
+ ],
+ [
+ 85,
+ 182,
+ 186
+ ],
+ [
+ 85,
+ 192,
+ 195
+ ],
+ [
+ 85,
+ 253,
+ 271
+ ],
+ [
+ 85,
+ 282,
+ 291
+ ],
+ [
+ 86,
+ 0,
+ 9
+ ],
+ [
+ 86,
+ 22,
+ 37
+ ],
+ [
+ 86,
+ 96,
+ 99
+ ],
+ [
+ 86,
+ 105,
+ 109
+ ],
+ [
+ 86,
+ 127,
+ 150
+ ],
+ [
+ 86,
+ 163,
+ 167
+ ],
+ [
+ 86,
+ 183,
+ 186
+ ],
+ [
+ 86,
+ 192,
+ 195
+ ],
+ [
+ 86,
+ 254,
+ 270
+ ],
+ [
+ 86,
+ 282,
+ 291
+ ],
+ [
+ 87,
+ 0,
+ 10
+ ],
+ [
+ 87,
+ 23,
+ 36
+ ],
+ [
+ 87,
+ 96,
+ 99
+ ],
+ [
+ 87,
+ 105,
+ 109
+ ],
+ [
+ 87,
+ 128,
+ 149
+ ],
+ [
+ 87,
+ 163,
+ 167
+ ],
+ [
+ 87,
+ 183,
+ 186
+ ],
+ [
+ 87,
+ 192,
+ 194
+ ],
+ [
+ 87,
+ 255,
+ 269
+ ],
+ [
+ 87,
+ 282,
+ 291
+ ],
+ [
+ 88,
+ 0,
+ 10
+ ],
+ [
+ 88,
+ 24,
+ 35
+ ],
+ [
+ 88,
+ 96,
+ 99
+ ],
+ [
+ 88,
+ 105,
+ 108
+ ],
+ [
+ 88,
+ 129,
+ 147
+ ],
+ [
+ 88,
+ 161,
+ 167
+ ],
+ [
+ 88,
+ 183,
+ 187
+ ],
+ [
+ 88,
+ 192,
+ 194
+ ],
+ [
+ 88,
+ 257,
+ 268
+ ],
+ [
+ 88,
+ 282,
+ 291
+ ],
+ [
+ 89,
+ 0,
+ 10
+ ],
+ [
+ 89,
+ 26,
+ 34
+ ],
+ [
+ 89,
+ 97,
+ 100
+ ],
+ [
+ 89,
+ 105,
+ 109
+ ],
+ [
+ 89,
+ 130,
+ 146
+ ],
+ [
+ 89,
+ 160,
+ 167
+ ],
+ [
+ 89,
+ 182,
+ 187
+ ],
+ [
+ 89,
+ 192,
+ 194
+ ],
+ [
+ 89,
+ 258,
+ 267
+ ],
+ [
+ 89,
+ 282,
+ 291
+ ],
+ [
+ 90,
+ 0,
+ 10
+ ],
+ [
+ 90,
+ 28,
+ 33
+ ],
+ [
+ 90,
+ 98,
+ 100
+ ],
+ [
+ 90,
+ 105,
+ 109
+ ],
+ [
+ 90,
+ 131,
+ 146
+ ],
+ [
+ 90,
+ 160,
+ 162
+ ],
+ [
+ 90,
+ 164,
+ 167
+ ],
+ [
+ 90,
+ 182,
+ 187
+ ],
+ [
+ 90,
+ 191,
+ 193
+ ],
+ [
+ 90,
+ 259,
+ 265
+ ],
+ [
+ 90,
+ 282,
+ 291
+ ],
+ [
+ 91,
+ 0,
+ 10
+ ],
+ [
+ 91,
+ 98,
+ 101
+ ],
+ [
+ 91,
+ 105,
+ 109
+ ],
+ [
+ 91,
+ 132,
+ 145
+ ],
+ [
+ 91,
+ 158,
+ 161
+ ],
+ [
+ 91,
+ 164,
+ 167
+ ],
+ [
+ 91,
+ 182,
+ 187
+ ],
+ [
+ 91,
+ 190,
+ 193
+ ],
+ [
+ 91,
+ 261,
+ 262
+ ],
+ [
+ 91,
+ 282,
+ 291
+ ],
+ [
+ 92,
+ 0,
+ 10
+ ],
+ [
+ 92,
+ 98,
+ 101
+ ],
+ [
+ 92,
+ 105,
+ 109
+ ],
+ [
+ 92,
+ 133,
+ 147
+ ],
+ [
+ 92,
+ 157,
+ 160
+ ],
+ [
+ 92,
+ 164,
+ 167
+ ],
+ [
+ 92,
+ 183,
+ 187
+ ],
+ [
+ 92,
+ 190,
+ 193
+ ],
+ [
+ 92,
+ 282,
+ 291
+ ],
+ [
+ 93,
+ 0,
+ 9
+ ],
+ [
+ 93,
+ 99,
+ 102
+ ],
+ [
+ 93,
+ 105,
+ 109
+ ],
+ [
+ 93,
+ 134,
+ 150
+ ],
+ [
+ 93,
+ 155,
+ 158
+ ],
+ [
+ 93,
+ 163,
+ 167
+ ],
+ [
+ 93,
+ 182,
+ 187
+ ],
+ [
+ 93,
+ 189,
+ 192
+ ],
+ [
+ 93,
+ 282,
+ 291
+ ],
+ [
+ 94,
+ 0,
+ 8
+ ],
+ [
+ 94,
+ 99,
+ 103
+ ],
+ [
+ 94,
+ 105,
+ 109
+ ],
+ [
+ 94,
+ 135,
+ 157
+ ],
+ [
+ 94,
+ 162,
+ 167
+ ],
+ [
+ 94,
+ 182,
+ 186
+ ],
+ [
+ 94,
+ 188,
+ 191
+ ],
+ [
+ 94,
+ 282,
+ 291
+ ],
+ [
+ 95,
+ 0,
+ 8
+ ],
+ [
+ 95,
+ 99,
+ 109
+ ],
+ [
+ 95,
+ 136,
+ 155
+ ],
+ [
+ 95,
+ 161,
+ 166
+ ],
+ [
+ 95,
+ 183,
+ 191
+ ],
+ [
+ 95,
+ 283,
+ 291
+ ],
+ [
+ 96,
+ 0,
+ 7
+ ],
+ [
+ 96,
+ 100,
+ 109
+ ],
+ [
+ 96,
+ 137,
+ 146
+ ],
+ [
+ 96,
+ 152,
+ 153
+ ],
+ [
+ 96,
+ 160,
+ 165
+ ],
+ [
+ 96,
+ 182,
+ 190
+ ],
+ [
+ 96,
+ 283,
+ 291
+ ],
+ [
+ 97,
+ 0,
+ 7
+ ],
+ [
+ 97,
+ 100,
+ 109
+ ],
+ [
+ 97,
+ 139,
+ 149
+ ],
+ [
+ 97,
+ 159,
+ 164
+ ],
+ [
+ 97,
+ 182,
+ 189
+ ],
+ [
+ 97,
+ 283,
+ 291
+ ],
+ [
+ 98,
+ 0,
+ 7
+ ],
+ [
+ 98,
+ 101,
+ 109
+ ],
+ [
+ 98,
+ 140,
+ 152
+ ],
+ [
+ 98,
+ 158,
+ 163
+ ],
+ [
+ 98,
+ 182,
+ 188
+ ],
+ [
+ 98,
+ 283,
+ 291
+ ],
+ [
+ 99,
+ 0,
+ 7
+ ],
+ [
+ 99,
+ 101,
+ 109
+ ],
+ [
+ 99,
+ 141,
+ 141
+ ],
+ [
+ 99,
+ 143,
+ 153
+ ],
+ [
+ 99,
+ 155,
+ 155
+ ],
+ [
+ 99,
+ 157,
+ 162
+ ],
+ [
+ 99,
+ 182,
+ 188
+ ],
+ [
+ 99,
+ 283,
+ 291
+ ],
+ [
+ 100,
+ 0,
+ 7
+ ],
+ [
+ 100,
+ 102,
+ 109
+ ],
+ [
+ 100,
+ 144,
+ 161
+ ],
+ [
+ 100,
+ 182,
+ 187
+ ],
+ [
+ 100,
+ 283,
+ 291
+ ],
+ [
+ 101,
+ 0,
+ 7
+ ],
+ [
+ 101,
+ 103,
+ 109
+ ],
+ [
+ 101,
+ 147,
+ 159
+ ],
+ [
+ 101,
+ 181,
+ 187
+ ],
+ [
+ 101,
+ 283,
+ 291
+ ],
+ [
+ 102,
+ 0,
+ 7
+ ],
+ [
+ 102,
+ 103,
+ 109
+ ],
+ [
+ 102,
+ 150,
+ 158
+ ],
+ [
+ 102,
+ 181,
+ 186
+ ],
+ [
+ 102,
+ 283,
+ 291
+ ],
+ [
+ 103,
+ 0,
+ 7
+ ],
+ [
+ 103,
+ 104,
+ 109
+ ],
+ [
+ 103,
+ 153,
+ 153
+ ],
+ [
+ 103,
+ 155,
+ 157
+ ],
+ [
+ 103,
+ 180,
+ 185
+ ],
+ [
+ 103,
+ 283,
+ 291
+ ],
+ [
+ 104,
+ 0,
+ 8
+ ],
+ [
+ 104,
+ 104,
+ 109
+ ],
+ [
+ 104,
+ 156,
+ 156
+ ],
+ [
+ 104,
+ 179,
+ 185
+ ],
+ [
+ 104,
+ 237,
+ 291
+ ],
+ [
+ 105,
+ 0,
+ 7
+ ],
+ [
+ 105,
+ 105,
+ 110
+ ],
+ [
+ 105,
+ 178,
+ 184
+ ],
+ [
+ 105,
+ 236,
+ 291
+ ],
+ [
+ 106,
+ 0,
+ 7
+ ],
+ [
+ 106,
+ 105,
+ 110
+ ],
+ [
+ 106,
+ 178,
+ 183
+ ],
+ [
+ 106,
+ 236,
+ 291
+ ],
+ [
+ 107,
+ 0,
+ 7
+ ],
+ [
+ 107,
+ 106,
+ 111
+ ],
+ [
+ 107,
+ 177,
+ 183
+ ],
+ [
+ 107,
+ 235,
+ 291
+ ],
+ [
+ 108,
+ 0,
+ 7
+ ],
+ [
+ 108,
+ 106,
+ 111
+ ],
+ [
+ 108,
+ 176,
+ 182
+ ],
+ [
+ 108,
+ 234,
+ 291
+ ],
+ [
+ 109,
+ 0,
+ 7
+ ],
+ [
+ 109,
+ 106,
+ 111
+ ],
+ [
+ 109,
+ 176,
+ 181
+ ],
+ [
+ 109,
+ 234,
+ 248
+ ],
+ [
+ 109,
+ 253,
+ 291
+ ],
+ [
+ 110,
+ 0,
+ 7
+ ],
+ [
+ 110,
+ 106,
+ 112
+ ],
+ [
+ 110,
+ 175,
+ 180
+ ],
+ [
+ 110,
+ 234,
+ 244
+ ],
+ [
+ 110,
+ 253,
+ 291
+ ],
+ [
+ 111,
+ 0,
+ 7
+ ],
+ [
+ 111,
+ 107,
+ 113
+ ],
+ [
+ 111,
+ 174,
+ 179
+ ],
+ [
+ 111,
+ 233,
+ 244
+ ],
+ [
+ 111,
+ 253,
+ 291
+ ],
+ [
+ 112,
+ 0,
+ 7
+ ],
+ [
+ 112,
+ 107,
+ 114
+ ],
+ [
+ 112,
+ 174,
+ 178
+ ],
+ [
+ 112,
+ 233,
+ 244
+ ],
+ [
+ 112,
+ 253,
+ 291
+ ],
+ [
+ 113,
+ 0,
+ 7
+ ],
+ [
+ 113,
+ 41,
+ 43
+ ],
+ [
+ 113,
+ 47,
+ 48
+ ],
+ [
+ 113,
+ 50,
+ 50
+ ],
+ [
+ 113,
+ 53,
+ 53
+ ],
+ [
+ 113,
+ 108,
+ 116
+ ],
+ [
+ 113,
+ 173,
+ 177
+ ],
+ [
+ 113,
+ 233,
+ 243
+ ],
+ [
+ 113,
+ 253,
+ 291
+ ],
+ [
+ 114,
+ 0,
+ 7
+ ],
+ [
+ 114,
+ 40,
+ 74
+ ],
+ [
+ 114,
+ 109,
+ 117
+ ],
+ [
+ 114,
+ 172,
+ 178
+ ],
+ [
+ 114,
+ 232,
+ 238
+ ],
+ [
+ 114,
+ 253,
+ 291
+ ],
+ [
+ 115,
+ 0,
+ 7
+ ],
+ [
+ 115,
+ 39,
+ 75
+ ],
+ [
+ 115,
+ 109,
+ 118
+ ],
+ [
+ 115,
+ 171,
+ 177
+ ],
+ [
+ 115,
+ 232,
+ 237
+ ],
+ [
+ 115,
+ 253,
+ 291
+ ],
+ [
+ 116,
+ 0,
+ 8
+ ],
+ [
+ 116,
+ 39,
+ 75
+ ],
+ [
+ 116,
+ 109,
+ 119
+ ],
+ [
+ 116,
+ 171,
+ 176
+ ],
+ [
+ 116,
+ 231,
+ 237
+ ],
+ [
+ 116,
+ 253,
+ 291
+ ],
+ [
+ 117,
+ 0,
+ 8
+ ],
+ [
+ 117,
+ 39,
+ 75
+ ],
+ [
+ 117,
+ 110,
+ 119
+ ],
+ [
+ 117,
+ 170,
+ 176
+ ],
+ [
+ 117,
+ 231,
+ 236
+ ],
+ [
+ 117,
+ 253,
+ 291
+ ],
+ [
+ 118,
+ 0,
+ 7
+ ],
+ [
+ 118,
+ 39,
+ 74
+ ],
+ [
+ 118,
+ 109,
+ 119
+ ],
+ [
+ 118,
+ 169,
+ 175
+ ],
+ [
+ 118,
+ 230,
+ 235
+ ],
+ [
+ 118,
+ 253,
+ 291
+ ],
+ [
+ 119,
+ 0,
+ 7
+ ],
+ [
+ 119,
+ 39,
+ 45
+ ],
+ [
+ 119,
+ 59,
+ 59
+ ],
+ [
+ 119,
+ 63,
+ 69
+ ],
+ [
+ 119,
+ 109,
+ 119
+ ],
+ [
+ 119,
+ 169,
+ 174
+ ],
+ [
+ 119,
+ 230,
+ 235
+ ],
+ [
+ 119,
+ 253,
+ 291
+ ],
+ [
+ 120,
+ 0,
+ 7
+ ],
+ [
+ 120,
+ 39,
+ 45
+ ],
+ [
+ 120,
+ 109,
+ 119
+ ],
+ [
+ 120,
+ 168,
+ 173
+ ],
+ [
+ 120,
+ 230,
+ 234
+ ],
+ [
+ 120,
+ 253,
+ 291
+ ],
+ [
+ 121,
+ 0,
+ 7
+ ],
+ [
+ 121,
+ 39,
+ 45
+ ],
+ [
+ 121,
+ 109,
+ 119
+ ],
+ [
+ 121,
+ 167,
+ 172
+ ],
+ [
+ 121,
+ 229,
+ 234
+ ],
+ [
+ 121,
+ 253,
+ 287
+ ],
+ [
+ 121,
+ 289,
+ 290
+ ],
+ [
+ 122,
+ 0,
+ 7
+ ],
+ [
+ 122,
+ 39,
+ 45
+ ],
+ [
+ 122,
+ 109,
+ 119
+ ],
+ [
+ 122,
+ 167,
+ 172
+ ],
+ [
+ 122,
+ 229,
+ 234
+ ],
+ [
+ 122,
+ 253,
+ 287
+ ],
+ [
+ 123,
+ 0,
+ 7
+ ],
+ [
+ 123,
+ 39,
+ 45
+ ],
+ [
+ 123,
+ 108,
+ 118
+ ],
+ [
+ 123,
+ 166,
+ 171
+ ],
+ [
+ 123,
+ 228,
+ 235
+ ],
+ [
+ 123,
+ 237,
+ 243
+ ],
+ [
+ 123,
+ 253,
+ 287
+ ],
+ [
+ 124,
+ 0,
+ 8
+ ],
+ [
+ 124,
+ 15,
+ 15
+ ],
+ [
+ 124,
+ 39,
+ 45
+ ],
+ [
+ 124,
+ 107,
+ 117
+ ],
+ [
+ 124,
+ 165,
+ 171
+ ],
+ [
+ 124,
+ 228,
+ 244
+ ],
+ [
+ 124,
+ 246,
+ 246
+ ],
+ [
+ 124,
+ 253,
+ 287
+ ],
+ [
+ 125,
+ 0,
+ 9
+ ],
+ [
+ 125,
+ 13,
+ 16
+ ],
+ [
+ 125,
+ 39,
+ 45
+ ],
+ [
+ 125,
+ 107,
+ 116
+ ],
+ [
+ 125,
+ 165,
+ 170
+ ],
+ [
+ 125,
+ 227,
+ 287
+ ],
+ [
+ 126,
+ 0,
+ 10
+ ],
+ [
+ 126,
+ 12,
+ 16
+ ],
+ [
+ 126,
+ 39,
+ 45
+ ],
+ [
+ 126,
+ 106,
+ 114
+ ],
+ [
+ 126,
+ 164,
+ 169
+ ],
+ [
+ 126,
+ 228,
+ 287
+ ],
+ [
+ 127,
+ 0,
+ 16
+ ],
+ [
+ 127,
+ 39,
+ 45
+ ],
+ [
+ 127,
+ 105,
+ 112
+ ],
+ [
+ 127,
+ 163,
+ 169
+ ],
+ [
+ 127,
+ 229,
+ 287
+ ],
+ [
+ 128,
+ 0,
+ 16
+ ],
+ [
+ 128,
+ 39,
+ 45
+ ],
+ [
+ 128,
+ 104,
+ 111
+ ],
+ [
+ 128,
+ 162,
+ 168
+ ],
+ [
+ 128,
+ 230,
+ 230
+ ],
+ [
+ 128,
+ 232,
+ 232
+ ],
+ [
+ 128,
+ 235,
+ 243
+ ],
+ [
+ 128,
+ 253,
+ 287
+ ],
+ [
+ 129,
+ 0,
+ 15
+ ],
+ [
+ 129,
+ 39,
+ 45
+ ],
+ [
+ 129,
+ 103,
+ 109
+ ],
+ [
+ 129,
+ 162,
+ 167
+ ],
+ [
+ 129,
+ 253,
+ 287
+ ],
+ [
+ 130,
+ 0,
+ 12
+ ],
+ [
+ 130,
+ 39,
+ 45
+ ],
+ [
+ 130,
+ 95,
+ 109
+ ],
+ [
+ 130,
+ 161,
+ 167
+ ],
+ [
+ 130,
+ 253,
+ 287
+ ],
+ [
+ 131,
+ 0,
+ 12
+ ],
+ [
+ 131,
+ 39,
+ 45
+ ],
+ [
+ 131,
+ 58,
+ 79
+ ],
+ [
+ 131,
+ 93,
+ 108
+ ],
+ [
+ 131,
+ 160,
+ 166
+ ],
+ [
+ 131,
+ 253,
+ 288
+ ],
+ [
+ 132,
+ 0,
+ 15
+ ],
+ [
+ 132,
+ 39,
+ 45
+ ],
+ [
+ 132,
+ 57,
+ 82
+ ],
+ [
+ 132,
+ 93,
+ 108
+ ],
+ [
+ 132,
+ 138,
+ 151
+ ],
+ [
+ 132,
+ 153,
+ 165
+ ],
+ [
+ 132,
+ 253,
+ 288
+ ],
+ [
+ 133,
+ 0,
+ 16
+ ],
+ [
+ 133,
+ 39,
+ 45
+ ],
+ [
+ 133,
+ 56,
+ 83
+ ],
+ [
+ 133,
+ 93,
+ 107
+ ],
+ [
+ 133,
+ 138,
+ 164
+ ],
+ [
+ 133,
+ 253,
+ 288
+ ],
+ [
+ 134,
+ 0,
+ 20
+ ],
+ [
+ 134,
+ 39,
+ 45
+ ],
+ [
+ 134,
+ 56,
+ 83
+ ],
+ [
+ 134,
+ 93,
+ 107
+ ],
+ [
+ 134,
+ 137,
+ 163
+ ],
+ [
+ 134,
+ 253,
+ 288
+ ],
+ [
+ 135,
+ 0,
+ 21
+ ],
+ [
+ 135,
+ 39,
+ 45
+ ],
+ [
+ 135,
+ 57,
+ 82
+ ],
+ [
+ 135,
+ 93,
+ 106
+ ],
+ [
+ 135,
+ 137,
+ 163
+ ],
+ [
+ 135,
+ 253,
+ 288
+ ],
+ [
+ 136,
+ 0,
+ 22
+ ],
+ [
+ 136,
+ 39,
+ 45
+ ],
+ [
+ 136,
+ 58,
+ 70
+ ],
+ [
+ 136,
+ 72,
+ 76
+ ],
+ [
+ 136,
+ 78,
+ 78
+ ],
+ [
+ 136,
+ 81,
+ 81
+ ],
+ [
+ 136,
+ 95,
+ 104
+ ],
+ [
+ 136,
+ 138,
+ 162
+ ],
+ [
+ 136,
+ 253,
+ 288
+ ],
+ [
+ 137,
+ 0,
+ 22
+ ],
+ [
+ 137,
+ 39,
+ 45
+ ],
+ [
+ 137,
+ 139,
+ 161
+ ],
+ [
+ 137,
+ 253,
+ 288
+ ],
+ [
+ 138,
+ 0,
+ 22
+ ],
+ [
+ 138,
+ 39,
+ 45
+ ],
+ [
+ 138,
+ 140,
+ 158
+ ],
+ [
+ 138,
+ 253,
+ 288
+ ],
+ [
+ 139,
+ 0,
+ 22
+ ],
+ [
+ 139,
+ 39,
+ 45
+ ],
+ [
+ 139,
+ 149,
+ 157
+ ],
+ [
+ 139,
+ 253,
+ 288
+ ],
+ [
+ 140,
+ 0,
+ 22
+ ],
+ [
+ 140,
+ 39,
+ 45
+ ],
+ [
+ 140,
+ 149,
+ 157
+ ],
+ [
+ 140,
+ 253,
+ 288
+ ],
+ [
+ 141,
+ 0,
+ 22
+ ],
+ [
+ 141,
+ 39,
+ 45
+ ],
+ [
+ 141,
+ 148,
+ 157
+ ],
+ [
+ 141,
+ 253,
+ 288
+ ],
+ [
+ 142,
+ 0,
+ 22
+ ],
+ [
+ 142,
+ 39,
+ 45
+ ],
+ [
+ 142,
+ 132,
+ 133
+ ],
+ [
+ 142,
+ 135,
+ 157
+ ],
+ [
+ 142,
+ 159,
+ 159
+ ],
+ [
+ 142,
+ 184,
+ 185
+ ],
+ [
+ 142,
+ 253,
+ 288
+ ],
+ [
+ 143,
+ 0,
+ 22
+ ],
+ [
+ 143,
+ 39,
+ 45
+ ],
+ [
+ 143,
+ 131,
+ 187
+ ],
+ [
+ 143,
+ 253,
+ 288
+ ],
+ [
+ 144,
+ 0,
+ 22
+ ],
+ [
+ 144,
+ 39,
+ 45
+ ],
+ [
+ 144,
+ 130,
+ 187
+ ],
+ [
+ 144,
+ 253,
+ 288
+ ],
+ [
+ 145,
+ 0,
+ 22
+ ],
+ [
+ 145,
+ 39,
+ 45
+ ],
+ [
+ 145,
+ 130,
+ 186
+ ],
+ [
+ 145,
+ 253,
+ 288
+ ],
+ [
+ 146,
+ 0,
+ 22
+ ],
+ [
+ 146,
+ 39,
+ 44
+ ],
+ [
+ 146,
+ 131,
+ 161
+ ],
+ [
+ 146,
+ 172,
+ 172
+ ],
+ [
+ 146,
+ 253,
+ 288
+ ],
+ [
+ 147,
+ 0,
+ 22
+ ],
+ [
+ 147,
+ 39,
+ 44
+ ],
+ [
+ 147,
+ 131,
+ 151
+ ],
+ [
+ 147,
+ 253,
+ 288
+ ],
+ [
+ 148,
+ 0,
+ 22
+ ],
+ [
+ 148,
+ 39,
+ 45
+ ],
+ [
+ 148,
+ 131,
+ 151
+ ],
+ [
+ 148,
+ 253,
+ 287
+ ],
+ [
+ 149,
+ 0,
+ 22
+ ],
+ [
+ 149,
+ 39,
+ 45
+ ],
+ [
+ 149,
+ 131,
+ 151
+ ],
+ [
+ 149,
+ 253,
+ 288
+ ],
+ [
+ 150,
+ 0,
+ 22
+ ],
+ [
+ 150,
+ 39,
+ 45
+ ],
+ [
+ 150,
+ 131,
+ 151
+ ],
+ [
+ 150,
+ 253,
+ 287
+ ],
+ [
+ 151,
+ 0,
+ 22
+ ],
+ [
+ 151,
+ 39,
+ 45
+ ],
+ [
+ 151,
+ 131,
+ 151
+ ],
+ [
+ 151,
+ 253,
+ 288
+ ],
+ [
+ 152,
+ 0,
+ 22
+ ],
+ [
+ 152,
+ 39,
+ 45
+ ],
+ [
+ 152,
+ 131,
+ 151
+ ],
+ [
+ 152,
+ 253,
+ 287
+ ],
+ [
+ 153,
+ 0,
+ 22
+ ],
+ [
+ 153,
+ 39,
+ 45
+ ],
+ [
+ 153,
+ 62,
+ 62
+ ],
+ [
+ 153,
+ 82,
+ 82
+ ],
+ [
+ 153,
+ 102,
+ 102
+ ],
+ [
+ 153,
+ 121,
+ 121
+ ],
+ [
+ 153,
+ 131,
+ 151
+ ],
+ [
+ 153,
+ 253,
+ 288
+ ],
+ [
+ 154,
+ 0,
+ 287
+ ],
+ [
+ 155,
+ 0,
+ 287
+ ],
+ [
+ 156,
+ 0,
+ 286
+ ],
+ [
+ 157,
+ 0,
+ 20
+ ],
+ [
+ 157,
+ 41,
+ 43
+ ],
+ [
+ 157,
+ 132,
+ 132
+ ],
+ [
+ 157,
+ 138,
+ 138
+ ],
+ [
+ 157,
+ 142,
+ 143
+ ],
+ [
+ 157,
+ 257,
+ 258
+ ],
+ [
+ 157,
+ 262,
+ 266
+ ],
+ [
+ 157,
+ 270,
+ 270
+ ],
+ [
+ 157,
+ 273,
+ 273
+ ],
+ [
+ 157,
+ 276,
+ 277
+ ],
+ [
+ 157,
+ 281,
+ 283
+ ],
+ [
+ 157,
+ 285,
+ 285
+ ],
+ [
+ 158,
+ 0,
+ 7
+ ],
+ [
+ 159,
+ 0,
+ 7
+ ],
+ [
+ 160,
+ 0,
+ 7
+ ]
+ ]
+ },
+ "regions": [
+ {
+ "id": 0,
+ "name": "wall",
+ "color": "#000000"
+ },
+ {
+ "id": 1,
+ "name": "ours_home",
+ "color": "#ff0000"
+ },
+ {
+ "id": 2,
+ "name": "them_home",
+ "color": "#eeff00"
+ },
+ {
+ "id": 3,
+ "name": "ours_fluctuant",
+ "color": "#11ff00"
+ },
+ {
+ "id": 4,
+ "name": "them_fluctuant",
+ "color": "#006eff"
+ },
+ {
+ "id": 5,
+ "name": "ours_road_begin",
+ "color": "#e100ff"
+ },
+ {
+ "id": 6,
+ "name": "thems_road_begin",
+ "color": "#ff0095"
+ },
+ {
+ "id": 7,
+ "name": "ours_trapezoidal_highland",
+ "color": "#00d5ff"
+ },
+ {
+ "id": 8,
+ "name": "them_trapezoidal_highland",
+ "color": "#7300ff"
+ },
+ {
+ "id": 9,
+ "name": "ours_road_waypoint_1",
+ "color": "#0040ff"
+ },
+ {
+ "id": 10,
+ "name": "them_road_waypoint_1",
+ "color": "#00ff88"
+ },
+ {
+ "id": 13,
+ "name": "ours_road_to_fluctuant",
+ "color": "#00eeff"
+ },
+ {
+ "id": 14,
+ "name": "them_road_to_fluctuant",
+ "color": "#5900ff"
+ },
+ {
+ "id": 15,
+ "name": "ours_road_to_highland",
+ "color": "#ff00bb"
+ },
+ {
+ "id": 16,
+ "name": "them_road_to_highland",
+ "color": "#99ff00"
+ },
+ {
+ "id": 17,
+ "name": "ours_highland",
+ "color": "#ffd500"
+ },
+ {
+ "id": 18,
+ "name": "them_highland",
+ "color": "#ff7b00"
+ }
+ ],
+ "polygons": [
+ {
+ "id": 1,
+ "region_id": 1,
+ "order": 1,
+ "points": [
+ [
+ 74,
+ 116
+ ],
+ [
+ 108,
+ 105
+ ],
+ [
+ 98,
+ 88
+ ],
+ [
+ 99,
+ 71
+ ],
+ [
+ 54,
+ 51
+ ],
+ [
+ 35,
+ 51
+ ],
+ [
+ 4,
+ 52
+ ],
+ [
+ 3,
+ 126
+ ],
+ [
+ 16,
+ 153
+ ],
+ [
+ 18,
+ 154
+ ],
+ [
+ 18,
+ 155
+ ],
+ [
+ 43,
+ 155
+ ],
+ [
+ 42,
+ 117
+ ],
+ [
+ 74,
+ 116
+ ]
+ ]
+ },
+ {
+ "id": 2,
+ "region_id": 2,
+ "order": 2,
+ "points": [
+ [
+ 219,
+ 44
+ ],
+ [
+ 186,
+ 56
+ ],
+ [
+ 191,
+ 70
+ ],
+ [
+ 193,
+ 88
+ ],
+ [
+ 239,
+ 106
+ ],
+ [
+ 286,
+ 107
+ ],
+ [
+ 287,
+ 22
+ ],
+ [
+ 287,
+ 4
+ ],
+ [
+ 250,
+ 5
+ ],
+ [
+ 250,
+ 42
+ ],
+ [
+ 218,
+ 43
+ ]
+ ]
+ },
+ {
+ "id": 3,
+ "region_id": 3,
+ "order": 3,
+ "points": [
+ [
+ 56,
+ 134
+ ],
+ [
+ 56,
+ 155
+ ],
+ [
+ 81,
+ 155
+ ],
+ [
+ 83,
+ 155
+ ],
+ [
+ 83,
+ 133
+ ],
+ [
+ 56,
+ 134
+ ]
+ ]
+ },
+ {
+ "id": 4,
+ "region_id": 4,
+ "order": 4,
+ "points": [
+ [
+ 209,
+ 7
+ ],
+ [
+ 209,
+ 25
+ ],
+ [
+ 235,
+ 25
+ ],
+ [
+ 235,
+ 7
+ ],
+ [
+ 209,
+ 7
+ ]
+ ]
+ },
+ {
+ "id": 5,
+ "region_id": 5,
+ "order": 5,
+ "points": [
+ [
+ 73,
+ 116
+ ],
+ [
+ 106,
+ 105
+ ],
+ [
+ 114,
+ 118
+ ],
+ [
+ 104,
+ 133
+ ],
+ [
+ 80,
+ 133
+ ],
+ [
+ 74,
+ 116
+ ]
+ ]
+ },
+ {
+ "id": 6,
+ "region_id": 6,
+ "order": 6,
+ "points": [
+ [
+ 187,
+ 27
+ ],
+ [
+ 213,
+ 27
+ ],
+ [
+ 210,
+ 27
+ ],
+ [
+ 218,
+ 44
+ ],
+ [
+ 186,
+ 56
+ ],
+ [
+ 179,
+ 42
+ ],
+ [
+ 187,
+ 27
+ ]
+ ]
+ },
+ {
+ "id": 7,
+ "region_id": 7,
+ "order": 7,
+ "points": [
+ [
+ 35,
+ 6
+ ],
+ [
+ 34,
+ 50
+ ],
+ [
+ 56,
+ 51
+ ],
+ [
+ 98,
+ 70
+ ],
+ [
+ 135,
+ 22
+ ],
+ [
+ 137,
+ 16
+ ],
+ [
+ 149,
+ 13
+ ],
+ [
+ 147,
+ 6
+ ],
+ [
+ 35,
+ 7
+ ]
+ ]
+ },
+ {
+ "id": 8,
+ "region_id": 8,
+ "order": 8,
+ "points": [
+ [
+ 194,
+ 88
+ ],
+ [
+ 160,
+ 135
+ ],
+ [
+ 155,
+ 136
+ ],
+ [
+ 148,
+ 148
+ ],
+ [
+ 147,
+ 155
+ ],
+ [
+ 256,
+ 155
+ ],
+ [
+ 255,
+ 107
+ ],
+ [
+ 238,
+ 106
+ ],
+ [
+ 194,
+ 88
+ ]
+ ]
+ },
+ {
+ "id": 9,
+ "region_id": 9,
+ "order": 9,
+ "points": [
+ [
+ 74,
+ 117
+ ],
+ [
+ 42,
+ 117
+ ],
+ [
+ 42,
+ 133
+ ],
+ [
+ 80,
+ 133
+ ],
+ [
+ 74,
+ 117
+ ]
+ ]
+ },
+ {
+ "id": 10,
+ "region_id": 13,
+ "order": 10,
+ "points": [
+ [
+ 43,
+ 134
+ ],
+ [
+ 43,
+ 155
+ ],
+ [
+ 56,
+ 155
+ ],
+ [
+ 56,
+ 133
+ ],
+ [
+ 43,
+ 133
+ ]
+ ]
+ },
+ {
+ "id": 11,
+ "region_id": 14,
+ "order": 11,
+ "points": [
+ [
+ 235,
+ 25
+ ],
+ [
+ 235,
+ 7
+ ],
+ [
+ 249,
+ 6
+ ],
+ [
+ 248,
+ 27
+ ],
+ [
+ 235,
+ 27
+ ]
+ ]
+ },
+ {
+ "id": 12,
+ "region_id": 10,
+ "order": 12,
+ "points": [
+ [
+ 210,
+ 27
+ ],
+ [
+ 249,
+ 27
+ ],
+ [
+ 249,
+ 42
+ ],
+ [
+ 218,
+ 42
+ ],
+ [
+ 217,
+ 42
+ ],
+ [
+ 211,
+ 28
+ ]
+ ]
+ },
+ {
+ "id": 13,
+ "region_id": 15,
+ "order": 13,
+ "points": [
+ [
+ 83,
+ 133
+ ],
+ [
+ 140,
+ 134
+ ],
+ [
+ 153,
+ 135
+ ],
+ [
+ 147,
+ 146
+ ],
+ [
+ 139,
+ 154
+ ],
+ [
+ 83,
+ 154
+ ],
+ [
+ 83,
+ 133
+ ]
+ ]
+ },
+ {
+ "id": 14,
+ "region_id": 16,
+ "order": 14,
+ "points": [
+ [
+ 136,
+ 25
+ ],
+ [
+ 209,
+ 26
+ ],
+ [
+ 209,
+ 7
+ ],
+ [
+ 154,
+ 7
+ ],
+ [
+ 152,
+ 16
+ ],
+ [
+ 138,
+ 18
+ ],
+ [
+ 137,
+ 25
+ ]
+ ]
+ },
+ {
+ "id": 15,
+ "region_id": 17,
+ "order": 15,
+ "points": [
+ [
+ 154,
+ 27
+ ],
+ [
+ 154,
+ 68
+ ],
+ [
+ 147,
+ 62
+ ],
+ [
+ 136,
+ 59
+ ],
+ [
+ 126,
+ 69
+ ],
+ [
+ 126,
+ 81
+ ],
+ [
+ 137,
+ 91
+ ],
+ [
+ 138,
+ 132
+ ],
+ [
+ 107,
+ 132
+ ],
+ [
+ 108,
+ 127
+ ],
+ [
+ 117,
+ 121
+ ],
+ [
+ 116,
+ 116
+ ],
+ [
+ 107,
+ 104
+ ],
+ [
+ 107,
+ 58
+ ],
+ [
+ 132,
+ 26
+ ],
+ [
+ 154,
+ 26
+ ]
+ ]
+ },
+ {
+ "id": 16,
+ "region_id": 18,
+ "order": 16,
+ "points": [
+ [
+ 154,
+ 25
+ ],
+ [
+ 187,
+ 25
+ ],
+ [
+ 177,
+ 41
+ ],
+ [
+ 184,
+ 56
+ ],
+ [
+ 184,
+ 99
+ ],
+ [
+ 159,
+ 134
+ ],
+ [
+ 138,
+ 133
+ ],
+ [
+ 137,
+ 93
+ ],
+ [
+ 156,
+ 102
+ ],
+ [
+ 167,
+ 92
+ ],
+ [
+ 165,
+ 78
+ ],
+ [
+ 154,
+ 67
+ ],
+ [
+ 154,
+ 25
+ ]
+ ]
+ }
+ ],
+ "fills": [
+ {
+ "id": 1,
+ "region_id": 17,
+ "order": 17,
+ "runs": [
+ [
+ 132,
+ 109,
+ 137
+ ],
+ [
+ 133,
+ 111,
+ 137
+ ]
+ ]
+ },
+ {
+ "id": 2,
+ "region_id": 8,
+ "order": 18,
+ "runs": [
+ [
+ 104,
+ 234,
+ 234
+ ]
+ ]
+ },
+ {
+ "id": 3,
+ "region_id": 8,
+ "order": 19,
+ "runs": [
+ [
+ 103,
+ 232,
+ 232
+ ]
+ ]
+ },
+ {
+ "id": 4,
+ "region_id": 8,
+ "order": 20,
+ "runs": [
+ [
+ 102,
+ 229,
+ 229
+ ]
+ ]
+ },
+ {
+ "id": 5,
+ "region_id": 7,
+ "order": 21,
+ "runs": [
+ [
+ 68,
+ 93,
+ 94
+ ]
+ ]
+ },
+ {
+ "id": 6,
+ "region_id": 7,
+ "order": 22,
+ "runs": [
+ [
+ 67,
+ 91,
+ 91
+ ]
+ ]
+ },
+ {
+ "id": 7,
+ "region_id": 7,
+ "order": 23,
+ "runs": [
+ [
+ 66,
+ 89,
+ 89
+ ]
+ ]
+ },
+ {
+ "id": 8,
+ "region_id": 7,
+ "order": 24,
+ "runs": [
+ [
+ 65,
+ 87,
+ 87
+ ]
+ ]
+ },
+ {
+ "id": 9,
+ "region_id": 7,
+ "order": 25,
+ "runs": [
+ [
+ 64,
+ 84,
+ 85
+ ]
+ ]
+ },
+ {
+ "id": 10,
+ "region_id": 7,
+ "order": 26,
+ "runs": [
+ [
+ 63,
+ 82,
+ 83
+ ]
+ ]
+ },
+ {
+ "id": 11,
+ "region_id": 7,
+ "order": 27,
+ "runs": [
+ [
+ 62,
+ 80,
+ 80
+ ]
+ ]
+ },
+ {
+ "id": 12,
+ "region_id": 7,
+ "order": 28,
+ "runs": [
+ [
+ 61,
+ 78,
+ 78
+ ]
+ ]
+ },
+ {
+ "id": 13,
+ "region_id": 7,
+ "order": 29,
+ "runs": [
+ [
+ 60,
+ 75,
+ 76
+ ]
+ ]
+ },
+ {
+ "id": 14,
+ "region_id": 7,
+ "order": 30,
+ "runs": [
+ [
+ 59,
+ 73,
+ 74
+ ]
+ ]
+ },
+ {
+ "id": 15,
+ "region_id": 7,
+ "order": 31,
+ "runs": [
+ [
+ 58,
+ 71,
+ 72
+ ]
+ ]
+ },
+ {
+ "id": 16,
+ "region_id": 7,
+ "order": 32,
+ "runs": [
+ [
+ 57,
+ 69,
+ 69
+ ]
+ ]
+ },
+ {
+ "id": 17,
+ "region_id": 7,
+ "order": 33,
+ "runs": [
+ [
+ 56,
+ 66,
+ 67
+ ]
+ ]
+ },
+ {
+ "id": 18,
+ "region_id": 7,
+ "order": 34,
+ "runs": [
+ [
+ 55,
+ 64,
+ 65
+ ]
+ ]
+ },
+ {
+ "id": 19,
+ "region_id": 7,
+ "order": 35,
+ "runs": [
+ [
+ 54,
+ 62,
+ 63
+ ]
+ ]
+ },
+ {
+ "id": 20,
+ "region_id": 7,
+ "order": 36,
+ "runs": [
+ [
+ 53,
+ 60,
+ 61
+ ]
+ ]
+ }
+ ]
+}
\ No newline at end of file
diff --git a/maps/rmuc.region.png b/maps/rmuc.region.png
new file mode 100644
index 0000000..3c430c9
Binary files /dev/null and b/maps/rmuc.region.png differ
diff --git a/maps/rmuc.yaml b/maps/rmuc.yaml
index e69de29..e3c3393 100644
--- a/maps/rmuc.yaml
+++ b/maps/rmuc.yaml
@@ -0,0 +1,7 @@
+image: rmuc.png
+mode: trinary
+resolution: 0.100000
+origin: [-4.300000, -8.000000, 0.000000]
+negate: 0
+occupied_thresh: 0.650000
+free_thresh: 0.196000
diff --git a/maps/train_map.lua b/maps/train_map.lua
new file mode 100644
index 0000000..e246136
--- /dev/null
+++ b/maps/train_map.lua
@@ -0,0 +1,152 @@
+-- Generated by tools/region-editor
+return {
+ width = 434,
+ height = 131,
+ resolution = 0.1,
+ origin = {
+ x = 0,
+ y = 0,
+ },
+ names = {
+ [0] = "wall",
+ [1] = "ours_home",
+ [2] = "road_region_begin",
+ [3] = "road_region_1",
+ [4] = "road_region_2",
+ [5] = "road_region_final",
+ [6] = "ours_highland",
+ },
+ rows = {
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 3, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 6, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 4, 0, 0, 0, 0, 0, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1, 1, 1, 1, 1, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 5, 5, 5, 5, 5, 5, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ { 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 },
+ },
+}
diff --git a/maps/train_map.png b/maps/train_map.png
new file mode 100644
index 0000000..4492aaa
Binary files /dev/null and b/maps/train_map.png differ
diff --git a/maps/train_map.region.json b/maps/train_map.region.json
new file mode 100644
index 0000000..c657af9
--- /dev/null
+++ b/maps/train_map.region.json
@@ -0,0 +1,6327 @@
+{
+ "version": 1,
+ "map": {
+ "name": "train_map",
+ "image": "train_map.png",
+ "width": 434,
+ "height": 131,
+ "resolution": 0.1,
+ "origin": {
+ "x": 0,
+ "y": 0
+ },
+ "protected_black_runs": [
+ [
+ 0,
+ 93,
+ 95
+ ],
+ [
+ 1,
+ 67,
+ 67
+ ],
+ [
+ 1,
+ 85,
+ 88
+ ],
+ [
+ 1,
+ 91,
+ 96
+ ],
+ [
+ 1,
+ 107,
+ 137
+ ],
+ [
+ 1,
+ 139,
+ 141
+ ],
+ [
+ 2,
+ 66,
+ 68
+ ],
+ [
+ 2,
+ 83,
+ 97
+ ],
+ [
+ 2,
+ 105,
+ 172
+ ],
+ [
+ 2,
+ 174,
+ 174
+ ],
+ [
+ 2,
+ 181,
+ 181
+ ],
+ [
+ 2,
+ 186,
+ 186
+ ],
+ [
+ 2,
+ 253,
+ 253
+ ],
+ [
+ 2,
+ 255,
+ 255
+ ],
+ [
+ 3,
+ 65,
+ 69
+ ],
+ [
+ 3,
+ 82,
+ 98
+ ],
+ [
+ 3,
+ 104,
+ 216
+ ],
+ [
+ 3,
+ 249,
+ 259
+ ],
+ [
+ 4,
+ 65,
+ 68
+ ],
+ [
+ 4,
+ 83,
+ 97
+ ],
+ [
+ 4,
+ 105,
+ 263
+ ],
+ [
+ 4,
+ 265,
+ 268
+ ],
+ [
+ 5,
+ 66,
+ 67
+ ],
+ [
+ 5,
+ 86,
+ 87
+ ],
+ [
+ 5,
+ 91,
+ 91
+ ],
+ [
+ 5,
+ 93,
+ 94
+ ],
+ [
+ 5,
+ 106,
+ 295
+ ],
+ [
+ 6,
+ 106,
+ 306
+ ],
+ [
+ 6,
+ 308,
+ 313
+ ],
+ [
+ 7,
+ 106,
+ 114
+ ],
+ [
+ 7,
+ 121,
+ 130
+ ],
+ [
+ 7,
+ 132,
+ 315
+ ],
+ [
+ 7,
+ 319,
+ 319
+ ],
+ [
+ 7,
+ 325,
+ 325
+ ],
+ [
+ 8,
+ 66,
+ 67
+ ],
+ [
+ 8,
+ 106,
+ 115
+ ],
+ [
+ 8,
+ 121,
+ 158
+ ],
+ [
+ 8,
+ 164,
+ 168
+ ],
+ [
+ 8,
+ 171,
+ 252
+ ],
+ [
+ 8,
+ 256,
+ 316
+ ],
+ [
+ 8,
+ 318,
+ 320
+ ],
+ [
+ 8,
+ 324,
+ 326
+ ],
+ [
+ 9,
+ 65,
+ 68
+ ],
+ [
+ 9,
+ 106,
+ 108
+ ],
+ [
+ 9,
+ 112,
+ 116
+ ],
+ [
+ 9,
+ 121,
+ 131
+ ],
+ [
+ 9,
+ 133,
+ 135
+ ],
+ [
+ 9,
+ 138,
+ 141
+ ],
+ [
+ 9,
+ 143,
+ 157
+ ],
+ [
+ 9,
+ 159,
+ 161
+ ],
+ [
+ 9,
+ 165,
+ 167
+ ],
+ [
+ 9,
+ 172,
+ 248
+ ],
+ [
+ 9,
+ 255,
+ 316
+ ],
+ [
+ 9,
+ 319,
+ 319
+ ],
+ [
+ 9,
+ 323,
+ 327
+ ],
+ [
+ 10,
+ 65,
+ 68
+ ],
+ [
+ 10,
+ 107,
+ 109
+ ],
+ [
+ 10,
+ 112,
+ 115
+ ],
+ [
+ 10,
+ 121,
+ 130
+ ],
+ [
+ 10,
+ 134,
+ 134
+ ],
+ [
+ 10,
+ 139,
+ 141
+ ],
+ [
+ 10,
+ 145,
+ 151
+ ],
+ [
+ 10,
+ 158,
+ 162
+ ],
+ [
+ 10,
+ 171,
+ 186
+ ],
+ [
+ 10,
+ 206,
+ 234
+ ],
+ [
+ 10,
+ 236,
+ 248
+ ],
+ [
+ 10,
+ 255,
+ 260
+ ],
+ [
+ 10,
+ 269,
+ 315
+ ],
+ [
+ 10,
+ 323,
+ 327
+ ],
+ [
+ 11,
+ 66,
+ 68
+ ],
+ [
+ 11,
+ 106,
+ 115
+ ],
+ [
+ 11,
+ 120,
+ 131
+ ],
+ [
+ 11,
+ 135,
+ 143
+ ],
+ [
+ 11,
+ 145,
+ 151
+ ],
+ [
+ 11,
+ 157,
+ 162
+ ],
+ [
+ 11,
+ 170,
+ 185
+ ],
+ [
+ 11,
+ 234,
+ 234
+ ],
+ [
+ 11,
+ 237,
+ 247
+ ],
+ [
+ 11,
+ 255,
+ 261
+ ],
+ [
+ 11,
+ 271,
+ 283
+ ],
+ [
+ 11,
+ 293,
+ 300
+ ],
+ [
+ 11,
+ 305,
+ 306
+ ],
+ [
+ 11,
+ 311,
+ 314
+ ],
+ [
+ 11,
+ 324,
+ 327
+ ],
+ [
+ 12,
+ 66,
+ 68
+ ],
+ [
+ 12,
+ 106,
+ 109
+ ],
+ [
+ 12,
+ 111,
+ 116
+ ],
+ [
+ 12,
+ 119,
+ 132
+ ],
+ [
+ 12,
+ 134,
+ 151
+ ],
+ [
+ 12,
+ 158,
+ 163
+ ],
+ [
+ 12,
+ 169,
+ 185
+ ],
+ [
+ 12,
+ 242,
+ 246
+ ],
+ [
+ 12,
+ 255,
+ 262
+ ],
+ [
+ 12,
+ 272,
+ 282
+ ],
+ [
+ 12,
+ 294,
+ 300
+ ],
+ [
+ 12,
+ 312,
+ 313
+ ],
+ [
+ 12,
+ 324,
+ 327
+ ],
+ [
+ 13,
+ 65,
+ 68
+ ],
+ [
+ 13,
+ 107,
+ 108
+ ],
+ [
+ 13,
+ 111,
+ 116
+ ],
+ [
+ 13,
+ 119,
+ 131
+ ],
+ [
+ 13,
+ 133,
+ 151
+ ],
+ [
+ 13,
+ 160,
+ 164
+ ],
+ [
+ 13,
+ 169,
+ 185
+ ],
+ [
+ 13,
+ 243,
+ 245
+ ],
+ [
+ 13,
+ 255,
+ 262
+ ],
+ [
+ 13,
+ 272,
+ 281
+ ],
+ [
+ 13,
+ 294,
+ 299
+ ],
+ [
+ 13,
+ 324,
+ 327
+ ],
+ [
+ 14,
+ 66,
+ 67
+ ],
+ [
+ 14,
+ 108,
+ 109
+ ],
+ [
+ 14,
+ 111,
+ 116
+ ],
+ [
+ 14,
+ 119,
+ 130
+ ],
+ [
+ 14,
+ 134,
+ 151
+ ],
+ [
+ 14,
+ 160,
+ 163
+ ],
+ [
+ 14,
+ 169,
+ 185
+ ],
+ [
+ 14,
+ 243,
+ 245
+ ],
+ [
+ 14,
+ 255,
+ 262
+ ],
+ [
+ 14,
+ 273,
+ 280
+ ],
+ [
+ 14,
+ 294,
+ 298
+ ],
+ [
+ 14,
+ 325,
+ 326
+ ],
+ [
+ 14,
+ 336,
+ 336
+ ],
+ [
+ 15,
+ 107,
+ 116
+ ],
+ [
+ 15,
+ 119,
+ 129
+ ],
+ [
+ 15,
+ 134,
+ 150
+ ],
+ [
+ 15,
+ 159,
+ 164
+ ],
+ [
+ 15,
+ 169,
+ 185
+ ],
+ [
+ 15,
+ 243,
+ 245
+ ],
+ [
+ 15,
+ 256,
+ 262
+ ],
+ [
+ 15,
+ 278,
+ 279
+ ],
+ [
+ 15,
+ 294,
+ 298
+ ],
+ [
+ 15,
+ 335,
+ 337
+ ],
+ [
+ 15,
+ 348,
+ 348
+ ],
+ [
+ 16,
+ 106,
+ 116
+ ],
+ [
+ 16,
+ 119,
+ 127
+ ],
+ [
+ 16,
+ 134,
+ 141
+ ],
+ [
+ 16,
+ 144,
+ 149
+ ],
+ [
+ 16,
+ 159,
+ 165
+ ],
+ [
+ 16,
+ 169,
+ 175
+ ],
+ [
+ 16,
+ 178,
+ 185
+ ],
+ [
+ 16,
+ 244,
+ 246
+ ],
+ [
+ 16,
+ 256,
+ 262
+ ],
+ [
+ 16,
+ 295,
+ 297
+ ],
+ [
+ 16,
+ 335,
+ 337
+ ],
+ [
+ 16,
+ 339,
+ 340
+ ],
+ [
+ 16,
+ 347,
+ 349
+ ],
+ [
+ 17,
+ 106,
+ 116
+ ],
+ [
+ 17,
+ 118,
+ 123
+ ],
+ [
+ 17,
+ 134,
+ 139
+ ],
+ [
+ 17,
+ 145,
+ 152
+ ],
+ [
+ 17,
+ 158,
+ 168
+ ],
+ [
+ 17,
+ 170,
+ 185
+ ],
+ [
+ 17,
+ 243,
+ 245
+ ],
+ [
+ 17,
+ 256,
+ 263
+ ],
+ [
+ 17,
+ 296,
+ 296
+ ],
+ [
+ 17,
+ 335,
+ 341
+ ],
+ [
+ 17,
+ 346,
+ 349
+ ],
+ [
+ 18,
+ 107,
+ 110
+ ],
+ [
+ 18,
+ 112,
+ 117
+ ],
+ [
+ 18,
+ 119,
+ 123
+ ],
+ [
+ 18,
+ 136,
+ 139
+ ],
+ [
+ 18,
+ 144,
+ 184
+ ],
+ [
+ 18,
+ 243,
+ 245
+ ],
+ [
+ 18,
+ 255,
+ 263
+ ],
+ [
+ 18,
+ 334,
+ 341
+ ],
+ [
+ 18,
+ 346,
+ 349
+ ],
+ [
+ 19,
+ 108,
+ 109
+ ],
+ [
+ 19,
+ 112,
+ 123
+ ],
+ [
+ 19,
+ 137,
+ 137
+ ],
+ [
+ 19,
+ 145,
+ 184
+ ],
+ [
+ 19,
+ 243,
+ 245
+ ],
+ [
+ 19,
+ 255,
+ 262
+ ],
+ [
+ 19,
+ 334,
+ 341
+ ],
+ [
+ 19,
+ 347,
+ 348
+ ],
+ [
+ 20,
+ 112,
+ 123
+ ],
+ [
+ 20,
+ 144,
+ 184
+ ],
+ [
+ 20,
+ 243,
+ 245
+ ],
+ [
+ 20,
+ 256,
+ 258
+ ],
+ [
+ 20,
+ 260,
+ 261
+ ],
+ [
+ 20,
+ 264,
+ 265
+ ],
+ [
+ 20,
+ 286,
+ 286
+ ],
+ [
+ 20,
+ 334,
+ 341
+ ],
+ [
+ 21,
+ 107,
+ 109
+ ],
+ [
+ 21,
+ 112,
+ 123
+ ],
+ [
+ 21,
+ 144,
+ 184
+ ],
+ [
+ 21,
+ 243,
+ 245
+ ],
+ [
+ 21,
+ 257,
+ 257
+ ],
+ [
+ 21,
+ 263,
+ 266
+ ],
+ [
+ 21,
+ 285,
+ 290
+ ],
+ [
+ 21,
+ 334,
+ 341
+ ],
+ [
+ 22,
+ 106,
+ 110
+ ],
+ [
+ 22,
+ 112,
+ 123
+ ],
+ [
+ 22,
+ 144,
+ 167
+ ],
+ [
+ 22,
+ 172,
+ 184
+ ],
+ [
+ 22,
+ 243,
+ 245
+ ],
+ [
+ 22,
+ 262,
+ 267
+ ],
+ [
+ 22,
+ 285,
+ 291
+ ],
+ [
+ 22,
+ 334,
+ 338
+ ],
+ [
+ 22,
+ 340,
+ 340
+ ],
+ [
+ 23,
+ 107,
+ 110
+ ],
+ [
+ 23,
+ 112,
+ 123
+ ],
+ [
+ 23,
+ 144,
+ 151
+ ],
+ [
+ 23,
+ 156,
+ 163
+ ],
+ [
+ 23,
+ 176,
+ 178
+ ],
+ [
+ 23,
+ 180,
+ 180
+ ],
+ [
+ 23,
+ 243,
+ 245
+ ],
+ [
+ 23,
+ 262,
+ 267
+ ],
+ [
+ 23,
+ 285,
+ 291
+ ],
+ [
+ 23,
+ 335,
+ 338
+ ],
+ [
+ 24,
+ 108,
+ 109
+ ],
+ [
+ 24,
+ 113,
+ 117
+ ],
+ [
+ 24,
+ 119,
+ 123
+ ],
+ [
+ 24,
+ 156,
+ 163
+ ],
+ [
+ 24,
+ 176,
+ 178
+ ],
+ [
+ 24,
+ 243,
+ 245
+ ],
+ [
+ 24,
+ 255,
+ 257
+ ],
+ [
+ 24,
+ 261,
+ 267
+ ],
+ [
+ 24,
+ 286,
+ 286
+ ],
+ [
+ 24,
+ 288,
+ 291
+ ],
+ [
+ 24,
+ 335,
+ 338
+ ],
+ [
+ 25,
+ 112,
+ 124
+ ],
+ [
+ 25,
+ 156,
+ 162
+ ],
+ [
+ 25,
+ 176,
+ 178
+ ],
+ [
+ 25,
+ 243,
+ 245
+ ],
+ [
+ 25,
+ 254,
+ 258
+ ],
+ [
+ 25,
+ 261,
+ 267
+ ],
+ [
+ 25,
+ 289,
+ 290
+ ],
+ [
+ 25,
+ 335,
+ 338
+ ],
+ [
+ 26,
+ 23,
+ 23
+ ],
+ [
+ 26,
+ 112,
+ 123
+ ],
+ [
+ 26,
+ 157,
+ 163
+ ],
+ [
+ 26,
+ 165,
+ 168
+ ],
+ [
+ 26,
+ 171,
+ 171
+ ],
+ [
+ 26,
+ 173,
+ 173
+ ],
+ [
+ 26,
+ 176,
+ 178
+ ],
+ [
+ 26,
+ 216,
+ 217
+ ],
+ [
+ 26,
+ 243,
+ 245
+ ],
+ [
+ 26,
+ 255,
+ 258
+ ],
+ [
+ 26,
+ 261,
+ 267
+ ],
+ [
+ 26,
+ 335,
+ 337
+ ],
+ [
+ 27,
+ 22,
+ 24
+ ],
+ [
+ 27,
+ 91,
+ 91
+ ],
+ [
+ 27,
+ 113,
+ 123
+ ],
+ [
+ 27,
+ 156,
+ 178
+ ],
+ [
+ 27,
+ 200,
+ 222
+ ],
+ [
+ 27,
+ 224,
+ 228
+ ],
+ [
+ 27,
+ 230,
+ 230
+ ],
+ [
+ 27,
+ 243,
+ 245
+ ],
+ [
+ 27,
+ 255,
+ 258
+ ],
+ [
+ 27,
+ 261,
+ 267
+ ],
+ [
+ 27,
+ 335,
+ 337
+ ],
+ [
+ 28,
+ 21,
+ 25
+ ],
+ [
+ 28,
+ 83,
+ 84
+ ],
+ [
+ 28,
+ 90,
+ 92
+ ],
+ [
+ 28,
+ 113,
+ 124
+ ],
+ [
+ 28,
+ 156,
+ 178
+ ],
+ [
+ 28,
+ 199,
+ 231
+ ],
+ [
+ 28,
+ 243,
+ 245
+ ],
+ [
+ 28,
+ 255,
+ 258
+ ],
+ [
+ 28,
+ 261,
+ 268
+ ],
+ [
+ 28,
+ 334,
+ 338
+ ],
+ [
+ 29,
+ 21,
+ 25
+ ],
+ [
+ 29,
+ 82,
+ 85
+ ],
+ [
+ 29,
+ 90,
+ 93
+ ],
+ [
+ 29,
+ 113,
+ 124
+ ],
+ [
+ 29,
+ 156,
+ 178
+ ],
+ [
+ 29,
+ 199,
+ 231
+ ],
+ [
+ 29,
+ 243,
+ 245
+ ],
+ [
+ 29,
+ 255,
+ 258
+ ],
+ [
+ 29,
+ 262,
+ 269
+ ],
+ [
+ 29,
+ 335,
+ 337
+ ],
+ [
+ 30,
+ 21,
+ 25
+ ],
+ [
+ 30,
+ 83,
+ 84
+ ],
+ [
+ 30,
+ 91,
+ 92
+ ],
+ [
+ 30,
+ 113,
+ 124
+ ],
+ [
+ 30,
+ 157,
+ 178
+ ],
+ [
+ 30,
+ 199,
+ 202
+ ],
+ [
+ 30,
+ 208,
+ 231
+ ],
+ [
+ 30,
+ 243,
+ 245
+ ],
+ [
+ 30,
+ 255,
+ 258
+ ],
+ [
+ 30,
+ 262,
+ 269
+ ],
+ [
+ 30,
+ 336,
+ 336
+ ],
+ [
+ 31,
+ 21,
+ 25
+ ],
+ [
+ 31,
+ 113,
+ 124
+ ],
+ [
+ 31,
+ 157,
+ 166
+ ],
+ [
+ 31,
+ 199,
+ 201
+ ],
+ [
+ 31,
+ 243,
+ 245
+ ],
+ [
+ 31,
+ 255,
+ 258
+ ],
+ [
+ 31,
+ 262,
+ 269
+ ],
+ [
+ 31,
+ 276,
+ 276
+ ],
+ [
+ 31,
+ 288,
+ 288
+ ],
+ [
+ 32,
+ 21,
+ 24
+ ],
+ [
+ 32,
+ 113,
+ 124
+ ],
+ [
+ 32,
+ 158,
+ 165
+ ],
+ [
+ 32,
+ 199,
+ 201
+ ],
+ [
+ 32,
+ 243,
+ 245
+ ],
+ [
+ 32,
+ 255,
+ 257
+ ],
+ [
+ 32,
+ 262,
+ 269
+ ],
+ [
+ 32,
+ 275,
+ 277
+ ],
+ [
+ 32,
+ 287,
+ 289
+ ],
+ [
+ 33,
+ 21,
+ 25
+ ],
+ [
+ 33,
+ 60,
+ 60
+ ],
+ [
+ 33,
+ 113,
+ 124
+ ],
+ [
+ 33,
+ 160,
+ 164
+ ],
+ [
+ 33,
+ 199,
+ 201
+ ],
+ [
+ 33,
+ 243,
+ 245
+ ],
+ [
+ 33,
+ 255,
+ 257
+ ],
+ [
+ 33,
+ 263,
+ 269
+ ],
+ [
+ 33,
+ 274,
+ 278
+ ],
+ [
+ 33,
+ 287,
+ 289
+ ],
+ [
+ 34,
+ 21,
+ 25
+ ],
+ [
+ 34,
+ 59,
+ 61
+ ],
+ [
+ 34,
+ 113,
+ 124
+ ],
+ [
+ 34,
+ 159,
+ 163
+ ],
+ [
+ 34,
+ 198,
+ 201
+ ],
+ [
+ 34,
+ 243,
+ 245
+ ],
+ [
+ 34,
+ 255,
+ 260
+ ],
+ [
+ 34,
+ 264,
+ 269
+ ],
+ [
+ 34,
+ 274,
+ 278
+ ],
+ [
+ 34,
+ 288,
+ 291
+ ],
+ [
+ 35,
+ 21,
+ 25
+ ],
+ [
+ 35,
+ 58,
+ 62
+ ],
+ [
+ 35,
+ 113,
+ 123
+ ],
+ [
+ 35,
+ 158,
+ 163
+ ],
+ [
+ 35,
+ 198,
+ 201
+ ],
+ [
+ 35,
+ 243,
+ 245
+ ],
+ [
+ 35,
+ 254,
+ 261
+ ],
+ [
+ 35,
+ 265,
+ 269
+ ],
+ [
+ 35,
+ 274,
+ 278
+ ],
+ [
+ 35,
+ 288,
+ 292
+ ],
+ [
+ 36,
+ 21,
+ 24
+ ],
+ [
+ 36,
+ 59,
+ 61
+ ],
+ [
+ 36,
+ 112,
+ 123
+ ],
+ [
+ 36,
+ 157,
+ 162
+ ],
+ [
+ 36,
+ 198,
+ 201
+ ],
+ [
+ 36,
+ 243,
+ 245
+ ],
+ [
+ 36,
+ 255,
+ 262
+ ],
+ [
+ 36,
+ 266,
+ 270
+ ],
+ [
+ 36,
+ 274,
+ 278
+ ],
+ [
+ 36,
+ 287,
+ 292
+ ],
+ [
+ 37,
+ 22,
+ 23
+ ],
+ [
+ 37,
+ 60,
+ 60
+ ],
+ [
+ 37,
+ 112,
+ 123
+ ],
+ [
+ 37,
+ 154,
+ 162
+ ],
+ [
+ 37,
+ 198,
+ 202
+ ],
+ [
+ 37,
+ 243,
+ 245
+ ],
+ [
+ 37,
+ 254,
+ 263
+ ],
+ [
+ 37,
+ 268,
+ 270
+ ],
+ [
+ 37,
+ 274,
+ 277
+ ],
+ [
+ 37,
+ 288,
+ 291
+ ],
+ [
+ 38,
+ 105,
+ 110
+ ],
+ [
+ 38,
+ 112,
+ 124
+ ],
+ [
+ 38,
+ 152,
+ 162
+ ],
+ [
+ 38,
+ 199,
+ 201
+ ],
+ [
+ 38,
+ 243,
+ 245
+ ],
+ [
+ 38,
+ 253,
+ 264
+ ],
+ [
+ 38,
+ 269,
+ 269
+ ],
+ [
+ 38,
+ 275,
+ 276
+ ],
+ [
+ 39,
+ 104,
+ 124
+ ],
+ [
+ 39,
+ 150,
+ 162
+ ],
+ [
+ 39,
+ 199,
+ 201
+ ],
+ [
+ 39,
+ 216,
+ 245
+ ],
+ [
+ 39,
+ 253,
+ 266
+ ],
+ [
+ 40,
+ 103,
+ 123
+ ],
+ [
+ 40,
+ 151,
+ 163
+ ],
+ [
+ 40,
+ 198,
+ 202
+ ],
+ [
+ 40,
+ 216,
+ 244
+ ],
+ [
+ 40,
+ 252,
+ 273
+ ],
+ [
+ 40,
+ 288,
+ 288
+ ],
+ [
+ 41,
+ 104,
+ 122
+ ],
+ [
+ 41,
+ 151,
+ 162
+ ],
+ [
+ 41,
+ 198,
+ 201
+ ],
+ [
+ 41,
+ 251,
+ 260
+ ],
+ [
+ 41,
+ 262,
+ 274
+ ],
+ [
+ 41,
+ 287,
+ 289
+ ],
+ [
+ 42,
+ 89,
+ 91
+ ],
+ [
+ 42,
+ 105,
+ 120
+ ],
+ [
+ 42,
+ 151,
+ 162
+ ],
+ [
+ 42,
+ 197,
+ 203
+ ],
+ [
+ 42,
+ 249,
+ 260
+ ],
+ [
+ 42,
+ 263,
+ 275
+ ],
+ [
+ 42,
+ 286,
+ 288
+ ],
+ [
+ 42,
+ 336,
+ 336
+ ],
+ [
+ 43,
+ 88,
+ 92
+ ],
+ [
+ 43,
+ 105,
+ 105
+ ],
+ [
+ 43,
+ 111,
+ 120
+ ],
+ [
+ 43,
+ 152,
+ 162
+ ],
+ [
+ 43,
+ 198,
+ 208
+ ],
+ [
+ 43,
+ 248,
+ 274
+ ],
+ [
+ 43,
+ 287,
+ 287
+ ],
+ [
+ 43,
+ 335,
+ 337
+ ],
+ [
+ 44,
+ 88,
+ 93
+ ],
+ [
+ 44,
+ 103,
+ 120
+ ],
+ [
+ 44,
+ 152,
+ 163
+ ],
+ [
+ 44,
+ 199,
+ 209
+ ],
+ [
+ 44,
+ 249,
+ 273
+ ],
+ [
+ 44,
+ 334,
+ 337
+ ],
+ [
+ 45,
+ 88,
+ 93
+ ],
+ [
+ 45,
+ 102,
+ 119
+ ],
+ [
+ 45,
+ 152,
+ 163
+ ],
+ [
+ 45,
+ 195,
+ 196
+ ],
+ [
+ 45,
+ 198,
+ 198
+ ],
+ [
+ 45,
+ 200,
+ 211
+ ],
+ [
+ 45,
+ 249,
+ 264
+ ],
+ [
+ 45,
+ 266,
+ 270
+ ],
+ [
+ 45,
+ 334,
+ 337
+ ],
+ [
+ 46,
+ 89,
+ 94
+ ],
+ [
+ 46,
+ 103,
+ 119
+ ],
+ [
+ 46,
+ 152,
+ 163
+ ],
+ [
+ 46,
+ 195,
+ 212
+ ],
+ [
+ 46,
+ 248,
+ 265
+ ],
+ [
+ 46,
+ 267,
+ 270
+ ],
+ [
+ 46,
+ 335,
+ 337
+ ],
+ [
+ 47,
+ 89,
+ 94
+ ],
+ [
+ 47,
+ 104,
+ 119
+ ],
+ [
+ 47,
+ 153,
+ 164
+ ],
+ [
+ 47,
+ 195,
+ 202
+ ],
+ [
+ 47,
+ 204,
+ 214
+ ],
+ [
+ 47,
+ 248,
+ 265
+ ],
+ [
+ 47,
+ 268,
+ 269
+ ],
+ [
+ 47,
+ 335,
+ 337
+ ],
+ [
+ 48,
+ 89,
+ 94
+ ],
+ [
+ 48,
+ 105,
+ 119
+ ],
+ [
+ 48,
+ 123,
+ 123
+ ],
+ [
+ 48,
+ 153,
+ 164
+ ],
+ [
+ 48,
+ 196,
+ 200
+ ],
+ [
+ 48,
+ 205,
+ 205
+ ],
+ [
+ 48,
+ 209,
+ 215
+ ],
+ [
+ 48,
+ 248,
+ 266
+ ],
+ [
+ 48,
+ 335,
+ 337
+ ],
+ [
+ 49,
+ 89,
+ 94
+ ],
+ [
+ 49,
+ 107,
+ 119
+ ],
+ [
+ 49,
+ 121,
+ 124
+ ],
+ [
+ 49,
+ 153,
+ 164
+ ],
+ [
+ 49,
+ 196,
+ 199
+ ],
+ [
+ 49,
+ 210,
+ 216
+ ],
+ [
+ 49,
+ 237,
+ 239
+ ],
+ [
+ 49,
+ 248,
+ 267
+ ],
+ [
+ 49,
+ 334,
+ 338
+ ],
+ [
+ 50,
+ 2,
+ 2
+ ],
+ [
+ 50,
+ 89,
+ 94
+ ],
+ [
+ 50,
+ 108,
+ 125
+ ],
+ [
+ 50,
+ 153,
+ 164
+ ],
+ [
+ 50,
+ 196,
+ 200
+ ],
+ [
+ 50,
+ 211,
+ 219
+ ],
+ [
+ 50,
+ 236,
+ 240
+ ],
+ [
+ 50,
+ 242,
+ 243
+ ],
+ [
+ 50,
+ 249,
+ 268
+ ],
+ [
+ 50,
+ 335,
+ 337
+ ],
+ [
+ 51,
+ 1,
+ 3
+ ],
+ [
+ 51,
+ 89,
+ 94
+ ],
+ [
+ 51,
+ 109,
+ 124
+ ],
+ [
+ 51,
+ 154,
+ 164
+ ],
+ [
+ 51,
+ 196,
+ 200
+ ],
+ [
+ 51,
+ 212,
+ 220
+ ],
+ [
+ 51,
+ 226,
+ 228
+ ],
+ [
+ 51,
+ 235,
+ 244
+ ],
+ [
+ 51,
+ 248,
+ 267
+ ],
+ [
+ 51,
+ 334,
+ 337
+ ],
+ [
+ 52,
+ 1,
+ 3
+ ],
+ [
+ 52,
+ 88,
+ 94
+ ],
+ [
+ 52,
+ 110,
+ 124
+ ],
+ [
+ 52,
+ 154,
+ 164
+ ],
+ [
+ 52,
+ 196,
+ 200
+ ],
+ [
+ 52,
+ 204,
+ 205
+ ],
+ [
+ 52,
+ 215,
+ 227
+ ],
+ [
+ 52,
+ 234,
+ 245
+ ],
+ [
+ 52,
+ 247,
+ 266
+ ],
+ [
+ 52,
+ 334,
+ 337
+ ],
+ [
+ 53,
+ 0,
+ 4
+ ],
+ [
+ 53,
+ 89,
+ 93
+ ],
+ [
+ 53,
+ 110,
+ 124
+ ],
+ [
+ 53,
+ 155,
+ 165
+ ],
+ [
+ 53,
+ 196,
+ 200
+ ],
+ [
+ 53,
+ 203,
+ 206
+ ],
+ [
+ 53,
+ 215,
+ 227
+ ],
+ [
+ 53,
+ 234,
+ 245
+ ],
+ [
+ 53,
+ 247,
+ 262
+ ],
+ [
+ 53,
+ 334,
+ 337
+ ],
+ [
+ 53,
+ 346,
+ 347
+ ],
+ [
+ 54,
+ 0,
+ 4
+ ],
+ [
+ 54,
+ 88,
+ 92
+ ],
+ [
+ 54,
+ 105,
+ 105
+ ],
+ [
+ 54,
+ 110,
+ 124
+ ],
+ [
+ 54,
+ 157,
+ 167
+ ],
+ [
+ 54,
+ 196,
+ 199
+ ],
+ [
+ 54,
+ 203,
+ 205
+ ],
+ [
+ 54,
+ 215,
+ 227
+ ],
+ [
+ 54,
+ 235,
+ 245
+ ],
+ [
+ 54,
+ 247,
+ 262
+ ],
+ [
+ 54,
+ 265,
+ 265
+ ],
+ [
+ 54,
+ 334,
+ 336
+ ],
+ [
+ 54,
+ 345,
+ 348
+ ],
+ [
+ 55,
+ 0,
+ 3
+ ],
+ [
+ 55,
+ 88,
+ 93
+ ],
+ [
+ 55,
+ 104,
+ 106
+ ],
+ [
+ 55,
+ 109,
+ 124
+ ],
+ [
+ 55,
+ 163,
+ 168
+ ],
+ [
+ 55,
+ 196,
+ 200
+ ],
+ [
+ 55,
+ 204,
+ 205
+ ],
+ [
+ 55,
+ 215,
+ 227
+ ],
+ [
+ 55,
+ 235,
+ 244
+ ],
+ [
+ 55,
+ 248,
+ 268
+ ],
+ [
+ 55,
+ 334,
+ 336
+ ],
+ [
+ 55,
+ 345,
+ 348
+ ],
+ [
+ 56,
+ 0,
+ 3
+ ],
+ [
+ 56,
+ 87,
+ 93
+ ],
+ [
+ 56,
+ 103,
+ 107
+ ],
+ [
+ 56,
+ 109,
+ 124
+ ],
+ [
+ 56,
+ 164,
+ 170
+ ],
+ [
+ 56,
+ 196,
+ 200
+ ],
+ [
+ 56,
+ 204,
+ 206
+ ],
+ [
+ 56,
+ 216,
+ 227
+ ],
+ [
+ 56,
+ 235,
+ 244
+ ],
+ [
+ 56,
+ 247,
+ 269
+ ],
+ [
+ 56,
+ 334,
+ 336
+ ],
+ [
+ 56,
+ 345,
+ 348
+ ],
+ [
+ 57,
+ 0,
+ 3
+ ],
+ [
+ 57,
+ 87,
+ 93
+ ],
+ [
+ 57,
+ 103,
+ 108
+ ],
+ [
+ 57,
+ 110,
+ 124
+ ],
+ [
+ 57,
+ 165,
+ 171
+ ],
+ [
+ 57,
+ 196,
+ 200
+ ],
+ [
+ 57,
+ 203,
+ 207
+ ],
+ [
+ 57,
+ 216,
+ 227
+ ],
+ [
+ 57,
+ 235,
+ 243
+ ],
+ [
+ 57,
+ 246,
+ 269
+ ],
+ [
+ 57,
+ 334,
+ 336
+ ],
+ [
+ 57,
+ 345,
+ 348
+ ],
+ [
+ 58,
+ 0,
+ 3
+ ],
+ [
+ 58,
+ 88,
+ 93
+ ],
+ [
+ 58,
+ 103,
+ 109
+ ],
+ [
+ 58,
+ 113,
+ 124
+ ],
+ [
+ 58,
+ 167,
+ 172
+ ],
+ [
+ 58,
+ 196,
+ 200
+ ],
+ [
+ 58,
+ 203,
+ 206
+ ],
+ [
+ 58,
+ 216,
+ 227
+ ],
+ [
+ 58,
+ 235,
+ 242
+ ],
+ [
+ 58,
+ 246,
+ 263
+ ],
+ [
+ 58,
+ 265,
+ 268
+ ],
+ [
+ 58,
+ 334,
+ 336
+ ],
+ [
+ 58,
+ 345,
+ 348
+ ],
+ [
+ 59,
+ 0,
+ 3
+ ],
+ [
+ 59,
+ 88,
+ 93
+ ],
+ [
+ 59,
+ 104,
+ 109
+ ],
+ [
+ 59,
+ 114,
+ 124
+ ],
+ [
+ 59,
+ 168,
+ 174
+ ],
+ [
+ 59,
+ 196,
+ 200
+ ],
+ [
+ 59,
+ 203,
+ 205
+ ],
+ [
+ 59,
+ 217,
+ 227
+ ],
+ [
+ 59,
+ 236,
+ 243
+ ],
+ [
+ 59,
+ 247,
+ 263
+ ],
+ [
+ 59,
+ 265,
+ 267
+ ],
+ [
+ 59,
+ 334,
+ 336
+ ],
+ [
+ 59,
+ 346,
+ 347
+ ],
+ [
+ 60,
+ 0,
+ 3
+ ],
+ [
+ 60,
+ 88,
+ 93
+ ],
+ [
+ 60,
+ 104,
+ 110
+ ],
+ [
+ 60,
+ 114,
+ 119
+ ],
+ [
+ 60,
+ 121,
+ 124
+ ],
+ [
+ 60,
+ 170,
+ 180
+ ],
+ [
+ 60,
+ 196,
+ 196
+ ],
+ [
+ 60,
+ 198,
+ 200
+ ],
+ [
+ 60,
+ 204,
+ 204
+ ],
+ [
+ 60,
+ 216,
+ 228
+ ],
+ [
+ 60,
+ 237,
+ 244
+ ],
+ [
+ 60,
+ 246,
+ 262
+ ],
+ [
+ 60,
+ 264,
+ 268
+ ],
+ [
+ 60,
+ 334,
+ 336
+ ],
+ [
+ 61,
+ 0,
+ 3
+ ],
+ [
+ 61,
+ 36,
+ 37
+ ],
+ [
+ 61,
+ 87,
+ 93
+ ],
+ [
+ 61,
+ 105,
+ 111
+ ],
+ [
+ 61,
+ 113,
+ 122
+ ],
+ [
+ 61,
+ 171,
+ 180
+ ],
+ [
+ 61,
+ 198,
+ 200
+ ],
+ [
+ 61,
+ 217,
+ 228
+ ],
+ [
+ 61,
+ 238,
+ 261
+ ],
+ [
+ 61,
+ 264,
+ 269
+ ],
+ [
+ 61,
+ 333,
+ 337
+ ],
+ [
+ 62,
+ 0,
+ 4
+ ],
+ [
+ 62,
+ 35,
+ 38
+ ],
+ [
+ 62,
+ 86,
+ 94
+ ],
+ [
+ 62,
+ 105,
+ 112
+ ],
+ [
+ 62,
+ 114,
+ 124
+ ],
+ [
+ 62,
+ 173,
+ 180
+ ],
+ [
+ 62,
+ 199,
+ 199
+ ],
+ [
+ 62,
+ 204,
+ 204
+ ],
+ [
+ 62,
+ 217,
+ 228
+ ],
+ [
+ 62,
+ 241,
+ 244
+ ],
+ [
+ 62,
+ 246,
+ 257
+ ],
+ [
+ 62,
+ 259,
+ 260
+ ],
+ [
+ 62,
+ 264,
+ 269
+ ],
+ [
+ 62,
+ 290,
+ 290
+ ],
+ [
+ 62,
+ 333,
+ 337
+ ],
+ [
+ 63,
+ 0,
+ 4
+ ],
+ [
+ 63,
+ 34,
+ 38
+ ],
+ [
+ 63,
+ 87,
+ 93
+ ],
+ [
+ 63,
+ 105,
+ 124
+ ],
+ [
+ 63,
+ 135,
+ 155
+ ],
+ [
+ 63,
+ 175,
+ 180
+ ],
+ [
+ 63,
+ 203,
+ 205
+ ],
+ [
+ 63,
+ 218,
+ 228
+ ],
+ [
+ 63,
+ 243,
+ 243
+ ],
+ [
+ 63,
+ 247,
+ 258
+ ],
+ [
+ 63,
+ 264,
+ 270
+ ],
+ [
+ 63,
+ 289,
+ 291
+ ],
+ [
+ 63,
+ 334,
+ 336
+ ],
+ [
+ 64,
+ 0,
+ 3
+ ],
+ [
+ 64,
+ 34,
+ 38
+ ],
+ [
+ 64,
+ 88,
+ 88
+ ],
+ [
+ 64,
+ 91,
+ 92
+ ],
+ [
+ 64,
+ 105,
+ 124
+ ],
+ [
+ 64,
+ 135,
+ 154
+ ],
+ [
+ 64,
+ 178,
+ 180
+ ],
+ [
+ 64,
+ 202,
+ 206
+ ],
+ [
+ 64,
+ 217,
+ 227
+ ],
+ [
+ 64,
+ 248,
+ 251
+ ],
+ [
+ 64,
+ 253,
+ 258
+ ],
+ [
+ 64,
+ 264,
+ 269
+ ],
+ [
+ 64,
+ 289,
+ 292
+ ],
+ [
+ 64,
+ 335,
+ 335
+ ],
+ [
+ 65,
+ 0,
+ 2
+ ],
+ [
+ 65,
+ 35,
+ 38
+ ],
+ [
+ 65,
+ 106,
+ 124
+ ],
+ [
+ 65,
+ 135,
+ 155
+ ],
+ [
+ 65,
+ 179,
+ 180
+ ],
+ [
+ 65,
+ 196,
+ 196
+ ],
+ [
+ 65,
+ 202,
+ 206
+ ],
+ [
+ 65,
+ 208,
+ 208
+ ],
+ [
+ 65,
+ 218,
+ 226
+ ],
+ [
+ 65,
+ 247,
+ 257
+ ],
+ [
+ 65,
+ 265,
+ 268
+ ],
+ [
+ 65,
+ 290,
+ 291
+ ],
+ [
+ 66,
+ 1,
+ 1
+ ],
+ [
+ 66,
+ 35,
+ 38
+ ],
+ [
+ 66,
+ 107,
+ 124
+ ],
+ [
+ 66,
+ 135,
+ 155
+ ],
+ [
+ 66,
+ 178,
+ 180
+ ],
+ [
+ 66,
+ 195,
+ 197
+ ],
+ [
+ 66,
+ 203,
+ 209
+ ],
+ [
+ 66,
+ 217,
+ 225
+ ],
+ [
+ 66,
+ 244,
+ 244
+ ],
+ [
+ 66,
+ 246,
+ 252
+ ],
+ [
+ 66,
+ 254,
+ 256
+ ],
+ [
+ 66,
+ 266,
+ 266
+ ],
+ [
+ 67,
+ 35,
+ 38
+ ],
+ [
+ 67,
+ 108,
+ 124
+ ],
+ [
+ 67,
+ 135,
+ 137
+ ],
+ [
+ 67,
+ 178,
+ 180
+ ],
+ [
+ 67,
+ 195,
+ 198
+ ],
+ [
+ 67,
+ 203,
+ 210
+ ],
+ [
+ 67,
+ 216,
+ 223
+ ],
+ [
+ 67,
+ 225,
+ 225
+ ],
+ [
+ 67,
+ 243,
+ 252
+ ],
+ [
+ 67,
+ 255,
+ 255
+ ],
+ [
+ 67,
+ 262,
+ 263
+ ],
+ [
+ 68,
+ 34,
+ 38
+ ],
+ [
+ 68,
+ 109,
+ 124
+ ],
+ [
+ 68,
+ 135,
+ 137
+ ],
+ [
+ 68,
+ 178,
+ 180
+ ],
+ [
+ 68,
+ 195,
+ 197
+ ],
+ [
+ 68,
+ 202,
+ 209
+ ],
+ [
+ 68,
+ 215,
+ 223
+ ],
+ [
+ 68,
+ 242,
+ 253
+ ],
+ [
+ 68,
+ 261,
+ 265
+ ],
+ [
+ 68,
+ 335,
+ 336
+ ],
+ [
+ 69,
+ 34,
+ 38
+ ],
+ [
+ 69,
+ 108,
+ 124
+ ],
+ [
+ 69,
+ 135,
+ 137
+ ],
+ [
+ 69,
+ 178,
+ 180
+ ],
+ [
+ 69,
+ 196,
+ 196
+ ],
+ [
+ 69,
+ 203,
+ 203
+ ],
+ [
+ 69,
+ 205,
+ 208
+ ],
+ [
+ 69,
+ 216,
+ 222
+ ],
+ [
+ 69,
+ 242,
+ 252
+ ],
+ [
+ 69,
+ 262,
+ 266
+ ],
+ [
+ 69,
+ 271,
+ 271
+ ],
+ [
+ 69,
+ 324,
+ 324
+ ],
+ [
+ 69,
+ 334,
+ 337
+ ],
+ [
+ 70,
+ 34,
+ 38
+ ],
+ [
+ 70,
+ 108,
+ 124
+ ],
+ [
+ 70,
+ 135,
+ 137
+ ],
+ [
+ 70,
+ 178,
+ 180
+ ],
+ [
+ 70,
+ 206,
+ 206
+ ],
+ [
+ 70,
+ 217,
+ 222
+ ],
+ [
+ 70,
+ 241,
+ 251
+ ],
+ [
+ 70,
+ 261,
+ 267
+ ],
+ [
+ 70,
+ 270,
+ 272
+ ],
+ [
+ 70,
+ 323,
+ 325
+ ],
+ [
+ 70,
+ 333,
+ 337
+ ],
+ [
+ 71,
+ 35,
+ 37
+ ],
+ [
+ 71,
+ 109,
+ 124
+ ],
+ [
+ 71,
+ 135,
+ 137
+ ],
+ [
+ 71,
+ 178,
+ 180
+ ],
+ [
+ 71,
+ 206,
+ 206
+ ],
+ [
+ 71,
+ 216,
+ 221
+ ],
+ [
+ 71,
+ 241,
+ 252
+ ],
+ [
+ 71,
+ 260,
+ 266
+ ],
+ [
+ 71,
+ 269,
+ 273
+ ],
+ [
+ 71,
+ 323,
+ 325
+ ],
+ [
+ 71,
+ 333,
+ 337
+ ],
+ [
+ 72,
+ 35,
+ 37
+ ],
+ [
+ 72,
+ 109,
+ 124
+ ],
+ [
+ 72,
+ 135,
+ 137
+ ],
+ [
+ 72,
+ 178,
+ 180
+ ],
+ [
+ 72,
+ 205,
+ 207
+ ],
+ [
+ 72,
+ 215,
+ 223
+ ],
+ [
+ 72,
+ 240,
+ 255
+ ],
+ [
+ 72,
+ 259,
+ 266
+ ],
+ [
+ 72,
+ 269,
+ 273
+ ],
+ [
+ 72,
+ 278,
+ 279
+ ],
+ [
+ 72,
+ 324,
+ 324
+ ],
+ [
+ 72,
+ 334,
+ 336
+ ],
+ [
+ 73,
+ 36,
+ 36
+ ],
+ [
+ 73,
+ 75,
+ 76
+ ],
+ [
+ 73,
+ 88,
+ 89
+ ],
+ [
+ 73,
+ 109,
+ 124
+ ],
+ [
+ 73,
+ 135,
+ 137
+ ],
+ [
+ 73,
+ 178,
+ 180
+ ],
+ [
+ 73,
+ 203,
+ 208
+ ],
+ [
+ 73,
+ 215,
+ 224
+ ],
+ [
+ 73,
+ 241,
+ 256
+ ],
+ [
+ 73,
+ 258,
+ 267
+ ],
+ [
+ 73,
+ 270,
+ 274
+ ],
+ [
+ 73,
+ 277,
+ 280
+ ],
+ [
+ 73,
+ 335,
+ 335
+ ],
+ [
+ 73,
+ 352,
+ 352
+ ],
+ [
+ 74,
+ 74,
+ 77
+ ],
+ [
+ 74,
+ 87,
+ 90
+ ],
+ [
+ 74,
+ 109,
+ 124
+ ],
+ [
+ 74,
+ 135,
+ 137
+ ],
+ [
+ 74,
+ 150,
+ 175
+ ],
+ [
+ 74,
+ 177,
+ 180
+ ],
+ [
+ 74,
+ 202,
+ 210
+ ],
+ [
+ 74,
+ 212,
+ 218
+ ],
+ [
+ 74,
+ 220,
+ 224
+ ],
+ [
+ 74,
+ 239,
+ 247
+ ],
+ [
+ 74,
+ 250,
+ 266
+ ],
+ [
+ 74,
+ 271,
+ 273
+ ],
+ [
+ 74,
+ 276,
+ 282
+ ],
+ [
+ 74,
+ 351,
+ 353
+ ],
+ [
+ 75,
+ 74,
+ 77
+ ],
+ [
+ 75,
+ 88,
+ 90
+ ],
+ [
+ 75,
+ 109,
+ 124
+ ],
+ [
+ 75,
+ 135,
+ 137
+ ],
+ [
+ 75,
+ 150,
+ 180
+ ],
+ [
+ 75,
+ 202,
+ 218
+ ],
+ [
+ 75,
+ 220,
+ 224
+ ],
+ [
+ 75,
+ 238,
+ 246
+ ],
+ [
+ 75,
+ 250,
+ 265
+ ],
+ [
+ 75,
+ 272,
+ 272
+ ],
+ [
+ 75,
+ 275,
+ 283
+ ],
+ [
+ 75,
+ 287,
+ 287
+ ],
+ [
+ 75,
+ 351,
+ 353
+ ],
+ [
+ 76,
+ 35,
+ 36
+ ],
+ [
+ 76,
+ 75,
+ 76
+ ],
+ [
+ 76,
+ 88,
+ 90
+ ],
+ [
+ 76,
+ 109,
+ 124
+ ],
+ [
+ 76,
+ 135,
+ 137
+ ],
+ [
+ 76,
+ 150,
+ 180
+ ],
+ [
+ 76,
+ 202,
+ 217
+ ],
+ [
+ 76,
+ 219,
+ 224
+ ],
+ [
+ 76,
+ 237,
+ 243
+ ],
+ [
+ 76,
+ 245,
+ 245
+ ],
+ [
+ 76,
+ 249,
+ 266
+ ],
+ [
+ 76,
+ 269,
+ 272
+ ],
+ [
+ 76,
+ 274,
+ 284
+ ],
+ [
+ 76,
+ 286,
+ 288
+ ],
+ [
+ 76,
+ 352,
+ 352
+ ],
+ [
+ 77,
+ 34,
+ 37
+ ],
+ [
+ 77,
+ 89,
+ 89
+ ],
+ [
+ 77,
+ 109,
+ 123
+ ],
+ [
+ 77,
+ 135,
+ 137
+ ],
+ [
+ 77,
+ 151,
+ 153
+ ],
+ [
+ 77,
+ 155,
+ 179
+ ],
+ [
+ 77,
+ 203,
+ 216
+ ],
+ [
+ 77,
+ 219,
+ 224
+ ],
+ [
+ 77,
+ 236,
+ 242
+ ],
+ [
+ 77,
+ 248,
+ 289
+ ],
+ [
+ 78,
+ 1,
+ 1
+ ],
+ [
+ 78,
+ 34,
+ 38
+ ],
+ [
+ 78,
+ 109,
+ 114
+ ],
+ [
+ 78,
+ 117,
+ 124
+ ],
+ [
+ 78,
+ 135,
+ 137
+ ],
+ [
+ 78,
+ 204,
+ 205
+ ],
+ [
+ 78,
+ 210,
+ 215
+ ],
+ [
+ 78,
+ 219,
+ 223
+ ],
+ [
+ 78,
+ 236,
+ 241
+ ],
+ [
+ 78,
+ 248,
+ 283
+ ],
+ [
+ 78,
+ 285,
+ 289
+ ],
+ [
+ 79,
+ 0,
+ 2
+ ],
+ [
+ 79,
+ 33,
+ 37
+ ],
+ [
+ 79,
+ 108,
+ 114
+ ],
+ [
+ 79,
+ 118,
+ 123
+ ],
+ [
+ 79,
+ 135,
+ 137
+ ],
+ [
+ 79,
+ 211,
+ 214
+ ],
+ [
+ 79,
+ 219,
+ 222
+ ],
+ [
+ 79,
+ 235,
+ 241
+ ],
+ [
+ 79,
+ 248,
+ 273
+ ],
+ [
+ 79,
+ 276,
+ 282
+ ],
+ [
+ 79,
+ 285,
+ 289
+ ],
+ [
+ 80,
+ 0,
+ 2
+ ],
+ [
+ 80,
+ 33,
+ 37
+ ],
+ [
+ 80,
+ 108,
+ 114
+ ],
+ [
+ 80,
+ 118,
+ 123
+ ],
+ [
+ 80,
+ 135,
+ 137
+ ],
+ [
+ 80,
+ 218,
+ 223
+ ],
+ [
+ 80,
+ 234,
+ 240
+ ],
+ [
+ 80,
+ 248,
+ 265
+ ],
+ [
+ 80,
+ 269,
+ 272
+ ],
+ [
+ 80,
+ 277,
+ 280
+ ],
+ [
+ 80,
+ 285,
+ 289
+ ],
+ [
+ 80,
+ 291,
+ 291
+ ],
+ [
+ 80,
+ 347,
+ 347
+ ],
+ [
+ 81,
+ 0,
+ 3
+ ],
+ [
+ 81,
+ 33,
+ 37
+ ],
+ [
+ 81,
+ 68,
+ 68
+ ],
+ [
+ 81,
+ 108,
+ 114
+ ],
+ [
+ 81,
+ 118,
+ 123
+ ],
+ [
+ 81,
+ 135,
+ 137
+ ],
+ [
+ 81,
+ 207,
+ 209
+ ],
+ [
+ 81,
+ 218,
+ 224
+ ],
+ [
+ 81,
+ 227,
+ 228
+ ],
+ [
+ 81,
+ 233,
+ 239
+ ],
+ [
+ 81,
+ 248,
+ 262
+ ],
+ [
+ 81,
+ 270,
+ 271
+ ],
+ [
+ 81,
+ 285,
+ 292
+ ],
+ [
+ 81,
+ 346,
+ 348
+ ],
+ [
+ 82,
+ 0,
+ 2
+ ],
+ [
+ 82,
+ 33,
+ 37
+ ],
+ [
+ 82,
+ 67,
+ 69
+ ],
+ [
+ 82,
+ 108,
+ 113
+ ],
+ [
+ 82,
+ 115,
+ 123
+ ],
+ [
+ 82,
+ 135,
+ 137
+ ],
+ [
+ 82,
+ 197,
+ 210
+ ],
+ [
+ 82,
+ 217,
+ 239
+ ],
+ [
+ 82,
+ 248,
+ 261
+ ],
+ [
+ 82,
+ 285,
+ 292
+ ],
+ [
+ 82,
+ 346,
+ 348
+ ],
+ [
+ 83,
+ 0,
+ 2
+ ],
+ [
+ 83,
+ 33,
+ 37
+ ],
+ [
+ 83,
+ 68,
+ 68
+ ],
+ [
+ 83,
+ 109,
+ 123
+ ],
+ [
+ 83,
+ 135,
+ 137
+ ],
+ [
+ 83,
+ 196,
+ 210
+ ],
+ [
+ 83,
+ 214,
+ 239
+ ],
+ [
+ 83,
+ 249,
+ 258
+ ],
+ [
+ 83,
+ 284,
+ 292
+ ],
+ [
+ 83,
+ 297,
+ 297
+ ],
+ [
+ 83,
+ 346,
+ 348
+ ],
+ [
+ 84,
+ 1,
+ 1
+ ],
+ [
+ 84,
+ 33,
+ 37
+ ],
+ [
+ 84,
+ 110,
+ 123
+ ],
+ [
+ 84,
+ 135,
+ 137
+ ],
+ [
+ 84,
+ 195,
+ 211
+ ],
+ [
+ 84,
+ 213,
+ 238
+ ],
+ [
+ 84,
+ 250,
+ 257
+ ],
+ [
+ 84,
+ 284,
+ 292
+ ],
+ [
+ 84,
+ 296,
+ 298
+ ],
+ [
+ 84,
+ 345,
+ 348
+ ],
+ [
+ 85,
+ 33,
+ 41
+ ],
+ [
+ 85,
+ 111,
+ 111
+ ],
+ [
+ 85,
+ 114,
+ 123
+ ],
+ [
+ 85,
+ 135,
+ 137
+ ],
+ [
+ 85,
+ 195,
+ 211
+ ],
+ [
+ 85,
+ 213,
+ 237
+ ],
+ [
+ 85,
+ 254,
+ 257
+ ],
+ [
+ 85,
+ 284,
+ 292
+ ],
+ [
+ 85,
+ 295,
+ 299
+ ],
+ [
+ 85,
+ 346,
+ 347
+ ],
+ [
+ 86,
+ 1,
+ 1
+ ],
+ [
+ 86,
+ 34,
+ 43
+ ],
+ [
+ 86,
+ 115,
+ 123
+ ],
+ [
+ 86,
+ 135,
+ 137
+ ],
+ [
+ 86,
+ 190,
+ 211
+ ],
+ [
+ 86,
+ 213,
+ 235
+ ],
+ [
+ 86,
+ 255,
+ 256
+ ],
+ [
+ 86,
+ 261,
+ 264
+ ],
+ [
+ 86,
+ 285,
+ 292
+ ],
+ [
+ 86,
+ 295,
+ 299
+ ],
+ [
+ 87,
+ 0,
+ 2
+ ],
+ [
+ 87,
+ 35,
+ 44
+ ],
+ [
+ 87,
+ 109,
+ 111
+ ],
+ [
+ 87,
+ 114,
+ 123
+ ],
+ [
+ 87,
+ 135,
+ 137
+ ],
+ [
+ 87,
+ 189,
+ 202
+ ],
+ [
+ 87,
+ 204,
+ 204
+ ],
+ [
+ 87,
+ 206,
+ 211
+ ],
+ [
+ 87,
+ 214,
+ 217
+ ],
+ [
+ 87,
+ 219,
+ 229
+ ],
+ [
+ 87,
+ 231,
+ 233
+ ],
+ [
+ 87,
+ 260,
+ 265
+ ],
+ [
+ 87,
+ 286,
+ 292
+ ],
+ [
+ 87,
+ 295,
+ 299
+ ],
+ [
+ 87,
+ 302,
+ 302
+ ],
+ [
+ 88,
+ 0,
+ 3
+ ],
+ [
+ 88,
+ 37,
+ 45
+ ],
+ [
+ 88,
+ 108,
+ 123
+ ],
+ [
+ 88,
+ 135,
+ 137
+ ],
+ [
+ 88,
+ 188,
+ 197
+ ],
+ [
+ 88,
+ 207,
+ 211
+ ],
+ [
+ 88,
+ 216,
+ 216
+ ],
+ [
+ 88,
+ 222,
+ 223
+ ],
+ [
+ 88,
+ 260,
+ 266
+ ],
+ [
+ 88,
+ 287,
+ 287
+ ],
+ [
+ 88,
+ 289,
+ 292
+ ],
+ [
+ 88,
+ 295,
+ 299
+ ],
+ [
+ 88,
+ 301,
+ 303
+ ],
+ [
+ 89,
+ 0,
+ 2
+ ],
+ [
+ 89,
+ 39,
+ 45
+ ],
+ [
+ 89,
+ 107,
+ 123
+ ],
+ [
+ 89,
+ 135,
+ 137
+ ],
+ [
+ 89,
+ 187,
+ 196
+ ],
+ [
+ 89,
+ 207,
+ 211
+ ],
+ [
+ 89,
+ 260,
+ 266
+ ],
+ [
+ 89,
+ 286,
+ 293
+ ],
+ [
+ 89,
+ 295,
+ 298
+ ],
+ [
+ 89,
+ 300,
+ 303
+ ],
+ [
+ 90,
+ 0,
+ 3
+ ],
+ [
+ 90,
+ 42,
+ 44
+ ],
+ [
+ 90,
+ 108,
+ 122
+ ],
+ [
+ 90,
+ 135,
+ 137
+ ],
+ [
+ 90,
+ 187,
+ 197
+ ],
+ [
+ 90,
+ 207,
+ 211
+ ],
+ [
+ 90,
+ 238,
+ 240
+ ],
+ [
+ 90,
+ 260,
+ 265
+ ],
+ [
+ 90,
+ 287,
+ 298
+ ],
+ [
+ 90,
+ 301,
+ 302
+ ],
+ [
+ 91,
+ 0,
+ 3
+ ],
+ [
+ 91,
+ 43,
+ 43
+ ],
+ [
+ 91,
+ 108,
+ 124
+ ],
+ [
+ 91,
+ 135,
+ 137
+ ],
+ [
+ 91,
+ 187,
+ 197
+ ],
+ [
+ 91,
+ 199,
+ 200
+ ],
+ [
+ 91,
+ 207,
+ 211
+ ],
+ [
+ 91,
+ 237,
+ 241
+ ],
+ [
+ 91,
+ 260,
+ 265
+ ],
+ [
+ 91,
+ 287,
+ 297
+ ],
+ [
+ 92,
+ 0,
+ 2
+ ],
+ [
+ 92,
+ 108,
+ 125
+ ],
+ [
+ 92,
+ 135,
+ 139
+ ],
+ [
+ 92,
+ 141,
+ 141
+ ],
+ [
+ 92,
+ 143,
+ 144
+ ],
+ [
+ 92,
+ 188,
+ 196
+ ],
+ [
+ 92,
+ 198,
+ 202
+ ],
+ [
+ 92,
+ 204,
+ 211
+ ],
+ [
+ 92,
+ 237,
+ 240
+ ],
+ [
+ 92,
+ 259,
+ 265
+ ],
+ [
+ 92,
+ 286,
+ 296
+ ],
+ [
+ 93,
+ 1,
+ 1
+ ],
+ [
+ 93,
+ 25,
+ 25
+ ],
+ [
+ 93,
+ 108,
+ 151
+ ],
+ [
+ 93,
+ 153,
+ 164
+ ],
+ [
+ 93,
+ 166,
+ 176
+ ],
+ [
+ 93,
+ 181,
+ 181
+ ],
+ [
+ 93,
+ 184,
+ 184
+ ],
+ [
+ 93,
+ 187,
+ 211
+ ],
+ [
+ 93,
+ 236,
+ 241
+ ],
+ [
+ 93,
+ 258,
+ 265
+ ],
+ [
+ 93,
+ 285,
+ 295
+ ],
+ [
+ 94,
+ 24,
+ 26
+ ],
+ [
+ 94,
+ 108,
+ 211
+ ],
+ [
+ 94,
+ 228,
+ 228
+ ],
+ [
+ 94,
+ 233,
+ 233
+ ],
+ [
+ 94,
+ 236,
+ 243
+ ],
+ [
+ 94,
+ 258,
+ 265
+ ],
+ [
+ 94,
+ 285,
+ 292
+ ],
+ [
+ 94,
+ 294,
+ 294
+ ],
+ [
+ 95,
+ 23,
+ 27
+ ],
+ [
+ 95,
+ 109,
+ 244
+ ],
+ [
+ 95,
+ 247,
+ 247
+ ],
+ [
+ 95,
+ 250,
+ 253
+ ],
+ [
+ 95,
+ 256,
+ 264
+ ],
+ [
+ 95,
+ 285,
+ 292
+ ],
+ [
+ 96,
+ 0,
+ 1
+ ],
+ [
+ 96,
+ 23,
+ 27
+ ],
+ [
+ 96,
+ 110,
+ 114
+ ],
+ [
+ 96,
+ 117,
+ 191
+ ],
+ [
+ 96,
+ 193,
+ 265
+ ],
+ [
+ 96,
+ 286,
+ 292
+ ],
+ [
+ 96,
+ 297,
+ 297
+ ],
+ [
+ 97,
+ 0,
+ 2
+ ],
+ [
+ 97,
+ 23,
+ 27
+ ],
+ [
+ 97,
+ 111,
+ 112
+ ],
+ [
+ 97,
+ 121,
+ 266
+ ],
+ [
+ 97,
+ 287,
+ 292
+ ],
+ [
+ 97,
+ 296,
+ 298
+ ],
+ [
+ 98,
+ 0,
+ 2
+ ],
+ [
+ 98,
+ 23,
+ 27
+ ],
+ [
+ 98,
+ 40,
+ 40
+ ],
+ [
+ 98,
+ 126,
+ 127
+ ],
+ [
+ 98,
+ 129,
+ 194
+ ],
+ [
+ 98,
+ 196,
+ 198
+ ],
+ [
+ 98,
+ 200,
+ 202
+ ],
+ [
+ 98,
+ 208,
+ 238
+ ],
+ [
+ 98,
+ 240,
+ 267
+ ],
+ [
+ 98,
+ 287,
+ 292
+ ],
+ [
+ 98,
+ 295,
+ 298
+ ],
+ [
+ 99,
+ 0,
+ 2
+ ],
+ [
+ 99,
+ 24,
+ 26
+ ],
+ [
+ 99,
+ 39,
+ 41
+ ],
+ [
+ 99,
+ 141,
+ 141
+ ],
+ [
+ 99,
+ 143,
+ 204
+ ],
+ [
+ 99,
+ 209,
+ 233
+ ],
+ [
+ 99,
+ 235,
+ 237
+ ],
+ [
+ 99,
+ 239,
+ 243
+ ],
+ [
+ 99,
+ 245,
+ 267
+ ],
+ [
+ 99,
+ 287,
+ 292
+ ],
+ [
+ 99,
+ 295,
+ 297
+ ],
+ [
+ 100,
+ 0,
+ 2
+ ],
+ [
+ 100,
+ 25,
+ 25
+ ],
+ [
+ 100,
+ 38,
+ 42
+ ],
+ [
+ 100,
+ 148,
+ 205
+ ],
+ [
+ 100,
+ 210,
+ 214
+ ],
+ [
+ 100,
+ 219,
+ 224
+ ],
+ [
+ 100,
+ 228,
+ 234
+ ],
+ [
+ 100,
+ 236,
+ 236
+ ],
+ [
+ 100,
+ 239,
+ 266
+ ],
+ [
+ 100,
+ 287,
+ 293
+ ],
+ [
+ 100,
+ 296,
+ 296
+ ],
+ [
+ 101,
+ 0,
+ 2
+ ],
+ [
+ 101,
+ 38,
+ 42
+ ],
+ [
+ 101,
+ 147,
+ 206
+ ],
+ [
+ 101,
+ 211,
+ 213
+ ],
+ [
+ 101,
+ 220,
+ 223
+ ],
+ [
+ 101,
+ 229,
+ 233
+ ],
+ [
+ 101,
+ 235,
+ 242
+ ],
+ [
+ 101,
+ 245,
+ 259
+ ],
+ [
+ 101,
+ 261,
+ 266
+ ],
+ [
+ 101,
+ 287,
+ 294
+ ],
+ [
+ 102,
+ 0,
+ 2
+ ],
+ [
+ 102,
+ 23,
+ 23
+ ],
+ [
+ 102,
+ 25,
+ 25
+ ],
+ [
+ 102,
+ 38,
+ 43
+ ],
+ [
+ 102,
+ 47,
+ 47
+ ],
+ [
+ 102,
+ 147,
+ 205
+ ],
+ [
+ 102,
+ 210,
+ 214
+ ],
+ [
+ 102,
+ 221,
+ 221
+ ],
+ [
+ 102,
+ 230,
+ 232
+ ],
+ [
+ 102,
+ 234,
+ 252
+ ],
+ [
+ 102,
+ 254,
+ 254
+ ],
+ [
+ 102,
+ 260,
+ 265
+ ],
+ [
+ 102,
+ 288,
+ 295
+ ],
+ [
+ 103,
+ 0,
+ 3
+ ],
+ [
+ 103,
+ 15,
+ 17
+ ],
+ [
+ 103,
+ 22,
+ 26
+ ],
+ [
+ 103,
+ 39,
+ 50
+ ],
+ [
+ 103,
+ 61,
+ 61
+ ],
+ [
+ 103,
+ 81,
+ 84
+ ],
+ [
+ 103,
+ 148,
+ 154
+ ],
+ [
+ 103,
+ 156,
+ 205
+ ],
+ [
+ 103,
+ 209,
+ 215
+ ],
+ [
+ 103,
+ 233,
+ 251
+ ],
+ [
+ 103,
+ 253,
+ 255
+ ],
+ [
+ 103,
+ 260,
+ 266
+ ],
+ [
+ 103,
+ 289,
+ 289
+ ],
+ [
+ 103,
+ 291,
+ 294
+ ],
+ [
+ 104,
+ 0,
+ 2
+ ],
+ [
+ 104,
+ 14,
+ 18
+ ],
+ [
+ 104,
+ 22,
+ 27
+ ],
+ [
+ 104,
+ 39,
+ 51
+ ],
+ [
+ 104,
+ 60,
+ 62
+ ],
+ [
+ 104,
+ 80,
+ 89
+ ],
+ [
+ 104,
+ 102,
+ 103
+ ],
+ [
+ 104,
+ 117,
+ 119
+ ],
+ [
+ 104,
+ 131,
+ 131
+ ],
+ [
+ 104,
+ 149,
+ 151
+ ],
+ [
+ 104,
+ 157,
+ 158
+ ],
+ [
+ 104,
+ 161,
+ 179
+ ],
+ [
+ 104,
+ 181,
+ 184
+ ],
+ [
+ 104,
+ 190,
+ 205
+ ],
+ [
+ 104,
+ 208,
+ 217
+ ],
+ [
+ 104,
+ 233,
+ 245
+ ],
+ [
+ 104,
+ 248,
+ 250
+ ],
+ [
+ 104,
+ 253,
+ 255
+ ],
+ [
+ 104,
+ 260,
+ 265
+ ],
+ [
+ 104,
+ 290,
+ 294
+ ],
+ [
+ 105,
+ 0,
+ 1
+ ],
+ [
+ 105,
+ 15,
+ 17
+ ],
+ [
+ 105,
+ 23,
+ 26
+ ],
+ [
+ 105,
+ 40,
+ 41
+ ],
+ [
+ 105,
+ 43,
+ 52
+ ],
+ [
+ 105,
+ 59,
+ 63
+ ],
+ [
+ 105,
+ 79,
+ 90
+ ],
+ [
+ 105,
+ 92,
+ 92
+ ],
+ [
+ 105,
+ 101,
+ 104
+ ],
+ [
+ 105,
+ 116,
+ 121
+ ],
+ [
+ 105,
+ 129,
+ 134
+ ],
+ [
+ 105,
+ 163,
+ 178
+ ],
+ [
+ 105,
+ 182,
+ 182
+ ],
+ [
+ 105,
+ 188,
+ 193
+ ],
+ [
+ 105,
+ 195,
+ 197
+ ],
+ [
+ 105,
+ 199,
+ 200
+ ],
+ [
+ 105,
+ 202,
+ 205
+ ],
+ [
+ 105,
+ 207,
+ 223
+ ],
+ [
+ 105,
+ 234,
+ 243
+ ],
+ [
+ 105,
+ 254,
+ 254
+ ],
+ [
+ 105,
+ 259,
+ 263
+ ],
+ [
+ 105,
+ 290,
+ 295
+ ],
+ [
+ 106,
+ 44,
+ 51
+ ],
+ [
+ 106,
+ 59,
+ 63
+ ],
+ [
+ 106,
+ 80,
+ 93
+ ],
+ [
+ 106,
+ 100,
+ 105
+ ],
+ [
+ 106,
+ 116,
+ 122
+ ],
+ [
+ 106,
+ 128,
+ 135
+ ],
+ [
+ 106,
+ 142,
+ 143
+ ],
+ [
+ 106,
+ 163,
+ 178
+ ],
+ [
+ 106,
+ 187,
+ 229
+ ],
+ [
+ 106,
+ 233,
+ 233
+ ],
+ [
+ 106,
+ 235,
+ 235
+ ],
+ [
+ 106,
+ 237,
+ 242
+ ],
+ [
+ 106,
+ 245,
+ 245
+ ],
+ [
+ 106,
+ 247,
+ 253
+ ],
+ [
+ 106,
+ 259,
+ 263
+ ],
+ [
+ 106,
+ 289,
+ 296
+ ],
+ [
+ 107,
+ 47,
+ 47
+ ],
+ [
+ 107,
+ 50,
+ 50
+ ],
+ [
+ 107,
+ 60,
+ 62
+ ],
+ [
+ 107,
+ 81,
+ 84
+ ],
+ [
+ 107,
+ 86,
+ 90
+ ],
+ [
+ 107,
+ 92,
+ 92
+ ],
+ [
+ 107,
+ 101,
+ 104
+ ],
+ [
+ 107,
+ 116,
+ 122
+ ],
+ [
+ 107,
+ 129,
+ 135
+ ],
+ [
+ 107,
+ 141,
+ 144
+ ],
+ [
+ 107,
+ 163,
+ 177
+ ],
+ [
+ 107,
+ 186,
+ 256
+ ],
+ [
+ 107,
+ 259,
+ 263
+ ],
+ [
+ 107,
+ 288,
+ 295
+ ],
+ [
+ 108,
+ 61,
+ 61
+ ],
+ [
+ 108,
+ 73,
+ 73
+ ],
+ [
+ 108,
+ 83,
+ 83
+ ],
+ [
+ 108,
+ 89,
+ 89
+ ],
+ [
+ 108,
+ 117,
+ 121
+ ],
+ [
+ 108,
+ 130,
+ 134
+ ],
+ [
+ 108,
+ 141,
+ 144
+ ],
+ [
+ 108,
+ 164,
+ 176
+ ],
+ [
+ 108,
+ 186,
+ 211
+ ],
+ [
+ 108,
+ 214,
+ 263
+ ],
+ [
+ 108,
+ 272,
+ 272
+ ],
+ [
+ 108,
+ 275,
+ 277
+ ],
+ [
+ 108,
+ 289,
+ 291
+ ],
+ [
+ 109,
+ 72,
+ 74
+ ],
+ [
+ 109,
+ 133,
+ 133
+ ],
+ [
+ 109,
+ 142,
+ 143
+ ],
+ [
+ 109,
+ 165,
+ 166
+ ],
+ [
+ 109,
+ 169,
+ 175
+ ],
+ [
+ 109,
+ 187,
+ 211
+ ],
+ [
+ 109,
+ 214,
+ 263
+ ],
+ [
+ 109,
+ 269,
+ 278
+ ],
+ [
+ 109,
+ 286,
+ 293
+ ],
+ [
+ 109,
+ 296,
+ 308
+ ],
+ [
+ 109,
+ 312,
+ 312
+ ],
+ [
+ 110,
+ 73,
+ 73
+ ],
+ [
+ 110,
+ 190,
+ 195
+ ],
+ [
+ 110,
+ 202,
+ 212
+ ],
+ [
+ 110,
+ 215,
+ 262
+ ],
+ [
+ 110,
+ 268,
+ 279
+ ],
+ [
+ 110,
+ 281,
+ 283
+ ],
+ [
+ 110,
+ 285,
+ 315
+ ],
+ [
+ 110,
+ 320,
+ 323
+ ],
+ [
+ 110,
+ 325,
+ 327
+ ],
+ [
+ 111,
+ 207,
+ 211
+ ],
+ [
+ 111,
+ 221,
+ 261
+ ],
+ [
+ 111,
+ 268,
+ 278
+ ],
+ [
+ 111,
+ 280,
+ 316
+ ],
+ [
+ 111,
+ 319,
+ 328
+ ],
+ [
+ 111,
+ 332,
+ 332
+ ],
+ [
+ 112,
+ 208,
+ 210
+ ],
+ [
+ 112,
+ 226,
+ 227
+ ],
+ [
+ 112,
+ 230,
+ 243
+ ],
+ [
+ 112,
+ 246,
+ 258
+ ],
+ [
+ 112,
+ 269,
+ 269
+ ],
+ [
+ 112,
+ 271,
+ 277
+ ],
+ [
+ 112,
+ 281,
+ 283
+ ],
+ [
+ 112,
+ 285,
+ 316
+ ],
+ [
+ 112,
+ 319,
+ 328
+ ],
+ [
+ 112,
+ 331,
+ 333
+ ],
+ [
+ 113,
+ 204,
+ 205
+ ],
+ [
+ 113,
+ 230,
+ 234
+ ],
+ [
+ 113,
+ 272,
+ 277
+ ],
+ [
+ 113,
+ 286,
+ 293
+ ],
+ [
+ 113,
+ 296,
+ 302
+ ],
+ [
+ 113,
+ 304,
+ 308
+ ],
+ [
+ 113,
+ 311,
+ 315
+ ],
+ [
+ 113,
+ 320,
+ 323
+ ],
+ [
+ 113,
+ 325,
+ 327
+ ],
+ [
+ 113,
+ 332,
+ 332
+ ],
+ [
+ 114,
+ 203,
+ 206
+ ],
+ [
+ 114,
+ 229,
+ 234
+ ],
+ [
+ 114,
+ 273,
+ 276
+ ],
+ [
+ 114,
+ 290,
+ 290
+ ],
+ [
+ 114,
+ 314,
+ 314
+ ],
+ [
+ 115,
+ 202,
+ 207
+ ],
+ [
+ 115,
+ 228,
+ 234
+ ],
+ [
+ 115,
+ 274,
+ 275
+ ],
+ [
+ 116,
+ 203,
+ 206
+ ],
+ [
+ 116,
+ 227,
+ 234
+ ],
+ [
+ 117,
+ 204,
+ 205
+ ],
+ [
+ 117,
+ 228,
+ 233
+ ],
+ [
+ 118,
+ 229,
+ 232
+ ],
+ [
+ 119,
+ 231,
+ 231
+ ],
+ [
+ 127,
+ 205,
+ 209
+ ],
+ [
+ 128,
+ 204,
+ 210
+ ],
+ [
+ 129,
+ 203,
+ 211
+ ],
+ [
+ 130,
+ 204,
+ 211
+ ]
+ ]
+ },
+ "regions": [
+ {
+ "id": 0,
+ "name": "wall",
+ "color": "#000000"
+ },
+ {
+ "id": 1,
+ "name": "ours_home",
+ "color": "#ff0000"
+ },
+ {
+ "id": 2,
+ "name": "road_region_begin",
+ "color": "#33d17a"
+ },
+ {
+ "id": 3,
+ "name": "road_region_1",
+ "color": "#9141ac"
+ },
+ {
+ "id": 4,
+ "name": "road_region_2",
+ "color": "#3584e4"
+ },
+ {
+ "id": 5,
+ "name": "road_region_final",
+ "color": "#f6d32d"
+ },
+ {
+ "id": 6,
+ "name": "ours_highland",
+ "color": "#99c1f1"
+ }
+ ],
+ "polygons": [
+ {
+ "id": 3,
+ "region_id": 1,
+ "order": 3,
+ "points": [
+ [
+ 180,
+ 63
+ ],
+ [
+ 156,
+ 64
+ ],
+ [
+ 136,
+ 65
+ ],
+ [
+ 136,
+ 94
+ ],
+ [
+ 120,
+ 95
+ ],
+ [
+ 122,
+ 53
+ ],
+ [
+ 121,
+ 14
+ ],
+ [
+ 146,
+ 12
+ ],
+ [
+ 160,
+ 24
+ ],
+ [
+ 161,
+ 45
+ ],
+ [
+ 160,
+ 50
+ ],
+ [
+ 173,
+ 61
+ ],
+ [
+ 180,
+ 63
+ ]
+ ]
+ },
+ {
+ "id": 4,
+ "region_id": 2,
+ "order": 4,
+ "points": [
+ [
+ 154,
+ 64
+ ],
+ [
+ 152,
+ 75
+ ],
+ [
+ 179,
+ 75
+ ],
+ [
+ 179,
+ 61
+ ],
+ [
+ 153,
+ 64
+ ]
+ ]
+ },
+ {
+ "id": 5,
+ "region_id": 3,
+ "order": 5,
+ "points": [
+ [
+ 154,
+ 64
+ ],
+ [
+ 135,
+ 63
+ ],
+ [
+ 136,
+ 76
+ ],
+ [
+ 152,
+ 76
+ ],
+ [
+ 155,
+ 64
+ ]
+ ]
+ },
+ {
+ "id": 6,
+ "region_id": 4,
+ "order": 6,
+ "points": [
+ [
+ 136,
+ 75
+ ],
+ [
+ 135,
+ 94
+ ],
+ [
+ 152,
+ 94
+ ],
+ [
+ 153,
+ 75
+ ],
+ [
+ 137,
+ 75
+ ]
+ ]
+ },
+ {
+ "id": 7,
+ "region_id": 5,
+ "order": 7,
+ "points": [
+ [
+ 153,
+ 76
+ ],
+ [
+ 151,
+ 93
+ ],
+ [
+ 191,
+ 96
+ ],
+ [
+ 205,
+ 76
+ ],
+ [
+ 153,
+ 75
+ ]
+ ]
+ },
+ {
+ "id": 8,
+ "region_id": 6,
+ "order": 8,
+ "points": [
+ [
+ 184,
+ 7
+ ],
+ [
+ 176,
+ 29
+ ],
+ [
+ 163,
+ 29
+ ],
+ [
+ 160,
+ 49
+ ],
+ [
+ 173,
+ 61
+ ],
+ [
+ 179,
+ 61
+ ],
+ [
+ 179,
+ 74
+ ],
+ [
+ 205,
+ 76
+ ],
+ [
+ 201,
+ 28
+ ],
+ [
+ 203,
+ 5
+ ],
+ [
+ 183,
+ 7
+ ]
+ ]
+ }
+ ],
+ "fills": [
+ {
+ "id": 1,
+ "region_id": 6,
+ "order": 9,
+ "runs": [
+ [
+ 74,
+ 181,
+ 184
+ ],
+ [
+ 75,
+ 181,
+ 197
+ ]
+ ]
+ }
+ ]
+}
\ No newline at end of file
diff --git a/maps/train_map.region.png b/maps/train_map.region.png
new file mode 100644
index 0000000..4c802ba
Binary files /dev/null and b/maps/train_map.region.png differ
diff --git a/maps/train_map.yaml b/maps/train_map.yaml
new file mode 100644
index 0000000..1040159
--- /dev/null
+++ b/maps/train_map.yaml
@@ -0,0 +1,7 @@
+image: train_map.png
+mode: trinary
+resolution: 0.1000
+origin: [-13.0, -7.1, 0.0]
+negate: 0
+occupied_thresh: 0.65
+free_thresh: 0.196
diff --git a/src/cxx/component.cc b/src/cxx/component.cc
index 81fbdb0..7763cc9 100644
--- a/src/cxx/component.cc
+++ b/src/cxx/component.cc
@@ -5,7 +5,7 @@
#endif
#include "cxx/context.hh"
-#include "cxx/navigation.hh"
+#include "cxx/util/navigation/navigation.hh"
#include "cxx/util/node_mixin.hh"
#include
@@ -149,20 +149,150 @@ class Navigation
auto lua_sync() {
const auto [x, y, yaw] = navigation.check_position();
+ auto read_context = [](
+ const details::Context::InputInterface& input,
+ T fallback) -> T {
+ if (input.ready())
+ return *input;
+
+ return fallback;
+ };
+
auto user = lua_blackboard["user"].get();
- user["health"] = *context.robot_health;
- user["bullet"] = *context.robot_bullet;
- user["chassis_power_limit"] = *context.chassis_power_limit_referee;
+ user["health"] = read_context(context.robot_health, std::uint16_t{0});
+ user["bullet"] = read_context(context.robot_bullet, std::uint16_t{0});
+ user["chassis_power_limit"] = read_context(context.chassis_power_limit_referee, 0.0);
user["x"] = x;
user["y"] = y;
user["yaw"] = yaw;
+ user["chassis_power"] = read_context(context.chassis_power_referee, 0.0);
+ user["chassis_buffer_energy"] = read_context(context.chassis_buffer_energy_referee, 0.0);
+ user["chassis_output_status"] = read_context(context.chassis_output_status, false);
+ user["shooter_cooling"] = read_context(context.robot_shooter_cooling, std::int64_t{0});
+ user["shooter_heat_limit"] =
+ read_context(context.robot_shooter_heat_limit, std::int64_t{0});
+ user["bullet_42mm"] = read_context(context.robot_42mm_bullet, std::uint16_t{0});
+ user["fortress_17mm_bullet"] =
+ read_context(context.robot_fortress_17mm_bullet, std::uint16_t{0});
+ user["initial_speed"] = read_context(context.robot_initial_speed, 0.0F);
+ user["shoot_timestamp"] = read_context(context.robot_shoot_timestamp, 0.0);
auto game = lua_blackboard["game"].get();
- game["stage"] = rmcs_msgs::to_string(*context.game_stage);
+ game["stage"] = rmcs_msgs::to_string(read_context(
+ context.game_stage, rmcs_msgs::GameStage::UNKNOWN));
+ game["outpost_health"] = read_context(context.ally_outpost_hp, std::uint16_t{0});
+ game["base_health"] = read_context(context.ally_base_hp, std::uint16_t{0});
+ game["hero_health"] = read_context(context.ally_hero_hp, std::uint16_t{0});
+ game["infantry_1_health"] =
+ read_context(context.ally_infantry_1_hp, std::uint16_t{0});
+ game["infantry_2_health"] =
+ read_context(context.ally_infantry_2_hp, std::uint16_t{0});
+ game["engineer_health"] = read_context(context.ally_engineer_hp, std::uint16_t{0});
+ game["remaining_time"] = read_context(context.stage_remain_time, std::uint16_t{0});
+ game["gold_coin"] = read_context(context.remaining_gold_coin, std::uint16_t{0});
+ game["exchangeable_ammunition_quantity"] =
+ read_context(context.sentry_exchangeable_bullet, std::uint16_t{0});
+ game["our_dart_nmber_of_hits"] =
+ static_cast(read_context(
+ context.dart_latest_hit_target_total_count, std::uint8_t{0}));
+ game["fortress_occupied"] =
+ read_context(context.ally_fortress_occupation_status, std::uint8_t{0}) != 0;
+ game["big_energy_mechanism_activated"] =
+ read_context(context.ally_big_energy_activation_status, std::uint8_t{0}) != 0;
+ game["small_energy_mechanism_activated"] =
+ read_context(context.ally_small_energy_activation_status, std::uint8_t{0}) != 0;
+
+ auto set_position = [](sol::table position, double x, double y) {
+ position["x"] = x;
+ position["y"] = y;
+ };
+ set_position(
+ game["hero_position"].get(),
+ read_context(context.ally_hero_position_x, 0.0),
+ read_context(context.ally_hero_position_y, 0.0));
+ set_position(
+ game["infantry_1_position"].get(),
+ read_context(context.ally_infantry_1_position_x, 0.0),
+ read_context(context.ally_infantry_1_position_y, 0.0));
+ set_position(
+ game["infantry_2_position"].get(),
+ read_context(context.ally_infantry_2_position_x, 0.0),
+ read_context(context.ally_infantry_2_position_y, 0.0));
+ set_position(
+ game["engineer_position"].get(),
+ read_context(context.ally_engineer_position_x, 0.0),
+ read_context(context.ally_engineer_position_y, 0.0));
+
+ auto referee = lua_blackboard["referee"].get();
+ referee["sync_timestamp"] = read_context(context.sync_timestamp, std::uint64_t{0});
+ const auto robot_id =
+ read_context(context.robot_id, rmcs_msgs::RobotId{rmcs_msgs::RobotId::UNKNOWN});
+ referee["robot_id"] = static_cast(robot_id);
+ auto robots_hp = referee["robots_hp"].get();
+ const auto hp =
+ read_context(context.robots_hp, rmcs_core::referee::status::GameRobotHp{});
+ const auto set_ally_hp =
+ [&](std::uint16_t hp1,
+ std::uint16_t hp2,
+ std::uint16_t hp3,
+ std::uint16_t hp4,
+ std::uint16_t hp5,
+ std::uint16_t hp7,
+ std::uint16_t outpost,
+ std::uint16_t base) {
+ robots_hp["ally_1"] = hp1;
+ robots_hp["ally_2"] = hp2;
+ robots_hp["ally_3"] = hp3;
+ robots_hp["ally_4"] = hp4;
+ robots_hp["reserved"] = hp5;
+ robots_hp["ally_7"] = hp7;
+ robots_hp["outpost"] = outpost;
+ robots_hp["base"] = base;
+ };
+ if (robot_id == rmcs_msgs::RobotId::UNKNOWN) {
+ set_ally_hp(0, 0, 0, 0, 0, 0, 0, 0);
+ } else if (robot_id.color() == rmcs_msgs::RobotColor::BLUE) {
+ set_ally_hp(
+ hp.blue_1,
+ hp.blue_2,
+ hp.blue_3,
+ hp.blue_4,
+ hp.blue_5,
+ hp.blue_7,
+ hp.blue_outpost,
+ hp.blue_base);
+ } else {
+ set_ally_hp(
+ hp.red_1,
+ hp.red_2,
+ hp.red_3,
+ hp.red_4,
+ hp.red_5,
+ hp.red_7,
+ hp.red_outpost,
+ hp.red_base);
+ }
+ referee["can_confirm_free_revive"] =
+ read_context(context.sentry_can_confirm_free_revive, false);
+ referee["can_exchange_instant_revive"] =
+ read_context(context.sentry_can_exchange_instant_revive, false);
+ referee["instant_revive_cost"] =
+ read_context(context.sentry_instant_revive_cost, std::uint16_t{0});
+ referee["exchanged_bullet"] =
+ read_context(context.sentry_exchanged_bullet, std::uint16_t{0});
+ referee["remote_bullet_exchange_count"] =
+ read_context(context.sentry_remote_bullet_exchange_count, std::uint8_t{0});
+ referee["sentry_mode"] = read_context(context.sentry_mode, std::uint8_t{0});
+ referee["energy_mechanism_activatable"] =
+ read_context(context.sentry_energy_mechanism_activatable, false);
+ referee["red_score"] = read_context(context.red_score, std::uint32_t{0});
+ referee["blue_score"] = read_context(context.blue_score, std::uint32_t{0});
auto play = lua_blackboard["play"].get();
- play["rswitch"] = rmcs_msgs::to_string(*context.switch_right);
- play["lswitch"] = rmcs_msgs::to_string(*context.switch_left);
+ play["rswitch"] =
+ rmcs_msgs::to_string(read_context(context.switch_right, rmcs_msgs::Switch::UNKNOWN));
+ play["lswitch"] =
+ rmcs_msgs::to_string(read_context(context.switch_left, rmcs_msgs::Switch::UNKNOWN));
auto meta = lua_blackboard["meta"].get();
meta["timestamp"] = this->now().seconds();
diff --git a/src/cxx/context.cc b/src/cxx/context.cc
index 60145af..6b4e692 100644
--- a/src/cxx/context.cc
+++ b/src/cxx/context.cc
@@ -54,14 +54,78 @@ auto Context::init(std::mutex& io_mutex, bool mock) -> void {
auto& subscription = pimpl->subscription;
auto& node = pimpl->node;
- make_input(component, "/referee/chassis/power_limit", chassis_power_limit_referee, mock);
+ make_input(component, "/referee/game/stage", game_stage, mock);
+ make_input(component, "/referee/game/stage_remain_time", stage_remain_time, mock);
+ make_input(component, "/referee/game/sync_timestamp", sync_timestamp, mock);
+ make_input(
+ component, "/referee/event/ally_big_energy_activation_status",
+ ally_big_energy_activation_status, mock);
+ make_input(
+ component, "/referee/event/ally_small_energy_activation_status",
+ ally_small_energy_activation_status, mock);
+ make_input(
+ component, "/referee/event/ally_fortress_occupation_status",
+ ally_fortress_occupation_status, mock);
+ make_input(
+ component, "/referee/dart/latest_hit_target_total_count",
+ dart_latest_hit_target_total_count, mock);
make_input(component, "/referee/id", robot_id, mock);
- make_input(component, "/remote/switch/right", switch_right, mock);
- make_input(component, "/remote/switch/left", switch_left, mock);
- make_input(component, "/referee/game/stage", game_stage, mock);
+ make_input(component, "/referee/shooter/cooling", robot_shooter_cooling, mock);
+ make_input(component, "/referee/shooter/heat_limit", robot_shooter_heat_limit, mock);
+ make_input(component, "/referee/chassis/power_limit", chassis_power_limit_referee, mock);
+ make_input(component, "/referee/chassis/power", chassis_power_referee, mock);
+ make_input(component, "/referee/chassis/buffer_energy", chassis_buffer_energy_referee, mock);
+ make_input(component, "/referee/chassis/output_status", chassis_output_status, mock);
+
+ make_input(component, "/referee/robots/hp", robots_hp, mock);
+ make_input(component, "/referee/ally/hero_hp", ally_hero_hp, mock);
+ make_input(component, "/referee/ally/engineer_hp", ally_engineer_hp, mock);
+ make_input(component, "/referee/ally/infantry_1_hp", ally_infantry_1_hp, mock);
+ make_input(component, "/referee/ally/infantry_2_hp", ally_infantry_2_hp, mock);
+ make_input(component, "/referee/ally/outpost/hp", ally_outpost_hp, mock);
+ make_input(component, "/referee/ally/base/hp", ally_base_hp, mock);
+ make_input(component, "/referee/ally/hero_position_x", ally_hero_position_x, mock);
+ make_input(component, "/referee/ally/hero_position_y", ally_hero_position_y, mock);
+ make_input(component, "/referee/ally/engineer_position_x", ally_engineer_position_x, mock);
+ make_input(component, "/referee/ally/engineer_position_y", ally_engineer_position_y, mock);
+ make_input(component, "/referee/ally/infantry_1_position_x", ally_infantry_1_position_x, mock);
+ make_input(component, "/referee/ally/infantry_1_position_y", ally_infantry_1_position_y, mock);
+ make_input(component, "/referee/ally/infantry_2_position_x", ally_infantry_2_position_x, mock);
+ make_input(component, "/referee/ally/infantry_2_position_y", ally_infantry_2_position_y, mock);
make_input(component, "/referee/current_hp", robot_health, mock);
make_input(component, "/referee/shooter/bullet_allowance", robot_bullet, mock);
+ make_input(component, "/referee/shooter/42mm_bullet_allowance", robot_42mm_bullet, mock);
+ make_input(
+ component, "/referee/shooter/fortress_17mm_bullet_allowance",
+ robot_fortress_17mm_bullet, mock);
+ make_input(component, "/referee/remaining_gold_coin", remaining_gold_coin, mock);
+
+ make_input(component, "/referee/shooter/initial_speed", robot_initial_speed, mock);
+ make_input(component, "/referee/shooter/shoot_timestamp", robot_shoot_timestamp, mock);
+
+ make_input(
+ component, "/referee/sentry/can_confirm_free_revive", sentry_can_confirm_free_revive,
+ mock);
+ make_input(
+ component, "/referee/sentry/can_exchange_instant_revive",
+ sentry_can_exchange_instant_revive, mock);
+ make_input(component, "/referee/sentry/instant_revive_cost", sentry_instant_revive_cost, mock);
+ make_input(
+ component, "/referee/sentry/exchanged_bullet_allowance", sentry_exchanged_bullet, mock);
+ make_input(
+ component, "/referee/sentry/remote_bullet_exchange_count",
+ sentry_remote_bullet_exchange_count, mock);
+ make_input(
+ component, "/referee/sentry/exchangeable_bullet_allowance", sentry_exchangeable_bullet,
+ mock);
+ make_input(component, "/referee/sentry/mode", sentry_mode, mock);
+ make_input(
+ component, "/referee/sentry/energy_mechanism_activatable",
+ sentry_energy_mechanism_activatable, mock);
+
+ make_input(component, "/remote/switch/right", switch_right, mock);
+ make_input(component, "/remote/switch/left", switch_left, mock);
make_input(component, "/referee/game/red_score", red_score, mock);
make_input(component, "/referee/game/blue_score", blue_score, mock);
diff --git a/src/cxx/context.hh b/src/cxx/context.hh
index ab0a534..c237331 100644
--- a/src/cxx/context.hh
+++ b/src/cxx/context.hh
@@ -1,6 +1,9 @@
#pragma once
#include "util/pimpl.hh"
+#include "referee/status/field.hpp"
+
+#include
#include
#include
#include
@@ -21,14 +24,53 @@ public:
using InputInterface = rmcs_executor::Component::InputInterface;
InputInterface game_stage;
+ InputInterface stage_remain_time;
+ InputInterface sync_timestamp;
+ InputInterface ally_big_energy_activation_status;
+ InputInterface ally_small_energy_activation_status;
+ InputInterface ally_fortress_occupation_status;
+ InputInterface dart_latest_hit_target_total_count;
InputInterface robot_id;
+ InputInterface robot_shooter_cooling;
+ InputInterface robot_shooter_heat_limit;
+ InputInterface chassis_power_limit_referee;
+ InputInterface chassis_power_referee;
+ InputInterface chassis_buffer_energy_referee;
+ InputInterface chassis_output_status;
+ InputInterface robots_hp;
+ InputInterface ally_hero_hp;
+ InputInterface ally_engineer_hp;
+ InputInterface ally_infantry_1_hp;
+ InputInterface ally_infantry_2_hp;
+ InputInterface ally_outpost_hp;
+ InputInterface ally_base_hp;
+ InputInterface ally_hero_position_x;
+ InputInterface ally_hero_position_y;
+ InputInterface ally_engineer_position_x;
+ InputInterface ally_engineer_position_y;
+ InputInterface ally_infantry_1_position_x;
+ InputInterface ally_infantry_1_position_y;
+ InputInterface ally_infantry_2_position_x;
+ InputInterface ally_infantry_2_position_y;
InputInterface robot_health;
InputInterface robot_bullet;
+ InputInterface robot_42mm_bullet;
+ InputInterface robot_fortress_17mm_bullet;
+ InputInterface remaining_gold_coin;
+ InputInterface robot_initial_speed;
+ InputInterface robot_shoot_timestamp;
+ InputInterface sentry_can_confirm_free_revive;
+ InputInterface sentry_can_exchange_instant_revive;
+ InputInterface sentry_instant_revive_cost;
+ InputInterface sentry_exchanged_bullet;
+ InputInterface sentry_remote_bullet_exchange_count;
+ InputInterface sentry_exchangeable_bullet;
+ InputInterface sentry_mode;
+ InputInterface sentry_energy_mechanism_activatable;
InputInterface red_score;
InputInterface blue_score;
InputInterface switch_right;
InputInterface switch_left;
- InputInterface chassis_power_limit_referee;
explicit Context(rclcpp::Node& node, rmcs_executor::Component& component) noexcept;
diff --git a/src/cxx/sim_sidecar.cc b/src/cxx/sim_sidecar.cc
new file mode 100644
index 0000000..a26ae85
--- /dev/null
+++ b/src/cxx/sim_sidecar.cc
@@ -0,0 +1,1694 @@
+/**
+ * @file sim_sidecar.cc
+ * @brief RMCS导航系统仿真
+ *
+ * 该文件实现了RMCS导航系统的仿真侧车服务,提供Lua脚本运行时环境、
+ * 网络通信接口和状态管理功能,用于在仿真环境中运行导航逻辑。
+ *
+ * @author RMCS Team
+ * @version 1.0.0
+ */
+
+#if defined(__clang__)
+# pragma clang diagnostic ignored "-Wdeprecated-declarations"
+#elif defined(__GNUC__)
+# pragma GCC diagnostic ignored "-Wdeprecated-declarations"
+#endif
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+#include
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+namespace rmcs::navigation::sim {
+
+/**
+ * @brief JSON值类型定义
+ *
+ * 支持布尔值、双精度浮点数和字符串三种基本数据类型
+ */
+using JsonValue = std::variant;
+
+/**
+ * @brief JSON字段定义
+ *
+ * 包含字段名和对应的JSON值
+ */
+using JsonField = std::pair;
+
+/**
+ * @brief JSON字段集合
+ *
+ * 用于构建JSON对象的字段列表
+ */
+using JsonFields = std::vector;
+
+/**
+ * @brief 日志级别枚举
+ *
+ * 定义系统日志的严重程度级别
+ */
+enum class LogLevel : std::uint8_t { Info, Warn, Error };
+
+/**
+ * @brief 作用域文件描述符管理类
+ *
+ * 提供RAII(资源获取即初始化)机制管理文件描述符,
+ * 确保文件描述符在作用域结束时自动关闭,避免资源泄漏。
+ */
+struct ScopedFd {
+ int value = -1;
+
+ /// @brief 默认构造函数,创建无效的文件描述符
+ ScopedFd() = default;
+
+ /// @brief 显式构造函数,接管现有文件描述符
+ /// @param fd 要管理的文件描述符
+ explicit ScopedFd(int fd)
+ : value{fd} {}
+
+ /// @brief 禁用拷贝构造,避免重复关闭文件描述符
+ ScopedFd(const ScopedFd&) = delete;
+ auto operator=(const ScopedFd&) -> ScopedFd& = delete;
+
+ /// @brief 移动构造函数,转移文件描述符所有权
+ /// @param rhs 源对象
+ ScopedFd(ScopedFd&& rhs) noexcept
+ : value{std::exchange(rhs.value, -1)} {}
+
+ /// @brief 移动赋值运算符
+ /// @param rhs 源对象
+ /// @return 当前对象引用
+ auto operator=(ScopedFd&& rhs) noexcept -> ScopedFd& {
+ if (this == &rhs)
+ return *this;
+ reset();
+ value = std::exchange(rhs.value, -1);
+ return *this;
+ }
+
+ /// @brief 析构函数,自动关闭文件描述符
+ ~ScopedFd() { reset(); }
+
+ /// @brief 重置文件描述符
+ /// @param fd 新的文件描述符,默认为-1(无效)
+ auto reset(int fd = -1) -> void {
+ if (value >= 0) {
+ ::close(value);
+ }
+ value = fd;
+ }
+
+ /// @brief 检查文件描述符是否有效
+ /// @return true表示有效,false表示无效
+ [[nodiscard]] auto valid() const -> bool { return value >= 0; }
+};
+
+[[nodiscard]] auto to_string(LogLevel level) -> std::string_view {
+ switch (level) {
+ case LogLevel::Info: return "info";
+ case LogLevel::Warn: return "warn";
+ case LogLevel::Error: return "error";
+ default: return "unknown";
+ }
+}
+
+[[nodiscard]] auto trim(std::string text) -> std::string {
+ auto is_space = [](char ch) { return std::isspace(static_cast(ch)); };
+ text.erase(text.begin(), std::find_if_not(text.begin(), text.end(), is_space));
+ text.erase(std::find_if_not(text.rbegin(), text.rend(), is_space).base(), text.end());
+ return text;
+}
+
+[[nodiscard]] auto escape_json(std::string_view text) -> std::string {
+ auto result = std::string{};
+ result.reserve(text.size() + 8);
+ for (const auto ch : text) {
+ switch (ch) {
+ case '\\': result += "\\\\"; break;
+ case '"': result += "\\\""; break;
+ case '\b': result += "\\b"; break;
+ case '\f': result += "\\f"; break;
+ case '\n': result += "\\n"; break;
+ case '\r': result += "\\r"; break;
+ case '\t': result += "\\t"; break;
+ default:
+ if (static_cast(ch) < 0x20) {
+ result += std::format("\\u{:04x}", static_cast(ch));
+ } else {
+ result += ch;
+ }
+ break;
+ }
+ }
+ return result;
+}
+
+[[nodiscard]] auto to_json(const JsonFields& fields) -> std::string {
+ auto result = std::string{"{"};
+ for (std::size_t index = 0; index < fields.size(); ++index) {
+ const auto& [name, value] = fields[index];
+ result += std::format("\"{}\":", escape_json(name));
+ std::visit(
+ [&](const auto& entry) {
+ using T = std::decay_t;
+ if constexpr (std::is_same_v) {
+ result += (entry ? "true" : "false");
+ } else if constexpr (std::is_same_v) {
+ if (!std::isfinite(entry)) {
+ result += "null";
+ } else {
+ result += std::format("{:.8f}", entry);
+ }
+ } else if constexpr (std::is_same_v) {
+ result += std::format("\"{}\"", escape_json(entry));
+ }
+ },
+ value);
+
+ if (index + 1 < fields.size()) {
+ result += ",";
+ }
+ }
+ result += "}";
+ return result;
+}
+
+/**
+ * @brief 递归将YAML节点追加到JSON字符串
+ *
+ * 深度优先遍历YAML数据结构,将其转换为JSON格式字符串
+ * 支持映射、序列和标量值的转换
+ *
+ * @param result 目标JSON字符串引用
+ * @param node 要转换的YAML节点
+ */
+auto append_json_node(std::string& result, const YAML::Node& node) -> void {
+ if (!node || node.IsNull()) {
+ result += "null";
+ return;
+ }
+
+ if (node.IsMap()) {
+ result += "{";
+ auto first = true;
+ for (const auto& entry : node) {
+ if (!first) {
+ result += ",";
+ }
+ first = false;
+
+ result += std::format("\"{}\":", escape_json(entry.first.as()));
+ append_json_node(result, entry.second);
+ }
+ result += "}";
+ return;
+ }
+
+ if (node.IsSequence()) {
+ result += "[";
+ for (auto index = std::size_t{0}; index < node.size(); ++index) {
+ if (index > 0) {
+ result += ",";
+ }
+ append_json_node(result, node[index]);
+ }
+ result += "]";
+ return;
+ }
+
+ if (auto scalar = node.Scalar(); scalar == "true" || scalar == "false") {
+ result += scalar;
+ return;
+ }
+
+ try {
+ result += std::to_string(node.as());
+ return;
+ } catch (...) {
+ }
+
+ try {
+ auto number = node.as();
+ if (!std::isfinite(number)) {
+ result += "null";
+ } else {
+ result += std::format("{:.8f}", number);
+ }
+ return;
+ } catch (...) {
+ }
+
+ result += std::format("\"{}\"", escape_json(node.as()));
+}
+
+[[nodiscard]] auto to_json(const YAML::Node& node) -> std::string {
+ auto result = std::string{};
+ append_json_node(result, node);
+ return result;
+}
+
+/**
+ * @brief 发送带换行符的完整数据行
+ *
+ * 将数据包添加换行符后通过套接字发送,确保完整发送所有数据
+ * 使用循环发送机制处理部分发送情况
+ *
+ * @param fd 目标套接字文件描述符
+ * @param payload 要发送的数据内容
+ * @throws std::runtime_error 当发送失败时抛出
+ */
+auto send_line(int fd, std::string_view payload) -> void {
+ auto packed = std::string{payload};
+ packed.push_back('\n');
+
+ std::size_t offset = 0;
+ while (offset < packed.size()) {
+ auto written = ::send(fd, packed.data() + offset, packed.size() - offset, MSG_NOSIGNAL);
+ if (written <= 0) {
+ throw std::runtime_error(
+ std::format("socket send failed: {}", std::strerror(errno)));
+ }
+ offset += static_cast(written);
+ }
+}
+
+/**
+ * @brief 条件赋值模板函数
+ *
+ * 如果YAML节点中存在指定键且值不为空,则将其转换为目标类型并赋值
+ *
+ * @tparam T 目标类型
+ * @param root 根YAML节点
+ * @param key 要查找的键名
+ * @param target 目标变量引用
+ * @param convert 类型转换函数
+ */
+template
+auto assign_if_present(
+ const YAML::Node& root,
+ std::string_view key,
+ T& target,
+ const std::function& convert) -> void {
+ auto value = root[std::string{key}];
+ if (!value || value.IsNull()) {
+ return;
+ }
+ target = convert(value);
+}
+
+/**
+ * @brief 安全标量解析模板函数
+ *
+ * 尝试解析YAML标量值,如果解析失败则返回默认值
+ * 提供异常安全的类型转换机制
+ *
+ * @tparam T 目标类型
+ * @param node 要解析的YAML节点
+ * @param fallback 解析失败时的默认值
+ * @param convert 类型转换函数
+ * @return T 解析结果或默认值
+ */
+template
+auto parse_scalar_or(
+ const YAML::Node& node, const T& fallback, const std::function& convert)
+ -> T {
+ try {
+ return convert(node);
+ } catch (...) {
+ return fallback;
+ }
+}
+
+[[nodiscard]] auto parse_boolean(const YAML::Node& node, bool fallback = false) -> bool {
+ return parse_scalar_or(node, fallback, [](const YAML::Node& value) {
+ return value.as();
+ });
+}
+
+[[nodiscard]] auto parse_double(const YAML::Node& node, double fallback = 0.0) -> double {
+ return parse_scalar_or(node, fallback, [](const YAML::Node& value) {
+ return value.as();
+ });
+}
+
+[[nodiscard]] auto parse_string(const YAML::Node& node, std::string fallback = {}) -> std::string {
+ return parse_scalar_or(
+ node, std::move(fallback), [](const YAML::Node& value) { return value.as(); });
+}
+
+[[nodiscard]] auto parse_revision(const YAML::Node& node, std::uint64_t fallback = 0) -> std::uint64_t {
+ if (!node) {
+ return fallback;
+ }
+
+ try {
+ auto value = node.as();
+ if (value < 0) {
+ return fallback;
+ }
+ return static_cast(value);
+ } catch (...) {
+ }
+
+ try {
+ auto value = node.as();
+ if (!std::isfinite(value) || value < 0) {
+ return fallback;
+ }
+ return static_cast(value);
+ } catch (...) {
+ }
+
+ return fallback;
+}
+
+[[nodiscard]] auto to_steady_timeout(std::chrono::steady_clock::time_point deadline) -> int {
+ auto now = std::chrono::steady_clock::now();
+ if (now >= deadline) {
+ return 0;
+ }
+
+ auto timeout = std::chrono::duration_cast(deadline - now).count();
+ if (timeout < 0) {
+ return 0;
+ }
+
+ constexpr auto kMaxPollTimeoutMs = 100;
+ return static_cast(std::min(timeout, kMaxPollTimeoutMs));
+}
+
+/**
+ * @brief 仿真状态数据结构
+ *
+ * 包含用户控制状态和元数据信息,用于描述仿真环境的当前状态
+ */
+struct SimState {
+ /**
+ * @brief 用户控制状态
+ *
+ * 包含机器人底盘功率限制、位置坐标、朝向角等控制参数
+ */
+ struct User {
+ double chassis_power_limit = 0.0; ///< 底盘功率限制(W)
+ double x = 0.0; ///< X坐标(m)
+ double y = 0.0; ///< Y坐标(m)
+ double yaw = 0.0; ///< 偏航角(rad)
+ std::optional health; ///< 健康值(可选)
+ std::optional bullet; ///< 子弹数量(可选)
+ };
+
+ /**
+ * @brief 元数据信息
+ *
+ * 包含时间戳等系统级信息
+ */
+ struct Meta {
+ double timestamp = 0.0; ///< 时间戳(s)
+ };
+
+ /**
+ * @brief 比赛态仿真状态
+ *
+ * 包含全局比赛对象(基地、前哨站)的生命值,
+ * 用于驱动比赛策略中的守家和前哨站相关判断。
+ */
+ struct Game {
+ std::optional base_health; ///< 基地血量(可选)
+ std::optional outpost_health; ///< 前哨站血量(可选)
+ std::optional gold_coin; ///< 队伍金币(可选)
+ std::optional remaining_time; ///< 比赛剩余时间(可选)
+ std::optional exchangeable_ammunition_quantity; ///< 可兑换弹药量(可选)
+ std::optional our_dart_nmber_of_hits; ///< 己方飞镖命中次数(可选)
+ std::optional fortress_occupied; ///< 己方堡垒是否被占领(可选)
+ std::optional big_energy_mechanism_activated; ///< 大能量机关是否激活(可选)
+ std::optional small_energy_mechanism_activated; ///< 小能量机关是否激活(可选)
+ };
+
+ User user; ///< 用户控制状态
+ Game game; ///< 比赛全局状态
+ Meta meta; ///< 元数据信息
+};
+
+/**
+ * @brief 状态覆盖配置结构
+ *
+ * 用于管理状态覆盖功能,支持动态修改仿真状态
+ */
+struct OverrideState {
+ bool enabled = false; ///< 是否启用状态覆盖
+ std::uint64_t last_rev = 0; ///< 最后修订版本号
+ std::optional patch; ///< 状态补丁配置
+};
+
+/**
+ * @brief Lua运行时环境管理类
+ *
+ * 负责管理Lua脚本的执行环境,包括脚本加载、函数调用、
+ * 状态同步和错误处理等功能。
+ */
+class LuaRuntime {
+private:
+ using EmitFn = std::function; ///< 事件发射函数类型
+ using LogFn = std::function; ///< 日志记录函数类型
+
+ std::unique_ptr lua; ///< Lua状态机实例
+ sol::table blackboard; ///< 共享数据黑板
+ sol::protected_function on_init; ///< 初始化回调函数
+ sol::protected_function on_tick; ///< 定时回调函数
+ sol::protected_function on_exit; ///< 退出回调函数
+ sol::protected_function on_control; ///< 控制输入回调函数
+ sol::protected_function blackboard_snapshot; ///< 黑板快照函数
+
+ EmitFn emit; ///< 事件发射器
+ LogFn log; ///< 日志记录器
+ bool closed = false; ///< 运行时是否已关闭
+
+ /**
+ * @brief 解包Lua函数调用结果
+ *
+ * 检查Lua函数调用是否成功,如果失败则抛出异常并包含错误信息
+ *
+ * @tparam Result 结果类型
+ * @param result Lua函数调用结果
+ * @param message 错误消息前缀
+ * @return Result 解包后的结果
+ * @throws std::runtime_error 当Lua函数调用失败时抛出
+ */
+ template
+ auto unwrap_result(Result&& result, std::string_view message) -> Result {
+ if (!result.valid()) {
+ auto error = result.template get();
+ throw std::runtime_error(std::format("{}: {}", message, error.what()));
+ }
+ return result;
+ }
+
+ /**
+ * @brief 发射日志事件
+ *
+ * 将日志消息同时发送到本地日志系统和远程客户端
+ *
+ * @param level 日志级别
+ * @param message 日志消息内容
+ */
+ auto emit_log(LogLevel level, const std::string& message) -> void {
+ log(level, message);
+ emit(JsonFields{
+ {"type", std::string{"sim.log"}},
+ {"level", std::string{to_string(level)}},
+ {"message", message},
+ });
+ }
+
+ /**
+ * @brief 设置Lua包搜索路径
+ *
+ * 配置Lua模块搜索路径,确保能够正确加载项目中的Lua脚本
+ *
+ * @param lua_root Lua脚本根目录路径
+ */
+ auto set_package_path(const std::string& lua_root) -> void {
+ auto package = (*lua)["package"].get();
+ auto package_path = package["path"].get_or(std::string{});
+ package["path"] = std::format(
+ "{};{}/?.lua;{}/?/init.lua", package_path, lua_root, lua_root);
+ }
+
+ /**
+ * @brief 将YAML节点转换为Lua对象
+ *
+ * 递归地将YAML数据结构转换为对应的Lua数据类型,
+ * 支持映射、序列和标量值的转换
+ *
+ * @param node YAML节点
+ * @return sol::object 对应的Lua对象
+ */
+ [[nodiscard]] auto yaml_to_lua_object(const YAML::Node& node) -> sol::object {
+ if (!node || node.IsNull()) {
+ return sol::make_object(*lua, sol::lua_nil);
+ }
+
+ if (node.IsMap()) {
+ auto table = lua->create_table();
+ apply_table_patch(table, node);
+ return sol::make_object(*lua, table);
+ }
+
+ if (node.IsSequence()) {
+ auto table = lua->create_table(static_cast(node.size()), 0);
+ for (auto index = std::size_t{0}; index < node.size(); ++index) {
+ table[index + 1] = yaml_to_lua_object(node[index]);
+ }
+ return sol::make_object(*lua, table);
+ }
+
+ if (auto scalar = node.Scalar(); scalar == "true" || scalar == "false") {
+ return sol::make_object(*lua, scalar == "true");
+ }
+
+ try {
+ return sol::make_object(*lua, node.as());
+ } catch (...) {
+ }
+
+ try {
+ return sol::make_object(*lua, node.as());
+ } catch (...) {
+ }
+
+ return sol::make_object(*lua, node.as());
+ }
+
+ /**
+ * @brief 应用表格补丁
+ *
+ * 递归地将YAML补丁应用到Lua表格中,支持嵌套结构的深度合并
+ *
+ * @param table 目标Lua表格
+ * @param patch YAML补丁配置
+ */
+ auto apply_table_patch(sol::table table, const YAML::Node& patch) -> void {
+ if (!patch || !patch.IsMap()) {
+ return;
+ }
+
+ for (const auto& entry : patch) {
+ auto key = entry.first.as();
+ auto value = entry.second;
+ if (!value || value.IsNull()) {
+ table[key] = sol::lua_nil;
+ continue;
+ }
+
+ if (value.IsMap()) {
+ auto existing = table[key].get_or(sol::object{});
+ if (existing.valid() && existing.get_type() == sol::type::table) {
+ apply_table_patch(existing.as(), value);
+ } else {
+ auto nested = lua->create_table();
+ apply_table_patch(nested, value);
+ table[key] = nested;
+ }
+ continue;
+ }
+
+ table[key] = yaml_to_lua_object(value);
+ }
+ }
+
+ /**
+ * @brief 判断Lua表格是否为数组
+ *
+ * 检查Lua表格是否具有连续的整数键(从1开始),
+ * 用于确定应该将表格转换为YAML序列还是映射
+ *
+ * @param table 要检查的Lua表格
+ * @return true 表格是数组,false 表格是映射
+ */
+ [[nodiscard]] auto lua_table_is_array(sol::table table) -> bool {
+ auto count = std::size_t{0};
+ auto has_entries = false;
+ for (const auto& entry : table) {
+ has_entries = true;
+ if (!entry.first.is()) {
+ return false;
+ }
+
+ auto numeric_key = entry.first.as();
+ auto integer_key = static_cast(numeric_key);
+ if (numeric_key != static_cast(integer_key) || integer_key == 0) {
+ return false;
+ }
+
+ count = std::max(count, integer_key);
+ }
+
+ if (!has_entries) {
+ return false;
+ }
+
+ for (auto index = std::size_t{1}; index <= count; ++index) {
+ auto value = table[static_cast(index)].get_or(sol::object{});
+ if (!value.valid() || value == sol::lua_nil) {
+ return false;
+ }
+ }
+
+ return true;
+ }
+
+ /**
+ * @brief 将Lua对象转换为YAML节点
+ *
+ * 递归地将Lua数据类型转换为对应的YAML数据结构,
+ * 支持nil、布尔值、数字、字符串和表格的转换
+ *
+ * @param object Lua对象
+ * @return YAML::Node 对应的YAML节点
+ */
+ [[nodiscard]] auto lua_to_yaml(const sol::object& object) -> YAML::Node {
+ switch (object.get_type()) {
+ case sol::type::lua_nil: return YAML::Node{};
+ case sol::type::boolean: return YAML::Node{object.as()};
+ case sol::type::number: return YAML::Node{object.as()};
+ case sol::type::string: return YAML::Node{object.as()};
+ case sol::type::table: {
+ auto table = object.as();
+ if (lua_table_is_array(table)) {
+ auto sequence = YAML::Node{YAML::NodeType::Sequence};
+ auto count = std::size_t{0};
+ for (const auto& entry : table) {
+ count = std::max(count, static_cast(entry.first.as()));
+ }
+ for (auto index = std::size_t{1}; index <= count; ++index) {
+ sequence.push_back(lua_to_yaml(table[static_cast(index)].get()));
+ }
+ return sequence;
+ }
+
+ auto mapping = YAML::Node{YAML::NodeType::Map};
+ for (const auto& entry : table) {
+ if (!entry.first.is()) {
+ continue;
+ }
+
+ mapping[entry.first.as()] = lua_to_yaml(entry.second.as());
+ }
+ return mapping;
+ }
+ default: return YAML::Node{};
+ }
+ }
+
+ /**
+ * @brief 注入API函数到Lua环境
+ *
+ * 将C++实现的API函数注册到Lua环境中,供Lua脚本调用
+ * 包括日志记录、导航控制、底盘控制等功能
+ */
+ auto inject_api() -> void {
+ auto api_result = unwrap_result(
+ lua->safe_script("return require('api')", sol::script_pass_on_error),
+ "failed to load api");
+
+ auto api = api_result.get();
+ api.set_function("info", [this](const std::string& text) { emit_log(LogLevel::Info, text); });
+ api.set_function("warn", [this](const std::string& text) { emit_log(LogLevel::Warn, text); });
+ api.set_function("fuck", [this](const std::string& text) { emit_log(LogLevel::Error, text); });
+
+ api.set_function("send_target", [this](double x, double y) {
+ emit(JsonFields{
+ {"type", std::string{"sim.nav_target"}},
+ {"x", x},
+ {"y", y},
+ });
+ });
+ api.set_function("update_gimbal_direction", [this](double angle) {
+ emit(JsonFields{
+ {"type", std::string{"sim.gimbal_direction"}},
+ {"angle", angle},
+ });
+ });
+ api.set_function("update_gimbal_dominator", [this](const std::string& name) {
+ emit(JsonFields{
+ {"type", std::string{"sim.gimbal_dominator"}},
+ {"name", name},
+ });
+ });
+ api.set_function("update_chassis_mode", [this](const std::string& mode) {
+ emit(JsonFields{
+ {"type", std::string{"sim.chassis_mode"}},
+ {"mode", mode},
+ });
+ });
+ api.set_function("update_chassis_vel", [this](double x, double y) {
+ emit(JsonFields{
+ {"type", std::string{"sim.chassis_vel"}},
+ {"x", x},
+ {"y", y},
+ });
+ });
+
+ // Sidecar mode: keep these entry points but avoid touching ROS processes.
+ api.set_function("switch_topic_forward", [this](bool enable) {
+ emit_log(LogLevel::Info, std::format("switch_topic_forward no-op: {}", enable));
+ });
+ api.set_function("restart_navigation", [this](const sol::table&) {
+ emit_log(LogLevel::Info, "restart_navigation no-op in sim mode");
+ return std::tuple{true, std::string{"ok"}};
+ });
+ api.set_function("stop_navigation", [this]() {
+ emit_log(LogLevel::Info, "stop_navigation no-op in sim mode");
+ return std::tuple{true, std::string{"ok"}};
+ });
+ }
+
+ auto inject_option(const std::optional& option_patch) -> void {
+ auto option_result = unwrap_result(
+ lua->safe_script("return require('option')", sol::script_pass_on_error),
+ "failed to load option");
+ auto option = option_result.get();
+
+ option["decision"] = std::string{"auxiliary"};
+ option["enable_goal_topic_forward"] = false;
+ option["sim_mode"] = true;
+
+ if (option_patch && option_patch->IsMap()) {
+ apply_table_patch(option, *option_patch);
+ }
+ }
+
+public:
+ /**
+ * @brief LuaRuntime构造函数
+ *
+ * 初始化Lua运行时环境,加载必要的库、配置包路径、注入API函数,
+ * 并加载指定的Lua端点脚本
+ *
+ * @param lua_root Lua脚本根目录路径
+ * @param endpoint 要加载的Lua端点名称
+ * @param emit_action 事件发射函数
+ * @param log_action 日志记录函数
+ * @param option_patch 可选配置补丁
+ * @throws std::runtime_error 当Lua环境初始化失败时抛出
+ */
+
+ explicit LuaRuntime(
+ const std::string& lua_root,
+ const std::string& endpoint,
+ EmitFn emit_action,
+ LogFn log_action,
+ std::optional option_patch = std::nullopt)
+ : lua{std::make_unique()}
+ , emit{std::move(emit_action)}
+ , log{std::move(log_action)} {
+ lua->open_libraries(
+ sol::lib::base, sol::lib::coroutine, sol::lib::math, sol::lib::os, sol::lib::package,
+ sol::lib::string, sol::lib::table, sol::lib::debug, sol::lib::io);
+
+ set_package_path(lua_root);
+ inject_api();
+ inject_option(option_patch);
+
+ auto required = std::format("require('endpoint.{}')", endpoint);
+ auto endpoint_result = unwrap_result(
+ lua->safe_script(required, sol::script_pass_on_error),
+ "failed to load endpoint");
+ (void)endpoint_result;
+
+ auto blackboard_sync_result = unwrap_result(
+ lua->safe_script("return require('blackboard_sync')", sol::script_pass_on_error),
+ "failed to load blackboard_sync");
+ auto blackboard_sync = blackboard_sync_result.get();
+
+ blackboard = (*lua)["blackboard"];
+ on_init = (*lua)["on_init"];
+ on_tick = (*lua)["on_tick"];
+ if (!on_init.valid() || !on_tick.valid()) {
+ throw std::runtime_error("lua endpoint must define on_init() and on_tick()");
+ }
+
+ on_exit = (*lua)["on_exit"];
+ if (on_exit == sol::lua_nil) {
+ on_exit = lua->safe_script("return function() end", sol::script_pass_on_error);
+ }
+ on_control = (*lua)["on_control"];
+ if (on_control == sol::lua_nil) {
+ on_control = lua->safe_script("return function(_, _, _) end", sol::script_pass_on_error);
+ }
+
+ blackboard_snapshot = blackboard_sync["snapshot"];
+ if (!blackboard_snapshot.valid()) {
+ throw std::runtime_error("blackboard_sync must define snapshot()");
+ }
+
+ unwrap_result(on_init(), "lua on_init failed");
+ emit_log(LogLevel::Info, "lua runtime initialized");
+ }
+
+ /// @brief 析构函数,自动关闭Lua运行时
+ ~LuaRuntime() { close(); }
+
+ /**
+ * @brief 关闭Lua运行时
+ *
+ * 执行清理操作,调用Lua端点的on_exit函数,
+ * 确保资源正确释放,避免内存泄漏
+ */
+ auto close() -> void {
+ if (closed) {
+ return;
+ }
+ closed = true;
+ try {
+ unwrap_result(on_exit(), "lua on_exit failed");
+ } catch (const std::exception& exception) {
+ emit_log(LogLevel::Error, std::format("on_exit failed: {}", exception.what()));
+ }
+ }
+
+ /**
+ * @brief 应用仿真状态到Lua黑板
+ *
+ * 将C++端的仿真状态同步到Lua运行时的共享数据黑板,
+ * 支持可选字段的健康值和子弹数量更新
+ *
+ * @param state 要应用的仿真状态
+ */
+
+ auto apply_state(const SimState& state) -> void {
+ auto user = blackboard["user"].get();
+ user["chassis_power_limit"] = state.user.chassis_power_limit;
+ user["x"] = state.user.x;
+ user["y"] = state.user.y;
+ user["yaw"] = state.user.yaw;
+ if (state.user.health) {
+ user["health"] = *state.user.health;
+ }
+ if (state.user.bullet) {
+ user["bullet"] = *state.user.bullet;
+ }
+
+ auto game = blackboard["game"].get();
+ if (state.game.base_health) {
+ game["base_health"] = *state.game.base_health;
+ }
+ if (state.game.outpost_health) {
+ game["outpost_health"] = *state.game.outpost_health;
+ }
+ if (state.game.gold_coin) {
+ game["gold_coin"] = *state.game.gold_coin;
+ }
+ if (state.game.remaining_time) {
+ game["remaining_time"] = *state.game.remaining_time;
+ }
+ if (state.game.exchangeable_ammunition_quantity) {
+ game["exchangeable_ammunition_quantity"] = *state.game.exchangeable_ammunition_quantity;
+ }
+ if (state.game.our_dart_nmber_of_hits) {
+ game["our_dart_nmber_of_hits"] = *state.game.our_dart_nmber_of_hits;
+ }
+ if (state.game.fortress_occupied) {
+ game["fortress_occupied"] = *state.game.fortress_occupied;
+ }
+ if (state.game.big_energy_mechanism_activated) {
+ game["big_energy_mechanism_activated"] = *state.game.big_energy_mechanism_activated;
+ }
+ if (state.game.small_energy_mechanism_activated) {
+ game["small_energy_mechanism_activated"] =
+ *state.game.small_energy_mechanism_activated;
+ }
+
+ auto meta = blackboard["meta"].get();
+ meta["timestamp"] = state.meta.timestamp;
+ }
+
+ /**
+ * @brief 应用状态覆盖补丁
+ *
+ * 将YAML格式的状态覆盖补丁应用到Lua黑板,
+ * 支持动态修改仿真状态参数
+ *
+ * @param patch 状态覆盖补丁
+ */
+
+ auto apply_override_patch(const YAML::Node& patch) -> void {
+ apply_table_patch(blackboard, patch);
+ }
+
+ /**
+ * @brief 获取Lua黑板快照
+ *
+ * 调用Lua端的快照函数,将当前黑板状态转换为YAML格式,
+ * 用于状态报告和决策状态构建
+ *
+ * @return YAML::Node 黑板状态快照
+ * @throws std::runtime_error 当快照操作失败时抛出
+ */
+ [[nodiscard]] auto snapshot_blackboard() -> YAML::Node {
+ auto result = unwrap_result(blackboard_snapshot(), "lua blackboard snapshot failed");
+ return lua_to_yaml(result.get());
+ }
+
+ /**
+ * @brief 执行定时回调
+ *
+ * 调用Lua端点的on_tick函数,执行周期性的逻辑处理,
+ * 这是仿真循环的核心执行点
+ *
+ * @throws std::runtime_error 当定时回调执行失败时抛出
+ */
+
+ auto tick() -> void { unwrap_result(on_tick(), "lua on_tick failed"); }
+
+ /**
+ * @brief 输入控制命令
+ *
+ * 将控制输入传递给Lua端点,用于处理底盘速度控制等命令
+ *
+ * @param vx X方向速度
+ * @param vy Y方向速度
+ * @param qx 旋转控制参数
+ * @throws std::runtime_error 当控制命令处理失败时抛出
+ */
+
+ auto feed_control(double vx, double vy, double qx) -> void {
+ unwrap_result(on_control(vx, vy, qx), "lua on_control failed");
+ }
+
+ /**
+ * @brief 调用仿真目标设置函数
+ *
+ * 如果Lua端点定义了on_sim_set_target函数,则调用该函数设置目标位置
+ *
+ * @param x 目标X坐标
+ * @param y 目标Y坐标
+ */
+ auto call_sim_set_target(double x, double y) -> void {
+ auto function = (*lua)["on_sim_set_target"];
+ if (!function.valid() || function.get_type() != sol::type::function) {
+ return;
+ }
+ auto callback = function.get();
+ unwrap_result(callback(x, y), "lua on_sim_set_target failed");
+ }
+
+ /**
+ * @brief 调用仿真启动函数
+ *
+ * 如果Lua端点定义了on_sim_start函数,则调用该函数启动仿真,
+ * 支持可选的目标位置参数
+ *
+ * @param x 可选的目标X坐标
+ * @param y 可选的目标Y坐标
+ */
+ auto call_sim_start(const std::optional& x, const std::optional& y) -> void {
+ auto function = (*lua)["on_sim_start"];
+ if (!function.valid() || function.get_type() != sol::type::function) {
+ return;
+ }
+ auto callback = function.get();
+ if (x && y) {
+ unwrap_result(callback(*x, *y), "lua on_sim_start failed");
+ return;
+ }
+
+ unwrap_result(callback(sol::lua_nil, sol::lua_nil), "lua on_sim_start failed");
+ }
+};
+
+/**
+ * @brief 命令行参数结构
+ *
+ * 存储仿真侧车服务的运行配置参数
+ */
+struct Args {
+ std::string host = "0.0.0.0"; ///< 服务器绑定主机地址
+ int port = 34567; ///< 服务器绑定端口号
+ std::string endpoint = "train-decision"; ///< Lua端点名称
+ std::string lua_root = RMCS_NAVIGATION_SOURCE_DIR "/src/lua"; ///< Lua脚本根目录
+ double tick_hz = 10.0; ///< 定时器频率(Hz)
+ int state_timeout_ms = 500; ///< 状态超时时间(毫秒)
+ std::optional option_file; ///< 可选配置文件路径
+};
+
+[[nodiscard]] auto parse_args(int argc, char** argv) -> Args {
+ auto args = Args{};
+ for (auto index = 1; index < argc; ++index) {
+ auto token = std::string_view{argv[index]};
+ auto take_next = [&](std::string_view name) {
+ if (index + 1 >= argc) {
+ throw std::runtime_error(std::format("{} requires a value", name));
+ }
+ ++index;
+ return std::string{argv[index]};
+ };
+
+ if (token == "--host") {
+ args.host = take_next(token);
+ } else if (token == "--port") {
+ args.port = std::stoi(take_next(token));
+ } else if (token == "--endpoint") {
+ args.endpoint = take_next(token);
+ } else if (token == "--lua-root") {
+ args.lua_root = take_next(token);
+ } else if (token == "--tick-hz") {
+ args.tick_hz = std::stod(take_next(token));
+ } else if (token == "--state-timeout-ms") {
+ args.state_timeout_ms = std::stoi(take_next(token));
+ } else if (token == "--option-file") {
+ args.option_file = take_next(token);
+ } else if (token == "--help" || token == "-h") {
+ std::cout
+ << "rmcs-navigation-sim-sidecar\n"
+ << " --host (default: 0.0.0.0)\n"
+ << " --port (default: 34567)\n"
+ << " --endpoint (default: train-decision)\n"
+ << " --lua-root (default: /src/lua)\n"
+ << " --tick-hz (default: 10)\n"
+ << " --state-timeout-ms (default: 500)\n"
+ << " --option-file \n";
+ std::exit(0);
+ } else {
+ throw std::runtime_error(std::format("unknown argument: {}", token));
+ }
+ }
+
+ if (args.port <= 0 || args.port > 65535) {
+ throw std::runtime_error("port must be between 1 and 65535");
+ }
+ if (!(args.tick_hz > 0.0)) {
+ throw std::runtime_error("tick-hz must be > 0");
+ }
+ if (args.state_timeout_ms < 0) {
+ throw std::runtime_error("state-timeout-ms must be >= 0");
+ }
+
+ return args;
+}
+
+[[nodiscard]] auto create_server_socket(const std::string& host, int port) -> ScopedFd {
+ auto hints = addrinfo{};
+ hints.ai_family = AF_UNSPEC;
+ hints.ai_socktype = SOCK_STREAM;
+ hints.ai_flags = AI_PASSIVE;
+
+ auto service = std::to_string(port);
+ addrinfo* result = nullptr;
+ auto ret = ::getaddrinfo(host.c_str(), service.c_str(), &hints, &result);
+ if (ret != 0) {
+ throw std::runtime_error(std::format("getaddrinfo failed: {}", gai_strerror(ret)));
+ }
+
+ auto cleanup = std::unique_ptr{result, ::freeaddrinfo};
+ for (auto* it = result; it != nullptr; it = it->ai_next) {
+ auto fd = ScopedFd{::socket(it->ai_family, it->ai_socktype, it->ai_protocol)};
+ if (!fd.valid()) {
+ continue;
+ }
+
+ int enable = 1;
+ ::setsockopt(fd.value, SOL_SOCKET, SO_REUSEADDR, &enable, sizeof(enable));
+
+ if (::bind(fd.value, it->ai_addr, it->ai_addrlen) != 0) {
+ continue;
+ }
+
+ if (::listen(fd.value, 1) != 0) {
+ continue;
+ }
+
+ return fd;
+ }
+
+ throw std::runtime_error("failed to bind server socket");
+}
+
+/**
+ * @brief 从YAML负载更新仿真状态
+ *
+ * 解析接收到的YAML消息,更新用户状态和元数据
+ * 支持可选字段的健康值和子弹数量更新
+ *
+ * @param root 接收到的YAML根节点
+ * @param state 要更新的仿真状态引用
+ */
+auto update_state_from_payload(const YAML::Node& root, SimState& state) -> void {
+ auto user = root["user"];
+ if (user && user.IsMap()) {
+ assign_if_present(
+ user,
+ "chassis_power_limit",
+ state.user.chassis_power_limit,
+ [](const YAML::Node& node) { return parse_double(node); });
+ assign_if_present(user, "x", state.user.x, [](const YAML::Node& node) {
+ return parse_double(node);
+ });
+ assign_if_present(user, "y", state.user.y, [](const YAML::Node& node) {
+ return parse_double(node);
+ });
+ assign_if_present(user, "yaw", state.user.yaw, [](const YAML::Node& node) {
+ return parse_double(node);
+ });
+ if (user["health"] && !user["health"].IsNull()) {
+ state.user.health = parse_double(user["health"]);
+ }
+ if (user["bullet"] && !user["bullet"].IsNull()) {
+ state.user.bullet = parse_double(user["bullet"]);
+ }
+ }
+
+ auto game = root["game"];
+ if (game && game.IsMap()) {
+ if (game["base_health"] && !game["base_health"].IsNull()) {
+ state.game.base_health = parse_double(game["base_health"]);
+ }
+ if (game["outpost_health"] && !game["outpost_health"].IsNull()) {
+ state.game.outpost_health = parse_double(game["outpost_health"]);
+ }
+ if (game["gold_coin"] && !game["gold_coin"].IsNull()) {
+ state.game.gold_coin = parse_double(game["gold_coin"]);
+ }
+ if (game["remaining_time"] && !game["remaining_time"].IsNull()) {
+ state.game.remaining_time = parse_double(game["remaining_time"]);
+ }
+ if (game["exchangeable_ammunition_quantity"]
+ && !game["exchangeable_ammunition_quantity"].IsNull()) {
+ state.game.exchangeable_ammunition_quantity =
+ parse_double(game["exchangeable_ammunition_quantity"]);
+ }
+ if (game["our_dart_nmber_of_hits"] && !game["our_dart_nmber_of_hits"].IsNull()) {
+ state.game.our_dart_nmber_of_hits = parse_double(game["our_dart_nmber_of_hits"]);
+ }
+ if (game["fortress_occupied"] && !game["fortress_occupied"].IsNull()) {
+ state.game.fortress_occupied = parse_boolean(game["fortress_occupied"]);
+ }
+ if (game["big_energy_mechanism_activated"]
+ && !game["big_energy_mechanism_activated"].IsNull()) {
+ state.game.big_energy_mechanism_activated =
+ parse_boolean(game["big_energy_mechanism_activated"]);
+ }
+ if (game["small_energy_mechanism_activated"]
+ && !game["small_energy_mechanism_activated"].IsNull()) {
+ state.game.small_energy_mechanism_activated =
+ parse_boolean(game["small_energy_mechanism_activated"]);
+ }
+ }
+
+ auto meta = root["meta"];
+ if (meta && meta.IsMap()) {
+ assign_if_present(
+ meta,
+ "timestamp",
+ state.meta.timestamp,
+ [](const YAML::Node& node) { return parse_double(node); });
+ }
+}
+
+/**
+ * @brief 检查YAML节点是否包含有效条目
+ *
+ * 验证节点是否为非空映射,用于判断是否需要进行进一步处理
+ *
+ * @param node 要检查的YAML节点
+ * @return true 节点包含有效条目,false 节点为空或无效
+ */
+[[nodiscard]] auto has_entries(const YAML::Node& node) -> bool {
+ return node && node.IsMap() && node.size() > 0;
+}
+
+/**
+ * @brief 过滤状态覆盖补丁
+ *
+ * 从完整的覆盖补丁中提取允许修改的字段,
+ * 限制客户端只能修改特定的状态字段,确保系统安全性
+ *
+ * @param patch 原始覆盖补丁
+ * @return YAML::Node 过滤后的安全补丁
+ */
+[[nodiscard]] auto filter_override_patch(const YAML::Node& patch) -> YAML::Node {
+ auto result = YAML::Node{YAML::NodeType::Map};
+ if (!patch || !patch.IsMap()) {
+ return result;
+ }
+
+ auto user = patch["user"];
+ if (user && user.IsMap()) {
+ auto filtered_user = YAML::Node{YAML::NodeType::Map};
+ if (user["health"]) {
+ filtered_user["health"] = user["health"];
+ }
+ if (user["bullet"]) {
+ filtered_user["bullet"] = user["bullet"];
+ }
+ if (has_entries(filtered_user)) {
+ result["user"] = filtered_user;
+ }
+ }
+
+ auto game = patch["game"];
+ if (game && game.IsMap()) {
+ auto filtered_game = YAML::Node{YAML::NodeType::Map};
+ if (game["stage"])
+ filtered_game["stage"] = game["stage"];
+ if (game["remaining_time"])
+ filtered_game["remaining_time"] = game["remaining_time"];
+ if (game["our_dart_nmber_of_hits"])
+ filtered_game["our_dart_nmber_of_hits"] = game["our_dart_nmber_of_hits"];
+ if (game["fortress_occupied"])
+ filtered_game["fortress_occupied"] = game["fortress_occupied"];
+ if (game["big_energy_mechanism_activated"])
+ filtered_game["big_energy_mechanism_activated"] =
+ game["big_energy_mechanism_activated"];
+ if (game["small_energy_mechanism_activated"])
+ filtered_game["small_energy_mechanism_activated"] =
+ game["small_energy_mechanism_activated"];
+ if (has_entries(filtered_game))
+ result["game"] = filtered_game;
+ }
+
+ auto play = patch["play"];
+ if (play && play.IsMap()) {
+ auto filtered_play = YAML::Node{YAML::NodeType::Map};
+ if (play["rswitch"]) {
+ filtered_play["rswitch"] = play["rswitch"];
+ }
+ if (play["lswitch"]) {
+ filtered_play["lswitch"] = play["lswitch"];
+ }
+ if (has_entries(filtered_play)) {
+ result["play"] = filtered_play;
+ }
+ }
+
+ return result;
+}
+
+/**
+ * @brief 构建决策状态快照
+ *
+ * 从完整的Lua黑板快照中提取决策相关的关键状态信息,
+ * 用于向客户端报告当前决策状态和任务进度
+ *
+ * @param snapshot Lua黑板完整快照
+ * @return YAML::Node 精简的决策状态信息
+ */
+[[nodiscard]] auto build_decision_state(const YAML::Node& snapshot) -> YAML::Node {
+ auto state = YAML::Node{YAML::NodeType::Map};
+
+ auto meta = snapshot["meta"];
+ if (meta && meta.IsMap() && meta["fsm_state"]) {
+ state["fsm_state"] = meta["fsm_state"];
+ }
+
+ auto result = snapshot["result"];
+ if (result && result.IsMap()) {
+ if (result["intent"]) {
+ state["intent"] = result["intent"];
+ }
+ if (result["task"]) {
+ state["task"] = result["task"];
+ }
+ if (result["progress"]) {
+ state["progress"] = result["progress"];
+ }
+ if (result["last_reason"]) {
+ state["last_reason"] = result["last_reason"];
+ }
+ if (result["job_done"]) {
+ state["job_done"] = result["job_done"];
+ }
+ if (result["job_success"]) {
+ state["job_success"] = result["job_success"];
+ }
+ }
+
+ auto game = snapshot["game"];
+ if (game && game.IsMap() && game["stage"]) {
+ state["stage"] = game["stage"];
+ }
+
+ auto user = snapshot["user"];
+ if (user && user.IsMap()) {
+ if (user["health"]) {
+ state["health"] = user["health"];
+ }
+ if (user["bullet"]) {
+ state["bullet"] = user["bullet"];
+ }
+ }
+
+ return state;
+}
+
+struct ClientRuntime {
+ SimState state;
+ OverrideState override_state;
+ bool has_input = false;
+ bool has_initial_remaining_time = false;
+ bool waiting_for_initial_remaining_time_logged = false;
+ std::chrono::steady_clock::time_point last_input_time = std::chrono::steady_clock::now();
+};
+
+/**
+ * @brief 处理客户端消息
+ *
+ * 根据消息类型分发处理逻辑,支持状态更新、控制输入、
+ * 状态覆盖和仿真控制等不同类型的消息
+ *
+ * @param runtime Lua运行时环境
+ * @param root 接收到的消息根节点
+ * @param context 客户端运行时上下文
+ * @param log 日志记录函数
+ */
+auto process_message(
+ LuaRuntime& runtime,
+ const YAML::Node& root,
+ ClientRuntime& context,
+ const std::function& log) -> void {
+ auto type_node = root["type"];
+ if (!type_node) {
+ log(LogLevel::Warn, "received message without type");
+ return;
+ }
+
+ auto type = parse_string(type_node);
+ auto now = std::chrono::steady_clock::now();
+
+ if (type == "sim.hello") {
+ log(LogLevel::Info, "client hello");
+ return;
+ }
+
+ if (type == "sim.input") {
+ auto payload = root["input"];
+ if (!payload || !payload.IsMap()) {
+ payload = root;
+ }
+
+ update_state_from_payload(payload, context.state);
+ if (context.state.game.remaining_time.has_value()) {
+ context.has_initial_remaining_time = true;
+ context.waiting_for_initial_remaining_time_logged = false;
+ }
+
+ auto control = payload["control"];
+ if (control && control.IsMap()) {
+ auto vx = parse_double(control["vx"], 0.0);
+ auto vy = parse_double(control["vy"], 0.0);
+ auto qx = parse_double(control["qx"], 0.0);
+ runtime.feed_control(vx, vy, qx);
+ }
+
+ context.has_input = true;
+ context.last_input_time = now;
+ return;
+ }
+
+ if (type == "sim.override_mode") {
+ context.override_state.enabled = parse_boolean(root["enabled"], false);
+ if (!context.override_state.enabled) {
+ context.override_state.patch.reset();
+ }
+
+ log(
+ LogLevel::Info,
+ std::format("override mode -> {}", context.override_state.enabled ? "enabled" : "disabled"));
+
+ context.has_input = true;
+ context.last_input_time = now;
+ return;
+ }
+
+ if (type == "sim.override_patch") {
+ if (!root["rev"]) {
+ log(LogLevel::Warn, "override patch missing rev");
+ return;
+ }
+
+ auto rev = parse_revision(root["rev"], 0);
+ if (rev <= context.override_state.last_rev) {
+ log(LogLevel::Warn, std::format("ignored stale override patch rev={}", rev));
+ return;
+ }
+
+ auto patch = root["patch"];
+ if (!patch || !patch.IsMap()) {
+ log(LogLevel::Warn, std::format("override patch rev={} missing patch map", rev));
+ context.override_state.last_rev = rev;
+ return;
+ }
+
+ auto filtered = filter_override_patch(patch);
+ context.override_state.last_rev = rev;
+
+ if (!has_entries(filtered)) {
+ log(LogLevel::Warn, std::format("override patch rev={} has no writable fields", rev));
+ return;
+ }
+
+ if (!context.override_state.enabled) {
+ context.override_state.patch.reset();
+ log(LogLevel::Warn, std::format("override patch rev={} ignored while mode disabled", rev));
+ return;
+ }
+
+ context.override_state.patch = filtered;
+ context.has_input = true;
+ context.last_input_time = now;
+ return;
+ }
+
+ if (type == "sim.command") {
+ auto command = parse_string(root["command"]);
+ if (command == "start_decision") {
+ auto x = std::optional{};
+ auto y = std::optional{};
+ if (root["x"]) {
+ x = parse_double(root["x"], 0.0);
+ }
+ if (root["y"]) {
+ y = parse_double(root["y"], 0.0);
+ }
+ runtime.call_sim_start(x, y);
+ context.has_input = true;
+ context.last_input_time = now;
+ return;
+ }
+
+ if (command == "set_target") {
+ auto x = parse_double(root["x"], 0.0);
+ auto y = parse_double(root["y"], 0.0);
+ runtime.call_sim_set_target(x, y);
+ return;
+ }
+
+ log(LogLevel::Warn, std::format("unknown sim.command: {}", command));
+ return;
+ }
+
+ log(LogLevel::Warn, std::format("unknown message type: {}", type));
+}
+
+auto handle_client(const Args& args, int client_fd) -> void {
+ auto context = ClientRuntime{};
+ auto input_is_stale = false;
+ auto input_buffer = std::string{};
+ auto bb_rev = std::uint64_t{0};
+
+ auto write_message = [client_fd](const JsonFields& fields) {
+ auto payload = to_json(fields);
+ send_line(client_fd, payload);
+ };
+
+ auto logger = [&](LogLevel level, const std::string& message) {
+ std::cerr << std::format("[sim-sidecar][{}] {}\n", to_string(level), message);
+ };
+
+ auto option_patch = std::optional{};
+ if (args.option_file) {
+ option_patch = YAML::LoadFile(*args.option_file);
+ }
+
+ auto runtime = LuaRuntime{
+ args.lua_root,
+ args.endpoint,
+ write_message,
+ logger,
+ option_patch,
+ };
+
+ auto emit_runtime_state = [&]() {
+ auto snapshot = runtime.snapshot_blackboard();
+ ++bb_rev;
+
+ auto blackboard_msg = YAML::Node{YAML::NodeType::Map};
+ blackboard_msg["type"] = "sim.blackboard";
+ blackboard_msg["bb_rev"] = static_cast(bb_rev);
+ blackboard_msg["blackboard"] = snapshot;
+ send_line(client_fd, to_json(blackboard_msg));
+
+ auto decision_msg = YAML::Node{YAML::NodeType::Map};
+ decision_msg["type"] = "sim.decision_state";
+ decision_msg["bb_rev"] = static_cast(bb_rev);
+ decision_msg["state"] = build_decision_state(snapshot);
+ send_line(client_fd, to_json(decision_msg));
+ };
+
+ emit_runtime_state();
+
+ auto period =
+ std::chrono::duration_cast(
+ std::chrono::duration{1.0 / args.tick_hz});
+ auto next_tick = std::chrono::steady_clock::now() + period;
+
+ while (true) {
+ auto timeout = to_steady_timeout(next_tick);
+ auto fd = pollfd{
+ .fd = client_fd,
+ .events = POLLIN,
+ .revents = 0,
+ };
+ auto result = ::poll(&fd, 1, timeout);
+ if (result < 0) {
+ if (errno == EINTR) {
+ continue;
+ }
+ throw std::runtime_error(std::format("poll failed: {}", std::strerror(errno)));
+ }
+
+ if ((fd.revents & POLLIN) != 0) {
+ auto chunk = std::array{};
+ auto recv_size = ::recv(client_fd, chunk.data(), chunk.size(), 0);
+ if (recv_size <= 0) {
+ return;
+ }
+
+ input_buffer.append(chunk.data(), static_cast(recv_size));
+ while (true) {
+ auto pos = input_buffer.find('\n');
+ if (pos == std::string::npos) {
+ break;
+ }
+
+ auto line = trim(input_buffer.substr(0, pos));
+ input_buffer.erase(0, pos + 1);
+ if (line.empty()) {
+ continue;
+ }
+
+ try {
+ auto message = YAML::Load(line);
+ if (!message || !message.IsMap()) {
+ logger(LogLevel::Warn, "ignored non-object message");
+ continue;
+ }
+ process_message(runtime, message, context, logger);
+ } catch (const std::exception& exception) {
+ logger(LogLevel::Warn, std::format("invalid message: {}", exception.what()));
+ }
+ }
+ }
+
+ auto now = std::chrono::steady_clock::now();
+ if (now < next_tick) {
+ continue;
+ }
+
+ while (next_tick <= now) {
+ next_tick += period;
+ }
+
+ if (!context.has_input) {
+ continue;
+ }
+
+ auto stale_duration = std::chrono::milliseconds{args.state_timeout_ms};
+ if ((now - context.last_input_time) > stale_duration) {
+ if (!input_is_stale) {
+ input_is_stale = true;
+ logger(
+ LogLevel::Warn,
+ std::format("input timeout > {}ms, tick paused", args.state_timeout_ms));
+ }
+ continue;
+ }
+
+ if (input_is_stale) {
+ input_is_stale = false;
+ logger(LogLevel::Info, "input stream resumed");
+ }
+
+ runtime.apply_state(context.state);
+ if (context.override_state.enabled && context.override_state.patch && context.override_state.patch->IsMap()) {
+ runtime.apply_override_patch(*context.override_state.patch);
+ }
+
+ auto blackboard_snapshot = runtime.snapshot_blackboard();
+ auto game = blackboard_snapshot["game"];
+ auto stage = parse_string(game["stage"], "UNKNOWN");
+ if (stage == "STARTED" && !context.has_initial_remaining_time) {
+ if (!context.waiting_for_initial_remaining_time_logged) {
+ context.waiting_for_initial_remaining_time_logged = true;
+ logger(
+ LogLevel::Info,
+ "waiting for initial game.remaining_time before STARTED tick");
+ }
+ emit_runtime_state();
+ continue;
+ }
+
+ runtime.tick();
+
+ if (context.override_state.enabled && context.override_state.patch && context.override_state.patch->IsMap()) {
+ runtime.apply_override_patch(*context.override_state.patch);
+ }
+
+ emit_runtime_state();
+ }
+}
+
+auto run(const Args& args) -> int {
+ auto server = create_server_socket(args.host, args.port);
+ std::cerr << std::format(
+ "[sim-sidecar][info] listening on {}:{}, endpoint={}\n",
+ args.host,
+ args.port,
+ args.endpoint);
+
+ while (true) {
+ auto client = ScopedFd{::accept(server.value, nullptr, nullptr)};
+ if (!client.valid()) {
+ if (errno == EINTR) {
+ continue;
+ }
+ throw std::runtime_error(std::format("accept failed: {}", std::strerror(errno)));
+ }
+
+ std::cerr << "[sim-sidecar][info] client connected\n";
+ try {
+ handle_client(args, client.value);
+ } catch (const std::exception& exception) {
+ std::cerr << std::format("[sim-sidecar][error] client failed: {}\n", exception.what());
+ }
+ std::cerr << "[sim-sidecar][info] client disconnected\n";
+ }
+}
+
+} // namespace rmcs::navigation::sim
+
+auto main(int argc, char** argv) -> int {
+ try {
+ auto args = rmcs::navigation::sim::parse_args(argc, argv);
+ return rmcs::navigation::sim::run(args);
+ } catch (const std::exception& exception) {
+ std::cerr << std::format("[sim-sidecar][fatal] {}\n", exception.what());
+ return 1;
+ }
+}
diff --git a/src/cxx/util/localization/engine.cc b/src/cxx/util/localization/engine.cc
new file mode 100644
index 0000000..b7bc6fe
--- /dev/null
+++ b/src/cxx/util/localization/engine.cc
@@ -0,0 +1,90 @@
+#include "cxx/util/localization/engine.hh"
+#include "cxx/util/node_mixin.hh"
+
+#include
+#include
+#include
+#include
+
+#include
+#include
+#include
+
+namespace rmcs::navigation {
+
+struct Localization::Impl {
+ Config config;
+ LoggerWrap logging;
+
+ struct Context {
+ using Point = pcl::PointXYZ;
+ using Cloud = pcl::PointCloud;
+
+ std::shared_ptr> subscription;
+ std::atomic stop_collecting = false;
+
+ std::shared_ptr map;
+ std::shared_ptr collected = std::make_shared();
+
+ explicit Context(Config& config) {
+ const auto& filename = config.map_filename;
+ if (pcl::io::loadPCDFile(filename, *map) != 0)
+ throw std::runtime_error{"Couldn't read " + filename};
+
+ auto& rclcpp = config.rclcpp;
+ subscription = rclcpp.create_subscription(
+ config.topic_registered, 10,
+ [this](const std::unique_ptr& msg) {
+ if (!stop_collecting) {
+ auto received = Cloud{};
+ pcl::fromROSMsg(*msg, received);
+
+ *collected += received;
+ }
+ });
+ }
+ } context;
+
+ pcl::NormalDistributionsTransform engine;
+
+ explicit Impl(Localization::Config config)
+ : config{std::move(config)}
+ , logging{config.rclcpp}
+ , context{config} {
+
+ engine.setTransformationEpsilon(config.ndt_result_epsilon); // 收敛判定阈值
+ engine.setStepSize(config.ndt_step_size); // More-Thuente 线搜索最大步长
+ engine.setResolution(config.ndt_resolution); // NDT 网格分辨率
+ engine.setMaximumIterations(config.ndt_max_iterations); // 最大迭代次数
+ }
+
+ auto start_collecting(std::chrono::seconds seconds) -> std::expected {
+ std::ignore = this;
+ std::ignore = seconds;
+ return {};
+ }
+
+ auto start_localizing(const Eigen::Isometry3d& initial_solution)
+ -> std::future> {
+ std::ignore = this;
+ std::ignore = initial_solution;
+ return {};
+ }
+};
+
+Localization::Localization(Config config)
+ : pimpl{std::make_unique(std::move(config))} {}
+
+Localization::~Localization() noexcept = default;
+
+auto Localization::start_collecting(std::chrono::seconds seconds)
+ -> std::expected {
+ return pimpl->start_collecting(seconds);
+}
+
+auto Localization::start_localizing(const Eigen::Isometry3d& initial_solution)
+ -> std::future> {
+ return pimpl->start_localizing(initial_solution);
+}
+
+} // namespace rmcs::navigation
diff --git a/src/cxx/util/localization/engine.hh b/src/cxx/util/localization/engine.hh
new file mode 100644
index 0000000..ac111e5
--- /dev/null
+++ b/src/cxx/util/localization/engine.hh
@@ -0,0 +1,37 @@
+#pragma once
+#include "cxx/util/pimpl.hh"
+
+#include
+#include
+#include
+#include
+
+namespace rmcs::navigation {
+
+class Localization {
+ RMCS_PIMPL_DEFINITION(Localization)
+
+public:
+ struct Config {
+ rclcpp::Node& rclcpp;
+
+ std::string topic_registered;
+ std::string map_filename;
+
+ float ndt_resolution = 1.0;
+ double ndt_step_size = 0.1;
+ double ndt_result_epsilon = 0.01;
+ int ndt_max_iterations = 50;
+ };
+
+ explicit Localization(Config config);
+
+ // 开始收集配准好的点云
+ auto start_collecting(std::chrono::seconds seconds) -> std::expected;
+
+ // 开始重定位
+ auto start_localizing(const Eigen::Isometry3d& initial_solution)
+ -> std::future>;
+};
+
+} // namespace rmcs::navigation
diff --git a/src/cxx/navigation.cc b/src/cxx/util/navigation/navigation.cc
similarity index 99%
rename from src/cxx/navigation.cc
rename to src/cxx/util/navigation/navigation.cc
index 9dbf32a..ea023a1 100644
--- a/src/cxx/navigation.cc
+++ b/src/cxx/util/navigation/navigation.cc
@@ -1,5 +1,5 @@
-#include "navigation.hh"
-#include "util/node_mixin.hh"
+#include "cxx/util/navigation/navigation.hh"
+#include "cxx/util/node_mixin.hh"
#include
#include
diff --git a/src/cxx/navigation.hh b/src/cxx/util/navigation/navigation.hh
similarity index 98%
rename from src/cxx/navigation.hh
rename to src/cxx/util/navigation/navigation.hh
index bf0d1b5..ede93e8 100644
--- a/src/cxx/navigation.hh
+++ b/src/cxx/util/navigation/navigation.hh
@@ -1,5 +1,5 @@
#pragma once
-#include "util/pimpl.hh"
+#include "cxx/util/pimpl.hh"
#include
#include
diff --git a/src/lua/AGENTS.md b/src/lua/AGENTS.md
new file mode 100644
index 0000000..f969c86
--- /dev/null
+++ b/src/lua/AGENTS.md
@@ -0,0 +1,19 @@
+## Lua 决策开发规则
+
+### 慎重提取辅助函数
+
+创造一个辅助函数是一个非常庄重的时刻,它意味着项目中有一个大量被使用着的功能,需要抽离出来公有化
+
+每当你想写一个辅助函数时,请仔细斟酌:它的使用范围有多大?是否大到足以变成一个在全项目可见的标准函数?我不能内联逻辑或者使用一个局部的函数来解决吗?
+
+如果大量地定义公共函数,那么全局的命名空间将会一片噪声,存在着大量用不上的函数
+
+### 关于非法条件检查
+
+有些错误,就应该让它爆出来,比如构造时传入的变量,作为 Option 的变量,面对这种情况,完全不需要为它们兜底,不需要指定默认值
+
+如果因为参数配置错误而导致被动使用了默认值,这会增加 debug 的难度
+
+最好的办法是在最初,比如初始化时,一次性把所有能检查的都检查好,有错误就爆出来,在构造之后就可以认为所有的配置参数都是合法的,完全没有必要检查它们
+
+此外,对于函数定义中传入的 Args,一般在注解表明了这些 Params 的类型,是否可选之类的,禁止再加入一层检查,就认为调用时传入的是与注解完美匹配的参数,只有可能超出范围,或者没有 index 等情况,需要额外检查,在这种情况下,应该优先报错,而不是兜底,fallback 会默认值
diff --git a/src/lua/api.lua b/src/lua/api.lua
index ab357ad..4dc7424 100644
--- a/src/lua/api.lua
+++ b/src/lua/api.lua
@@ -13,7 +13,7 @@ local util = require("util.native")
--- @field fuck fun(message: string)
---
--- @field send_target fun(x: number, y: number)
---- @field update_gimbal_direction fun(angle: number)
+--- @field update_gimbal_direction fun(angle: number)
--- @field update_gimbal_dominator fun(name: string)
--- @field update_chassis_mode fun(mode: string)
--- @field update_chassis_vel fun(x: number, y: number)
@@ -38,7 +38,7 @@ local api = setmetatable({}, {
function api.restart_navigation(config)
config = config or {}
- local filename, msg = util.find_env_setup_bash()
+ local filename, msg = util.search_setup_resource()
if not filename then
error(msg)
end
@@ -58,27 +58,28 @@ function api.restart_navigation(config)
-- FIXME: 存在调试用的进程(foxglove),记得去掉
local command = [[
- source %q
+source %q
- screen -S rmcs-navigation -X quit
+screen -S rmcs-navigation -X quit
- screen -dmS rmcs-navigation
- screen -S rmcs-navigation -X screen bash -lc "ros2 launch foxglove_bridge foxglove_bridge_launch.xml"
+screen -dmS rmcs-navigation
+screen -S rmcs-navigation -X screen bash -lc "ros2 launch foxglove_bridge foxglove_bridge_launch.xml"
- configs=%q
- screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation motion.launch.yaml $configs"
- screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation sensor.launch.yaml $configs"
- ]]
+configs=%q
+screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation sensor.launch.yaml $configs"
+sleep 1
+screen -S rmcs-navigation -X screen bash -lc "ros2 launch rmcs-navigation motion.launch.yaml $configs"
+]]
local packed_command = string.format(command, filename, configs)
- return util.run_command(string.format("(%s) >/dev/null 2>&1 &", packed_command))
+ return util.run(string.format("(%s) >/dev/null 2>&1 &", packed_command))
end
function api.stop_navigation()
local command = [[
screen -S rmcs-navigation -X quit
]]
- return util.run_command(string.format("(%s) >/dev/null 2>&1 &", command))
+ return util.run(string.format("(%s) >/dev/null 2>&1 &", command))
end
return api
diff --git a/src/lua/blackboard.lua b/src/lua/blackboard.lua
index dea3bcb..b6624ea 100644
--- a/src/lua/blackboard.lua
+++ b/src/lua/blackboard.lua
@@ -6,18 +6,52 @@ local function PointPair(points)
end
local function create_default_blackboard()
+ local last_our_dart_nmber_of_hits = nil
local result = {
-- Dynamic Information
user = {
- health = 0,
- bullet = 0,
- chassis_power_limit = 0,
+ health = 400,
+ bullet = 100,
+ chassis_power_limit = 100,
+ chassis_power = 0,
+ chassis_buffer_energy = 0,
+ chassis_output_status = false,
+ shooter_cooling = 0,
+ shooter_heat_limit = 0,
+ bullet_42mm = 0,
+ fortress_17mm_bullet = 0,
+ initial_speed = 0,
+ shoot_timestamp = 0,
x = 0,
y = 0,
yaw = 0,
+
+ mode = "UNKNOWN",
},
game = {
stage = "UNKNOWN",
+
+ outpost_health = 1500, -- 前哨站血量
+ base_health = 5000, -- 基地血量
+
+ hero_health = 150,
+ infantry_1_health = 150,
+ infantry_2_health = 150,
+ engineer_health = 250,
+
+ hero_position = { x = 0.0, y = 0.0 },
+ infantry_1_position = { x = 0.0, y = 0.0 },
+ infantry_2_position = { x = 0.0, y = 0.0 },
+ engineer_position = { x = 0.0, y = 0.0 },
+
+ remaining_time = 0, -- 比赛剩余时间
+ gold_coin = 0, -- 队伍剩余金币数
+ exchangeable_ammunition_quantity = 0, -- 队伍 17mm 允许发弹量的剩余可兑换数
+
+ our_dart_nmber_of_hits = false, -- 己方飞镖击中次数
+ fortress_occupied = false, -- 己方堡垒是否被占领
+ big_energy_mechanism_activated = false, -- 大能量机关是否被激活
+ small_energy_mechanism_activated = false, -- 小能量机关是否被激活
},
play = {
rswitch = "UNKNOWN",
@@ -25,39 +59,101 @@ local function create_default_blackboard()
},
meta = {
timestamp = 0, -- 秒
+ fsm_state = "unknown",
+ fsm_return_stage = "before_fluctuant",
+ },
+ referee = {
+ sync_timestamp = 0,
+ robot_id = 0,
+ robots_hp = {
+ ally_1 = 0,
+ ally_2 = 0,
+ ally_3 = 0,
+ ally_4 = 0,
+ reserved = 0,
+ ally_7 = 0,
+ outpost = 0,
+ base = 0,
+ },
+
+ can_confirm_free_revive = false,
+ can_exchange_instant_revive = false,
+ instant_revive_cost = 0,
+ exchanged_bullet = 0,
+ remote_bullet_exchange_count = 0,
+ sentry_mode = 0,
+ energy_mechanism_activatable = false,
+
+ red_score = 0,
+ blue_score = 0,
},
-- Static Information
rule = {
decision = "auxiliary",
- -- 状态类规则
+ -- 自身状态类规则
+
+ health_limit = 210,
+ health_ready = 400,
+ bullet_limit = 40,
+ bullet_ready = 160,
+ mode = "movement",
- health_limit = 0,
- health_ready = 0,
- bullet_limit = 0,
- bullet_ready = 0,
+ -- 其他状态类规则
+
+ -- 比赛相关
+ time_of_the_competition_red_line = 90, --比赛剩余时间红线
+
+ -- 队伍资源相关
+ exchangeable_ammunition_quantity_red_line = 1000, -- 队伍 17mm 允许发弹量的剩余可兑换数红线
+ gold_coin_red_line = 400, -- 队伍剩余金币数红线
+
+ -- 前哨站相关
+ outpost_health_red_line = 1500,
+
+ -- 基地相关
+ base_health_red_line = 2000,
+
+ -- 友方机器人相关
+ hero_health_ready_red_line = 50,
+ infantry_1_health_ready_red_line = 50,
+ infantry_2_health_ready_red_line = 50,
+ engineer_health_ready_red_line = 50,
-- 坐标类规则
-- 定义顺序:ours = 0,them = 1
-- 普通地形坐标
- fortress = PointPair { { 0, 0 }, { 0, 0 } }, -- 堡垒
- resupply_zone = PointPair { { 0, 0 }, { 0, 0 } }, -- 补给点
- road_zone_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区
+ fortress = PointPair { { 0, 0 }, { 0, 0 } }, -- 堡垒
+ resupply_zone = PointPair { { 0, 0 }, { 0, 0 } }, -- 补给点
+ road_zone_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区
road_zone_final = PointPair { { 0, 0 }, { 0, 0 } },
- launch_ramp_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 飞坡
+ road_zone_way_point_1 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点1
+ road_zone_way_point_2 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点2
+ road_zone_way_point_3 = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路区路径点3
+ launch_ramp_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 飞坡
launch_ramp_final = PointPair { { 0, 0 }, { 0, 0 } },
- outpost_resupply = PointPair { { 0, 0 }, { 0, 0 } }, -- 前哨站补给点
+ outpost_resupply = PointPair { { 0, 0 }, { 0, 0 } }, -- 前哨站补给点
+ attack_outpost_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 攻击前哨站点
assembly_zone = PointPair { { 0, 0 }, { 0, 0 } },
+ central_highland_near_fluctuant_road = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近起伏路一侧
+ central_highland_near_doghole = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近狗洞一侧
+ central_highland_middle = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地一侧中间
+ central_highland_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地增益点
+ central_highland_near_two_steps_and_outpost = PointPair { { 0, 0 }, { 0, 0 } }, -- 中央高地靠近二级台阶(二级台阶增益点和前哨站中间)
+ base_left_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 左侧基地增益点
+ base_right_gain_point = PointPair { { 0, 0 }, { 0, 0 } }, -- 右侧基地增益点
-- 特殊跨越地形坐标
- road_tunnel_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路隧道
+ road_tunnel_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 公路隧道
road_tunnel_final = PointPair { { 0, 0 }, { 0, 0 } },
- one_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶
- one_step_final = PointPair { { 0, 0 }, { 0, 0 } },
- two_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 二级台阶
+ one_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶高点
+ one_step_final = PointPair { { 0, 0 }, { 0, 0 } }, -- 一级台阶低点
+ two_step_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 二级台阶高点
two_step_final = PointPair { { 0, 0 }, { 0, 0 } },
+ fluctuant_road_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 起伏路段
+ fluctuant_road_final = PointPair { { 0, 0 }, { 0, 0 } },
common_elevated_ground_begin = PointPair { { 0, 0 }, { 0, 0 } }, -- 普通高地(飞坡起点那个高地)
common_elevated_ground_final = PointPair { { 0, 0 }, { 0, 0 } },
},
@@ -83,6 +179,43 @@ local function create_default_blackboard()
return result.user.bullet >= result.rule.bullet_ready
end,
+ base_in_danger = function()
+ return result.game.base_health <= result.rule.base_health_red_line
+ end,
+
+ oupost_survival = function()
+ return result.game.outpost_health > 0
+ end,
+
+ dart_hit_first_time = function()
+ local current = result.game.our_dart_nmber_of_hits
+
+ if last_our_dart_nmber_of_hits == nil then
+ last_our_dart_nmber_of_hits = current
+ return false
+ end
+
+ local triggered = last_our_dart_nmber_of_hits == 0 and current == 1
+ last_our_dart_nmber_of_hits = current
+ return triggered
+ end,
+
+ fortress_occupied = function()
+ return result.game.fortress_occupied
+ end,
+
+ big_energy_mechanism_activated = function()
+ return result.game.big_energy_mechanism_activated
+ end,
+
+ small_energy_mechanism_activated = function()
+ return result.game.small_energy_mechanism_activated
+ end,
+
+ game_close_to_end = function()
+ return result.game.remaining_time <= result.rule.time_of_the_competition_red_line
+ end,
+
--- @param target {x: number, y: number}
--- @param tolerance? number|{x: number, y: number}
near = function(target, tolerance)
diff --git a/src/lua/blackboard_sync.lua b/src/lua/blackboard_sync.lua
new file mode 100644
index 0000000..3d0793b
--- /dev/null
+++ b/src/lua/blackboard_sync.lua
@@ -0,0 +1,86 @@
+local blackboard = require("blackboard").singleton()
+
+local sections = {
+ "user",
+ "game",
+ "play",
+ "meta",
+ "rule",
+ "result",
+}
+
+local function is_serializable(value)
+ local value_type = type(value)
+ return value_type == "nil"
+ or value_type == "boolean"
+ or value_type == "number"
+ or value_type == "string"
+ or value_type == "table"
+end
+
+local function deep_copy(value)
+ if type(value) ~= "table" then
+ return value
+ end
+
+ local copy = {}
+ for key, entry in pairs(value) do
+ local key_type = type(key)
+ if (key_type == "string" or key_type == "number") and is_serializable(entry) then
+ copy[key] = deep_copy(entry)
+ end
+ end
+
+ return copy
+end
+
+local function replace_table(target, source)
+ for key in pairs(target) do
+ if source[key] == nil then
+ target[key] = nil
+ end
+ end
+
+ for key, value in pairs(source) do
+ if type(value) == "table" then
+ if type(target[key]) ~= "table" then
+ target[key] = {}
+ end
+ replace_table(target[key], value)
+ else
+ target[key] = value
+ end
+ end
+end
+
+local M = {}
+
+function M.snapshot()
+ local snapshot = {}
+ for _, section in ipairs(sections) do
+ snapshot[section] = deep_copy(blackboard[section])
+ end
+ return snapshot
+end
+
+function M.apply(snapshot)
+ if type(snapshot) ~= "table" then
+ return
+ end
+
+ for _, section in ipairs(sections) do
+ local source = snapshot[section]
+ if source ~= nil then
+ if type(source) == "table" then
+ if type(blackboard[section]) ~= "table" then
+ blackboard[section] = {}
+ end
+ replace_table(blackboard[section], source)
+ else
+ blackboard[section] = source
+ end
+ end
+ end
+end
+
+return M
diff --git a/src/lua/endpoint/competition-test.lua b/src/lua/endpoint/competition-test.lua
new file mode 100644
index 0000000..cd515c0
--- /dev/null
+++ b/src/lua/endpoint/competition-test.lua
@@ -0,0 +1,565 @@
+---
+--- Local Context
+---
+
+local action = require("action")
+local ascii = require("util.ascii_art")
+local clock = require("util.clock")
+local fsm = require("util.fsm")
+local Map = require("rmuc_map")
+local option = require("option")
+
+local EscapeToHomeIntent = require("intent.competion.escape-to-home")
+local ForwardPressIntent = require("intent.competion.forward-press")
+local GuardHomeIntent = require("intent.competion.guard-home")
+local KeepCruiseIntent = require("intent.competion.keep-cruise")
+local Region = require("region")
+local StartCruiseIntent = require("intent.competion.start-cruise")
+
+local Scheduler = require("util.scheduler")
+local scheduler = Scheduler.new()
+local request = Scheduler.request
+
+local edges = require("util.edge").new()
+
+---
+--- Export Context
+---
+
+blackboard = require("blackboard").singleton()
+
+local runtime = {
+ ours_zone = nil,
+ switch_interval = nil,
+ region = nil,
+ region_name = "unknown",
+ region_phase = Region.Phase.unknown,
+ current_state = "idle",
+ current_phase = "none",
+ current_intent_kind = nil,
+ current_intent = nil,
+ navigation_ready = false,
+ escape_route = nil,
+ forward_press_mode = nil,
+}
+
+local forward_press_duration = 30.0
+
+local requests = {
+ start = false,
+}
+
+local job = {
+ handle = nil,
+ name = nil,
+ done = false,
+ success = false,
+}
+
+local function read_option(name, fallback)
+ local value = rawget(option, name)
+ if value == nil then
+ return fallback
+ end
+ return value
+end
+
+local function configure_test_rule()
+ local rule = blackboard.rule
+
+ rule.health_limit = read_option("health_limit", 210)
+ rule.health_ready = read_option("health_ready", 400)
+ rule.bullet_limit = read_option("bullet_limit", 40)
+ rule.bullet_ready = read_option("bullet_ready", 300)
+ rule.time_of_the_competition_red_line = read_option("time_of_the_competition_red_line", 90)
+ rule.exchangeable_ammunition_quantity_red_line =
+ read_option("exchangeable_ammunition_quantity_red_line", 1000)
+ rule.gold_coin_red_line = read_option("gold_coin_red_line", 400)
+ rule.outpost_health_red_line = read_option("outpost_health_red_line", 1500)
+ rule.base_health_red_line = read_option("base_health_red_line", 2000)
+ rule.hero_health_ready_red_line = read_option("hero_health_ready_red_line", 50)
+ rule.infantry_1_health_ready_red_line =
+ read_option("infantry_1_health_ready_red_line", 50)
+ rule.infantry_2_health_ready_red_line =
+ read_option("infantry_2_health_ready_red_line", 50)
+ rule.engineer_health_ready_red_line =
+ read_option("engineer_health_ready_red_line", 50)
+
+ rule.resupply_zone.ours = { x = 3.0, y = 2.0 }
+ rule.road_zone_begin.ours = { x = 8.2, y = 3.7 }
+ rule.road_zone_way_point_1.ours = { x = 5.3, y = 3.4 }
+ rule.fluctuant_road_begin.ours = { x = 5.6, y = 1.2 }
+ rule.fluctuant_road_final.ours = { x = 8.5, y = 1.0 }
+ rule.one_step_begin.ours = { x = 8.7, y = 3.1 }
+ rule.one_step_final.ours = { x = 8.7, y = 2.1 }
+ rule.central_highland_near_fluctuant_road.ours = { x = 12.8, y = 3.0 }
+ rule.central_highland_middle = { x = 12.0, y = 8.0 }
+ rule.central_highland_near_doghole.ours = { x = 15.0, y = 12.5 }
+ rule.base_left_gain_point.ours = { x = 4.5, y = 8.7 }
+ rule.base_right_gain_point.ours = { x = 4.5, y = 7.3 }
+ rule.attack_outpost_point.ours = { x = 11.5, y = 4.1 }
+ rule.fortress.ours = { x = 7.2 , y = 8.0}
+ rule.central_highland_near_fluctuant_road.them = { x = 16.5, y = 12.8 }
+ rule.central_highland_near_doghole.them = { x = 15.0, y = 3.5 }
+ rule.fluctuant_road_final.them = { x = 20.0, y = 14.2 }
+ --这是什么
+ rule.central_highland_gain_point.ours={x = 12.0 , y = 10.8 }
+ rule.central_highland_gain_point.them={x = 17.2 , y = 8.0 }
+ rule.central_highland_near_two_steps_and_outpost.ours ={x = 11.5 , y = 5.5 }
+ rule.central_highland_near_two_steps_and_outpost.them ={x = 18.0 , y = 10.0 }
+end
+
+local function reset_job_status()
+ job.done = false
+ job.success = false
+end
+
+local function cancel_job()
+ if job.handle ~= nil then
+ job.handle.cancel()
+ job.handle = nil
+ end
+ job.name = nil
+ reset_job_status()
+end
+
+local function run_job(name, fn)
+ cancel_job()
+ job.name = name
+ reset_job_status()
+
+ job.handle = scheduler:append_task(function()
+ local ok, result = xpcall(fn, debug.traceback)
+ job.handle = nil
+ job.name = nil
+ job.done = true
+
+ if not ok then
+ job.success = false
+ action:fuck(string.format("fsm job '%s' failed:\n%s", name, result))
+ return
+ end
+
+ job.success = (result ~= false)
+ if not job.success then
+ action:warn(string.format("fsm job '%s' finished with false", name))
+ end
+ end)
+end
+
+local function clear_current_intent()
+ cancel_job()
+ runtime.current_intent_kind = nil
+ runtime.current_intent = nil
+ runtime.current_phase = "none"
+end
+
+local function take_request(name)
+ local value = requests[name]
+ requests[name] = false
+ return value
+end
+
+local function set_state(name)
+ if runtime.current_state == name then
+ return
+ end
+ runtime.current_state = name
+ blackboard.meta.fsm_state = name
+ action:info("fsm state -> " .. name)
+end
+
+local function set_phase(name)
+ if runtime.current_phase == name then
+ return
+ end
+ runtime.current_phase = name
+ action:info("fsm phase -> " .. name)
+end
+
+local function sync_region()
+ local region, region_name = Region.current()
+ runtime.region = region
+ runtime.region_name = region_name
+ runtime.region_phase = Region.phase(region)
+ blackboard.meta.region = region_name
+ blackboard.meta.fsm_return_stage = Region.return_stage(region)
+end
+
+local function configure_region_map(name)
+ assert(type(name) == "string", "global_map should be a string")
+ local ok, loaded_or_error = pcall(Map.singleton, name)
+ if not ok then
+ action:fuck("load region map failed: " .. tostring(loaded_or_error))
+ return false, loaded_or_error
+ end
+ action:info("region map -> " .. Map.current_name())
+ return true, loaded_or_error
+end
+
+local function start_navigation()
+ local global_map = read_option("global_map", "rmuc")
+ local ok, load_error = configure_region_map(global_map)
+ if not ok then
+ return false, load_error
+ end
+
+ local ok, message = action:restart_navigation({
+ global_map = global_map,
+ launch_livox = read_option("launch_livox", true),
+ launch_odin1 = read_option("launch_odin1", false),
+ use_sim_time = read_option("use_sim_time", false),
+ })
+ if not ok then
+ action:fuck("restart_navigation 触发失败: " .. tostring(message))
+ end
+
+ return ok, message
+end
+
+local function setup_edges()
+ edges:on(blackboard.getter.rswitch, "UP", function()
+ requests.start = true
+ end)
+end
+
+local function should_enter_guard_home()
+ local condition = blackboard.condition
+ return condition.game_close_to_end() or condition.base_in_danger()
+end
+
+local function guard_home_target()
+ if blackboard.condition.fortress_occupied() then
+ return "cruise_in_front_of_base"
+ end
+ return "occupy_fortress"
+end
+
+local last_double_damage_activated = false
+local last_big_energy_mechanism_activated = false
+local last_small_energy_mechanism_activated = false
+
+local function select_forward_press_mode()
+ -- local condition = blackboard.condition
+ -- local dart_hit_first_time = condition.dart_hit_first_time()
+ -- local double_damage_activated = condition.double_damage_activated()
+ -- local big_energy_mechanism_activated = condition.big_energy_mechanism_activated()
+ -- local small_energy_mechanism_activated = condition.small_energy_mechanism_activated()
+ -- local double_damage_rising = double_damage_activated and not last_double_damage_activated
+ -- local big_energy_rising = big_energy_mechanism_activated and not last_big_energy_mechanism_activated
+ -- local small_energy_rising =
+ -- small_energy_mechanism_activated and not last_small_energy_mechanism_activated
+
+ -- last_double_damage_activated = double_damage_activated
+ -- last_big_energy_mechanism_activated = big_energy_mechanism_activated
+ -- last_small_energy_mechanism_activated = small_energy_mechanism_activated
+
+ if true then
+ return "two_step"
+ end
+
+ if dart_hit_first_time or double_damage_rising or big_energy_rising then
+ return "one_step"
+ end
+
+ return nil
+end
+
+local function create_intent(kind)
+ if kind == "start_cruise" then
+ return StartCruiseIntent.new({
+ ours_zone = runtime.ours_zone,
+ })
+ end
+
+ if kind == "keep_cruise" then
+ return KeepCruiseIntent.new({
+ ours_zone = runtime.ours_zone,
+ switch_interval = runtime.switch_interval,
+ })
+ end
+
+ if kind == "guard_home" then
+ return GuardHomeIntent.new({
+ ours_zone = runtime.ours_zone,
+ })
+ end
+
+ if kind == "forward_press" then
+ assert(type(runtime.forward_press_mode) == "string", "forward_press_mode should be set")
+ return ForwardPressIntent.new({
+ mode = runtime.forward_press_mode,
+ switch_interval = runtime.switch_interval,
+ duration = forward_press_duration,
+ })
+ end
+
+ if kind == "escape" then
+ assert(type(runtime.escape_route) == "string", "escape_route should be set")
+ return EscapeToHomeIntent.new({
+ route = runtime.escape_route,
+ })
+ end
+
+ error("unknown intent kind: " .. tostring(kind))
+end
+
+local function replace_intent(kind, force)
+ assert(type(kind) == "string", "intent kind should be a string")
+ if not force and runtime.current_intent_kind == kind and runtime.current_intent ~= nil then
+ return
+ end
+
+ clear_current_intent()
+ runtime.current_intent_kind = kind
+ runtime.current_intent = create_intent(kind)
+ action:info("intent -> " .. kind)
+end
+
+local intent_ctx = {
+ run_job = run_job,
+ cancel_job = cancel_job,
+ job_state = function()
+ return job
+ end,
+ region = function()
+ return runtime.region
+ end,
+ region_phase = function()
+ return runtime.region_phase
+ end,
+ guard_home_target = guard_home_target,
+}
+
+local function sync_intent_phase()
+ if runtime.current_intent == nil or type(runtime.current_intent.phase_name) ~= "function" then
+ set_phase("none")
+ return
+ end
+ set_phase(runtime.current_intent:phase_name())
+end
+
+local function spin_current_intent()
+ if runtime.current_intent == nil then
+ set_phase("none")
+ return nil
+ end
+
+ local status = runtime.current_intent:spin(intent_ctx)
+ sync_intent_phase()
+ return status
+end
+
+local function choose_active_intent_kind()
+ if should_enter_guard_home() then
+ return "guard_home"
+ end
+
+ if runtime.current_intent_kind == "forward_press" and runtime.current_intent ~= nil then
+ return "forward_press"
+ end
+
+ if Region.is_before_fluctuant(runtime.region) or Region.is_on_fluctuant(runtime.region) then
+ return "start_cruise"
+ end
+
+ local mode = select_forward_press_mode()
+ if mode ~= nil then
+ runtime.forward_press_mode = mode
+ return "forward_press"
+ end
+
+ return "keep_cruise"
+end
+
+local function create_endpoint_fsm()
+ local State = {
+ idle = "idle",
+ active = "active",
+ escape = "escape",
+ recover = "recover",
+ }
+
+ local condition = blackboard.condition
+ local endpoint_fsm = fsm:new(State.idle)
+
+ endpoint_fsm:use({
+ state = State.idle,
+ enter = function()
+ clear_current_intent()
+ runtime.escape_route = nil
+ runtime.forward_press_mode = nil
+ runtime.navigation_ready = false
+ set_state(State.idle)
+ set_phase("none")
+ end,
+ event = function(handle)
+ sync_region()
+
+ if take_request("start") then
+ local ok = start_navigation()
+ runtime.navigation_ready = ok
+ end
+
+ -- if runtime.navigation_ready and blackboard.game.stage == "STARTED" then
+ if blackboard.game.stage == "STARTED" then
+ handle:set_next(State.active)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.active,
+ enter = function()
+ set_state(State.active)
+ end,
+ event = function(handle)
+ sync_region()
+
+ if condition.low_health() or condition.low_bullet() then
+ runtime.escape_route = Region.escape_route(runtime.region)
+ clear_current_intent()
+ handle:set_next(State.escape)
+ return
+ end
+
+ local desired_kind = choose_active_intent_kind()
+ if runtime.current_intent_kind ~= desired_kind or runtime.current_intent == nil then
+ replace_intent(desired_kind, true)
+ end
+
+ local status = spin_current_intent()
+ if status == "failed" then
+ action:warn(string.format(
+ "fsm(active:%s): 当前 intent 失败,重建 %s",
+ runtime.current_phase,
+ desired_kind
+ ))
+ replace_intent(desired_kind, true)
+ return
+ end
+
+ if status == "success" then
+ if runtime.current_intent_kind == "forward_press" then
+ runtime.forward_press_mode = nil
+ end
+ clear_current_intent()
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.escape,
+ enter = function()
+ set_state(State.escape)
+ runtime.escape_route = runtime.escape_route or Region.escape_route(runtime.region)
+ replace_intent("escape", true)
+ end,
+ event = function(handle)
+ sync_region()
+
+ local status = spin_current_intent()
+ if status == "failed" then
+ action:warn("fsm(escape): 回家失败,重试 escape intent")
+ replace_intent("escape", true)
+ return
+ end
+
+ if status == "success" then
+ clear_current_intent()
+ handle:set_next(State.recover)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.recover,
+ enter = function()
+ clear_current_intent()
+ runtime.escape_route = nil
+ runtime.forward_press_mode = nil
+ set_state(State.recover)
+ set_phase("none")
+ end,
+ event = function(handle)
+ sync_region()
+
+ if condition.low_health() or condition.low_bullet() then
+ return
+ end
+
+ if condition.health_ready() and condition.bullet_ready() then
+ handle:set_next(State.active)
+ end
+ end,
+ })
+
+ assert(endpoint_fsm:init_ready(State), "endpoint fsm init_ready failed")
+ return endpoint_fsm
+end
+
+on_init = function()
+ clock:reset(blackboard.meta.timestamp)
+
+ option:set_handler(function(error)
+ action:warn("while fetch option: " .. error)
+ end)
+
+ runtime.ours_zone = read_option("fsm_ours_zone", true)
+ runtime.switch_interval = read_option("fsm_switch_interval", 5.0)
+
+ configure_test_rule()
+ do
+ local ok, err = configure_region_map(read_option("global_map", "rmuc"))
+ assert(ok, "failed to configure region map: " .. tostring(err))
+ end
+ setup_edges()
+
+ if read_option("enable_goal_topic_forward", false) then
+ action:switch_topic_forward(true)
+ end
+ action:bind(scheduler)
+
+ local endpoint_fsm = create_endpoint_fsm()
+ scheduler:append_task(function()
+ while true do
+ endpoint_fsm:spin_once()
+ request:yield()
+ end
+ end)
+
+ scheduler:append_task(function()
+ while true do
+ request:sleep(1.0)
+ action:info(string.format(
+ "fsm=%s intent=%s phase=%s region=%s hp=%s bullet=%s rs=%s ls=%s",
+ runtime.current_state,
+ tostring(runtime.current_intent_kind),
+ runtime.current_phase,
+ runtime.region_name,
+ tostring(blackboard.user.health),
+ tostring(blackboard.user.bullet),
+ blackboard.play.rswitch,
+ blackboard.play.lswitch
+ ))
+ end
+ end)
+
+ action:info(ascii.banner)
+ action:warn("new FSM endpoint loaded")
+end
+
+on_tick = function()
+ clock:update(blackboard.meta.timestamp)
+ edges:spin()
+ scheduler:spin_once()
+end
+
+on_exit = function()
+ clear_current_intent()
+ action:stop_navigation()
+end
+
+on_control = function(vx, vy, _)
+ action:update_chassis_vel(vx, vy)
+end
diff --git a/src/lua/endpoint/main.lua b/src/lua/endpoint/main.lua
index 407f343..206d0d7 100644
--- a/src/lua/endpoint/main.lua
+++ b/src/lua/endpoint/main.lua
@@ -23,6 +23,9 @@ blackboard = require("blackboard").singleton()
on_init = function()
clock:reset(blackboard.meta.timestamp)
+ action:bind(scheduler)
+ action:info("use decision: '" .. option.decision .. "'")
+
option:set_handler(function(error)
action:fuck("while fetch option: " .. error)
end)
@@ -31,9 +34,6 @@ on_init = function()
action:switch_topic_forward(true)
end
- action:bind(scheduler)
- action:info("use decision: '" .. option.decision .. "'")
-
scheduler:append_task(function()
local Intent = {
nothing = "nothing",
diff --git a/src/lua/endpoint/mock.lua b/src/lua/endpoint/mock.lua
index 6b492b8..2920b97 100644
--- a/src/lua/endpoint/mock.lua
+++ b/src/lua/endpoint/mock.lua
@@ -25,7 +25,7 @@ on_init = function()
clock:reset(blackboard.meta.timestamp)
action:switch_topic_forward(true)
- native.run_command("ros2 launch rmcs-navigation static.launch.yaml &")
+ native.run("ros2 launch rmcs-navigation static.launch.yaml &")
action:info("static.launch.yaml launched")
scheduler:append_task(function()
diff --git a/src/lua/endpoint/test.lua b/src/lua/endpoint/test.lua
index f1019ee..459cb62 100644
--- a/src/lua/endpoint/test.lua
+++ b/src/lua/endpoint/test.lua
@@ -28,6 +28,7 @@ end
blackboard = require("blackboard").singleton()
on_init = function()
+ action:bind(scheduler)
action:info(ascii.banner)
action:warn("⚠️ TEST 模式,别上场哦")
@@ -35,7 +36,7 @@ on_init = function()
action:switch_topic_forward(true)
restart_navigation()
- edges:on(blackboard.getter.rswitch, "UP", restart_navigation)
+ -- edges:on(blackboard.getter.rswitch, "UP", restart_navigation)
scheduler:append_task(function()
while true do
diff --git a/src/lua/endpoint/train-decision.lua b/src/lua/endpoint/train-decision.lua
new file mode 100644
index 0000000..f71a73a
--- /dev/null
+++ b/src/lua/endpoint/train-decision.lua
@@ -0,0 +1,491 @@
+---
+--- Local Context
+---
+
+local action = require("action")
+local ascii = require("util.ascii_art")
+local clock = require("util.clock")
+local fsm = require("util.fsm")
+local option = require("option")
+
+local start_cruise = require("intent.train.start-cruise-train")
+local keep_cruise = require("intent.train.keep-cruise")
+local escape_to_home = require("intent.train.escape-to-home")
+
+local Scheduler = require("util.scheduler")
+local scheduler = Scheduler.new()
+local request = Scheduler.request
+
+---
+--- Export Context
+---
+
+blackboard = require("blackboard").singleton()
+
+local runtime = {
+ ours_zone = true,
+ switch_interval = 2.0,
+ current_state = "idle",
+ navigation_ready = false,
+}
+
+local requests = {
+ start = false,
+}
+
+local job = {
+ handle = nil,
+ name = nil,
+ done = false,
+ success = false,
+}
+
+local function read_option(name, fallback)
+ local value = rawget(option, name)
+ if value == nil then
+ return fallback
+ end
+ return value
+end
+
+local function ensure_point_pair(rule, name)
+ if type(rule[name]) ~= "table" then
+ rule[name] = {
+ ours = { x = 0.0, y = 0.0 },
+ them = { x = 0.0, y = 0.0 },
+ }
+ return
+ end
+
+ if type(rule[name].ours) ~= "table" then
+ rule[name].ours = { x = 0.0, y = 0.0 }
+ end
+ if type(rule[name].them) ~= "table" then
+ rule[name].them = { x = 0.0, y = 0.0 }
+ end
+
+ rule[name].ours.x = tonumber(rule[name].ours.x) or 0.0
+ rule[name].ours.y = tonumber(rule[name].ours.y) or 0.0
+ rule[name].them.x = tonumber(rule[name].them.x) or 0.0
+ rule[name].them.y = tonumber(rule[name].them.y) or 0.0
+end
+
+local function ensure_schema()
+ if type(blackboard.user) ~= "table" then
+ blackboard.user = {}
+ end
+ if type(blackboard.game) ~= "table" then
+ blackboard.game = {}
+ end
+ if type(blackboard.play) ~= "table" then
+ blackboard.play = {}
+ end
+ if type(blackboard.meta) ~= "table" then
+ blackboard.meta = {}
+ end
+ if type(blackboard.result) ~= "table" then
+ blackboard.result = {}
+ end
+ if type(blackboard.rule) ~= "table" then
+ blackboard.rule = {}
+ end
+
+ blackboard.user.health = tonumber(blackboard.user.health) or 0
+ blackboard.user.bullet = tonumber(blackboard.user.bullet) or 0
+ blackboard.user.chassis_power_limit = tonumber(blackboard.user.chassis_power_limit) or 0
+ blackboard.user.x = tonumber(blackboard.user.x) or 0
+ blackboard.user.y = tonumber(blackboard.user.y) or 0
+ blackboard.user.yaw = tonumber(blackboard.user.yaw) or 0
+
+ blackboard.game.stage = tostring(blackboard.game.stage or "UNKNOWN")
+ blackboard.play.rswitch = tostring(blackboard.play.rswitch or "UNKNOWN")
+ blackboard.play.lswitch = tostring(blackboard.play.lswitch or "UNKNOWN")
+ blackboard.meta.timestamp = tonumber(blackboard.meta.timestamp) or 0
+
+ if type(blackboard.meta.navigate_point_queue) ~= "table" then
+ blackboard.meta.navigate_point_queue = {}
+ end
+
+ local rule = blackboard.rule
+ rule.health_limit = tonumber(rule.health_limit) or 0
+ rule.health_ready = tonumber(rule.health_ready) or 0
+ rule.bullet_limit = tonumber(rule.bullet_limit) or 0
+ rule.bullet_ready = tonumber(rule.bullet_ready) or 0
+
+ ensure_point_pair(rule, "resupply_zone")
+ ensure_point_pair(rule, "road_zone_begin")
+ ensure_point_pair(rule, "road_zone_final")
+ ensure_point_pair(rule, "one_step_begin")
+ ensure_point_pair(rule, "one_step_final")
+ ensure_point_pair(rule, "fluctuant_road_begin")
+ ensure_point_pair(rule, "fluctuant_road_final")
+ ensure_point_pair(rule, "central_highland_near_crossing_road")
+ ensure_point_pair(rule, "central_highland_near_doghole")
+
+ if type(blackboard.enqueue_navigate_point) ~= "function" then
+ blackboard.enqueue_navigate_point = function(point, source)
+ if type(point) ~= "table" then
+ return
+ end
+ if type(point.x) ~= "number" or type(point.y) ~= "number" then
+ return
+ end
+
+ local queue = blackboard.meta.navigate_point_queue
+ if type(queue) ~= "table" then
+ queue = {}
+ blackboard.meta.navigate_point_queue = queue
+ end
+
+ queue[#queue + 1] = {
+ x = point.x,
+ y = point.y,
+ source = source or "unknown",
+ timestamp = blackboard.meta.timestamp,
+ }
+
+ local max_history = 64
+ while #queue > max_history do
+ table.remove(queue, 1)
+ end
+ end
+ end
+end
+
+local function set_reason(reason)
+ if type(blackboard.result) ~= "table" then
+ blackboard.result = {}
+ end
+ blackboard.result.last_reason = tostring(reason or "")
+end
+
+local function publish_decision_state(progress)
+ if type(blackboard.result) ~= "table" then
+ blackboard.result = {}
+ end
+ if type(blackboard.meta) ~= "table" then
+ blackboard.meta = {}
+ end
+
+ blackboard.meta.fsm_state = runtime.current_state
+ blackboard.result.intent = runtime.current_state
+ blackboard.result.task = job.name or "idle"
+ blackboard.result.job_done = job.done
+ blackboard.result.job_success = job.success
+ blackboard.result.progress = progress or blackboard.result.progress or "running"
+end
+
+local function configure_test_rule()
+ local rule = blackboard.rule
+
+ rule.health_limit = read_option("fsm_health_limit", 200)
+ rule.health_ready = read_option("fsm_health_ready", 400)
+ rule.bullet_limit = read_option("fsm_bullet_limit", 30)
+ rule.bullet_ready = read_option("fsm_bullet_ready", 300)
+
+ -- Ours side sample points
+ rule.resupply_zone.ours = { x = -1.2, y = 6.0 }
+ rule.road_zone_begin.ours = { x = 1.5, y = 4.4 }
+ rule.road_zone_final.ours = { x = 6.5, y = 6.5 }
+ rule.fluctuant_road_begin.ours = { x = 2.5, y = 6.5 }
+ rule.fluctuant_road_final.ours = { x = 5.5, y = 6.5 }
+ rule.one_step_begin.ours = { x = 4.4, y = 6 }
+ rule.one_step_final.ours = { x = 4.4, y = 4.5 }
+ rule.central_highland_near_crossing_road.ours = { x = 8.8, y = 4.0 }
+ rule.central_highland_near_doghole.ours = { x = 10.5, y = -4.0 }
+end
+
+local function reset_job_status()
+ job.done = false
+ job.success = false
+end
+
+local function cancel_job()
+ if job.handle ~= nil then
+ job.handle.cancel()
+ job.handle = nil
+ end
+ job.name = nil
+ reset_job_status()
+ publish_decision_state("job_canceled")
+end
+
+local function run_job(name, fn)
+ cancel_job()
+ job.name = name
+ reset_job_status()
+ publish_decision_state("job_running")
+
+ job.handle = scheduler:append_task(function()
+ local ok, result = xpcall(fn, debug.traceback)
+ job.handle = nil
+ job.name = nil
+ job.done = true
+
+ if not ok then
+ job.success = false
+ publish_decision_state("job_failed")
+ action:fuck(string.format("fsm job '%s' failed:\n%s", name, result))
+ return
+ end
+
+ job.success = (result ~= false)
+ if not job.success then
+ publish_decision_state("job_returned_false")
+ action:warn(string.format("fsm job '%s' finished with false", name))
+ return
+ end
+
+ publish_decision_state("job_succeeded")
+ end)
+end
+
+local function take_request(name)
+ local value = requests[name]
+ requests[name] = false
+ return value
+end
+
+local function set_state(name)
+ runtime.current_state = name
+ publish_decision_state("state_enter")
+ action:info("fsm state -> " .. name)
+end
+
+local function start_runtime()
+ runtime.navigation_ready = true
+ set_reason("sim_start")
+ return true, "ok"
+end
+
+local function clear_navigate_history()
+ local queue = blackboard.meta.navigate_point_queue
+ if type(queue) ~= "table" then
+ blackboard.meta.navigate_point_queue = {}
+ return
+ end
+
+ for i = #queue, 1, -1 do
+ queue[i] = nil
+ end
+end
+
+local function create_intent_fsm()
+ local State = {
+ idle = "idle",
+ start_cruise = "start_cruise",
+ keep_cruise = "keep_cruise",
+ escape = "escape",
+ recover = "recover",
+ }
+
+ local condition = blackboard.condition
+ local intent_fsm = fsm:new(State.idle)
+ local function restart_start_cruise_job()
+ run_job("start_cruise", function()
+ return start_cruise(runtime.ours_zone)
+ end)
+ end
+ local function restart_keep_cruise_job()
+ run_job("keep_cruise", function()
+ return keep_cruise(runtime.ours_zone, runtime.switch_interval)
+ end)
+ end
+ local function restart_escape_job()
+ run_job("escape_to_home", function()
+ return escape_to_home(runtime.ours_zone)
+ end)
+ end
+
+ intent_fsm:use({
+ state = State.idle,
+ enter = function()
+ cancel_job()
+ set_state(State.idle)
+ runtime.navigation_ready = false
+ end,
+ event = function(handle)
+ if take_request("start") then
+ local ok = start_runtime()
+ runtime.navigation_ready = ok
+ end
+
+ if runtime.navigation_ready and blackboard.game.stage == "STARTED" then
+ clear_navigate_history()
+ set_reason("idle_to_start_cruise")
+ handle:set_next(State.start_cruise)
+ end
+ end,
+ })
+
+ intent_fsm:use({
+ state = State.start_cruise,
+ enter = function()
+ set_state(State.start_cruise)
+ restart_start_cruise_job()
+ end,
+ event = function(handle)
+ if condition.low_health() or condition.low_bullet() then
+ cancel_job()
+ set_reason("start_cruise_low_resource")
+ handle:set_next(State.escape)
+ return
+ end
+
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ set_reason("start_cruise_done")
+ handle:set_next(State.keep_cruise)
+ return
+ end
+
+ action:warn("fsm(start_cruise): 导航失败,重试当前状态")
+ set_reason("start_cruise_retry")
+ restart_start_cruise_job()
+ end,
+ })
+
+ intent_fsm:use({
+ state = State.keep_cruise,
+ enter = function()
+ set_state(State.keep_cruise)
+ restart_keep_cruise_job()
+ end,
+ event = function(handle)
+ if condition.low_health() or condition.low_bullet() then
+ cancel_job()
+ set_reason("keep_cruise_low_resource")
+ handle:set_next(State.escape)
+ return
+ end
+
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ return
+ end
+
+ action:warn("fsm(keep_cruise): 导航失败,重试当前状态")
+ set_reason("keep_cruise_retry")
+ restart_keep_cruise_job()
+ end,
+ })
+
+ intent_fsm:use({
+ state = State.escape,
+ enter = function()
+ set_state(State.escape)
+ restart_escape_job()
+ end,
+ event = function(handle)
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ set_reason("escape_done")
+ handle:set_next(State.recover)
+ return
+ end
+
+ action:warn("fsm(escape): 导航失败,重试当前状态")
+ set_reason("escape_retry")
+ restart_escape_job()
+ end,
+ })
+
+ intent_fsm:use({
+ state = State.recover,
+ enter = function()
+ cancel_job()
+ set_state(State.recover)
+ end,
+ event = function(handle)
+ if condition.low_health() or condition.low_bullet() then
+ return
+ end
+
+ if condition.health_ready() and condition.bullet_ready() then
+ set_reason("recover_to_start_cruise")
+ handle:set_next(State.start_cruise)
+ end
+ end,
+ })
+
+ assert(intent_fsm:init_ready(State), "intent fsm init_ready failed")
+ return intent_fsm
+end
+
+on_init = function()
+ ensure_schema()
+ clock:reset(blackboard.meta.timestamp)
+
+ option:set_handler(function(error)
+ action:warn("while fetch option: " .. error)
+ end)
+
+ runtime.ours_zone = read_option("fsm_ours_zone", true)
+ runtime.switch_interval = read_option("fsm_switch_interval", 2.0)
+
+ configure_test_rule()
+ publish_decision_state("initialized")
+
+ if read_option("enable_goal_topic_forward", false) then
+ action:switch_topic_forward(true)
+ end
+ action:bind(scheduler)
+
+ local intent_fsm = create_intent_fsm()
+ scheduler:append_task(function()
+ while true do
+ intent_fsm:spin_once()
+ request:yield()
+ end
+ end)
+
+ scheduler:append_task(function()
+ while true do
+ request:sleep(1.0)
+ publish_decision_state("heartbeat")
+ action:info(string.format(
+ "fsm=%s stage=%s hp=%s bullet=%s",
+ runtime.current_state,
+ blackboard.game.stage,
+ tostring(blackboard.user.health),
+ tostring(blackboard.user.bullet)
+ ))
+ end
+ end)
+
+ action:info(ascii.banner)
+ action:warn("FSM test endpoint loaded (sim mode)")
+end
+
+on_tick = function()
+ clock:update(blackboard.meta.timestamp)
+ scheduler:spin_once()
+end
+
+on_exit = function()
+ cancel_job()
+end
+
+--- Callback for simulated control feedback.
+on_control = function(vx, vy, _)
+ action:update_chassis_vel(vx, vy)
+end
+
+function on_sim_start(_, _)
+ requests.start = true
+ blackboard.game.stage = "STARTED"
+ set_reason("sim_start_command")
+end
+
+function on_sim_set_target(_, _)
+ -- train-decision currently uses rule points; dynamic target injection is ignored.
+end
\ No newline at end of file
diff --git a/src/lua/endpoint/train-test.lua b/src/lua/endpoint/train-test.lua
new file mode 100644
index 0000000..a90ff60
--- /dev/null
+++ b/src/lua/endpoint/train-test.lua
@@ -0,0 +1,534 @@
+---
+--- Local Context
+---
+
+local action = require("action")
+local ascii = require("util.ascii_art")
+local clock = require("util.clock")
+local fsm = require("util.fsm")
+local option = require("option")
+local TrainMap = require("train_map")
+
+local CrossRoadIntent = require("intent.train.cross-road")
+local EscapeToHomeIntent = require("intent.train.escape-to-home")
+local KeepCruiseIntent = require("intent.train.keep-cruise")
+
+local Scheduler = require("util.scheduler")
+local scheduler = Scheduler.new()
+local request = Scheduler.request
+
+local edges = require("util.edge").new()
+local BlackboardLogger = require("util.blackboard_logger")
+
+---
+--- Export Context
+---
+
+blackboard = require("blackboard").singleton()
+
+local runtime = {
+ ours_zone = true,
+ switch_interval = 5.0,
+ region = nil,
+ region_name = "unknown",
+ escape_route = nil,
+ current_state = "idle",
+ current_phase = "none",
+ current_intent_kind = nil,
+ current_intent = nil,
+ navigation_ready = false,
+}
+
+local requests = {
+ start = false,
+}
+
+local job = {
+ handle = nil,
+ name = nil,
+ done = false,
+ success = false,
+}
+
+local function read_option(name, fallback)
+ local value = rawget(option, name)
+ if value == nil then
+ return fallback
+ end
+ return value
+end
+
+local function configure_train_rule()
+ local rule = blackboard.rule
+
+ rule.health_limit = read_option("health_limit", rule.health_limit)
+ rule.health_ready = read_option("health_ready", rule.health_ready)
+ rule.bullet_limit = read_option("bullet_limit", rule.bullet_limit)
+ rule.bullet_ready = read_option("bullet_ready", rule.bullet_ready)
+
+ rule.resupply_zone.ours = { x = -1.2, y = 6.0 }
+ rule.road_zone_begin.ours = { x = 1.5, y = 4.4 }
+ rule.road_zone_final.ours = { x = 6.5, y = 6.5 }
+ rule.road_zone_way_point_1 = { x = 0.5, y = 4.2 }
+ rule.road_zone_way_point_2 = { x = 0.7, y = 6.5 }
+ rule.central_highland_middle = { x = 7.0, y = 0.0 }
+ rule.central_highland_near_fluctuant_road.ours = { x = 8.5, y = 3.0 }
+ rule.central_highland_near_doghole.ours = { x = 8.5, y = -3.0 }
+end
+
+local function reset_job_status()
+ job.done = false
+ job.success = false
+end
+
+local function cancel_job()
+ if job.handle ~= nil then
+ job.handle.cancel()
+ job.handle = nil
+ end
+ job.name = nil
+ reset_job_status()
+end
+
+local function run_job(name, fn)
+ cancel_job()
+ job.name = name
+ reset_job_status()
+
+ job.handle = scheduler:append_task(function()
+ local ok, result = xpcall(fn, debug.traceback)
+ job.handle = nil
+ job.name = nil
+ job.done = true
+
+ if not ok then
+ job.success = false
+ action:fuck(string.format("train fsm job '%s' failed:\n%s", name, result))
+ return
+ end
+
+ job.success = (result ~= false)
+ if not job.success then
+ action:warn(string.format("train fsm job '%s' finished with false", name))
+ end
+ end)
+end
+
+local function clear_current_intent()
+ cancel_job()
+ runtime.current_intent_kind = nil
+ runtime.current_intent = nil
+ runtime.current_phase = "none"
+end
+
+local function take_request(name)
+ local value = requests[name]
+ requests[name] = false
+ return value
+end
+
+local function set_state(name)
+ if runtime.current_state == name then
+ return
+ end
+ runtime.current_state = name
+ blackboard.meta.fsm_state = name
+ action:info("train fsm state -> " .. name)
+end
+
+local function set_phase(name)
+ if runtime.current_phase == name then
+ return
+ end
+ runtime.current_phase = name
+ action:info("train fsm phase -> " .. name)
+end
+
+local function current_train_region()
+ local map = TrainMap.singleton(read_option("global_map", "train_map"))
+ local region = map:locate({
+ x = blackboard.user.x,
+ y = blackboard.user.y,
+ })
+ return region, map.names[region] or "unknown"
+end
+
+local function sync_train_region()
+ local region, region_name = current_train_region()
+ runtime.region = region
+ runtime.region_name = region_name
+ blackboard.meta.region = region_name
+end
+
+local function distance_to(point)
+ local dx = point.x - blackboard.user.x
+ local dy = point.y - blackboard.user.y
+ return math.sqrt(dx * dx + dy * dy)
+end
+
+local function select_rule_point(point)
+ if type(point.x) == "number" and type(point.y) == "number" then
+ return point
+ end
+ return runtime.ours_zone and point.ours or point.them
+end
+
+local function nearest_road_return_route()
+ local rule = blackboard.rule
+ local candidates = {
+ {
+ route = "road_region_final",
+ point = select_rule_point(rule.road_zone_final),
+ },
+ {
+ route = "road_region_2",
+ point = select_rule_point(rule.road_zone_way_point_2),
+ },
+ {
+ route = "road_region_1",
+ point = select_rule_point(rule.road_zone_way_point_1),
+ },
+ {
+ route = "road_region_begin",
+ point = select_rule_point(rule.road_zone_begin),
+ },
+ }
+
+ local selected = candidates[1]
+ local selected_distance = distance_to(selected.point)
+ for index = 2, #candidates do
+ local candidate = candidates[index]
+ local candidate_distance = distance_to(candidate.point)
+ if candidate_distance < selected_distance then
+ selected = candidate
+ selected_distance = candidate_distance
+ end
+ end
+
+ return selected.route
+end
+
+local function select_escape_route()
+ local Region = TrainMap.Region
+
+ if runtime.region == nil then
+ sync_train_region()
+ end
+
+ if runtime.region == Region.OURS_HOME then
+ return "ours_home"
+ end
+
+ if runtime.region == Region.ROAD_REGION_BEGIN then
+ return "road_region_begin"
+ end
+
+ if runtime.region == Region.ROAD_REGION_1 then
+ return "road_region_1"
+ end
+
+ if runtime.region == Region.ROAD_REGION_2 then
+ return "road_region_2"
+ end
+
+ if runtime.region == Region.ROAD_REGION_FINAL then
+ return "road_region_final"
+ end
+
+ if runtime.region == Region.OURS_HIGHLAND then
+ return "highland"
+ end
+
+ return nearest_road_return_route()
+end
+
+local function start_navigation()
+ local global_map = read_option("global_map", "train_map")
+ local ok, load_error = pcall(TrainMap.singleton, global_map)
+ if not ok then
+ action:fuck("train load region map failed: " .. tostring(load_error))
+ return false, load_error
+ end
+
+ local ok, message = action:restart_navigation({
+ global_map = global_map,
+ launch_livox = read_option("launch_livox", true),
+ launch_odin1 = read_option("launch_odin1", false),
+ use_sim_time = read_option("use_sim_time", false),
+ })
+ if not ok then
+ action:fuck("train restart_navigation 触发失败: " .. tostring(message))
+ end
+
+ return ok, message
+end
+
+local function setup_edges()
+ edges:on(blackboard.getter.rswitch, "UP", function()
+ -- 手动测试入口:仅允许右拨杆向上触发启动。
+ requests.start = true
+ end)
+end
+
+local function create_intent(kind)
+ if kind == "cross_road" then
+ return CrossRoadIntent.new({
+ ours_zone = runtime.ours_zone,
+ forward_center = true,
+ })
+ end
+
+ if kind == "keep_cruise" then
+ return KeepCruiseIntent.new({
+ ours_zone = runtime.ours_zone,
+ switch_interval = runtime.switch_interval,
+ })
+ end
+
+ if kind == "escape" then
+ return EscapeToHomeIntent.new({
+ ours_zone = runtime.ours_zone,
+ route = runtime.escape_route or select_escape_route(),
+ })
+ end
+
+ error("unknown train intent kind: " .. tostring(kind))
+end
+
+local function replace_intent(kind, force)
+ assert(type(kind) == "string", "intent kind should be a string")
+ if not force and runtime.current_intent_kind == kind and runtime.current_intent ~= nil then
+ return
+ end
+
+ clear_current_intent()
+ runtime.current_intent_kind = kind
+ runtime.current_intent = create_intent(kind)
+ action:info("train intent -> " .. kind)
+end
+
+local intent_ctx = {
+ run_job = run_job,
+ cancel_job = cancel_job,
+ job_state = function()
+ return job
+ end,
+}
+
+local function sync_intent_phase()
+ if runtime.current_intent == nil or type(runtime.current_intent.phase_name) ~= "function" then
+ set_phase("none")
+ return
+ end
+ set_phase(runtime.current_intent:phase_name())
+end
+
+local function spin_current_intent()
+ if runtime.current_intent == nil then
+ set_phase("none")
+ return nil
+ end
+
+ local status = runtime.current_intent:spin(intent_ctx)
+ sync_intent_phase()
+ return status
+end
+
+local function create_endpoint_fsm()
+ local State = {
+ idle = "idle",
+ cross_road = "cross_road",
+ keep_cruise = "keep_cruise",
+ escape = "escape",
+ recover = "recover",
+ }
+
+ local condition = blackboard.condition
+ local endpoint_fsm = fsm:new(State.idle)
+
+ endpoint_fsm:use({
+ state = State.idle,
+ enter = function()
+ clear_current_intent()
+ runtime.escape_route = nil
+ runtime.navigation_ready = false
+ set_state(State.idle)
+ set_phase("none")
+ end,
+ event = function(handle)
+ sync_train_region()
+
+ if take_request("start") then
+ local ok = start_navigation()
+ runtime.navigation_ready = ok
+ end
+
+ if runtime.navigation_ready then
+ handle:set_next(State.cross_road)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.cross_road,
+ enter = function()
+ set_state(State.cross_road)
+ replace_intent("cross_road", true)
+ end,
+ event = function(handle)
+ sync_train_region()
+
+ if condition.low_health() then
+ runtime.escape_route = select_escape_route()
+ clear_current_intent()
+ handle:set_next(State.escape)
+ return
+ end
+
+ local status = spin_current_intent()
+ if status == "failed" then
+ action:warn("train fsm(cross_road): 通过公路区失败,重试")
+ replace_intent("cross_road", true)
+ return
+ end
+
+ if status == "success" then
+ clear_current_intent()
+ handle:set_next(State.keep_cruise)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.keep_cruise,
+ enter = function()
+ set_state(State.keep_cruise)
+ replace_intent("keep_cruise", true)
+ end,
+ event = function(handle)
+ sync_train_region()
+
+ if condition.low_health() then
+ runtime.escape_route = select_escape_route()
+ clear_current_intent()
+ handle:set_next(State.escape)
+ return
+ end
+
+ local status = spin_current_intent()
+ if status == "failed" then
+ action:warn("train fsm(keep_cruise): 巡航失败,重试")
+ replace_intent("keep_cruise", true)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.escape,
+ enter = function()
+ set_state(State.escape)
+ runtime.escape_route = runtime.escape_route or select_escape_route()
+ replace_intent("escape", true)
+ end,
+ event = function(handle)
+ sync_train_region()
+
+ local status = spin_current_intent()
+ if status == "failed" then
+ action:warn("train fsm(escape): 回补给点失败,重试")
+ replace_intent("escape", true)
+ return
+ end
+
+ if status == "success" then
+ clear_current_intent()
+ handle:set_next(State.recover)
+ end
+ end,
+ })
+
+ endpoint_fsm:use({
+ state = State.recover,
+ enter = function()
+ clear_current_intent()
+ runtime.escape_route = nil
+ set_state(State.recover)
+ set_phase("none")
+ end,
+ event = function(handle)
+ sync_train_region()
+
+ if condition.low_health() then
+ return
+ end
+
+ if condition.health_ready() then
+ handle:set_next(State.cross_road)
+ end
+ end,
+ })
+
+ assert(endpoint_fsm:init_ready(State), "train endpoint fsm init_ready failed")
+ return endpoint_fsm
+end
+
+on_init = function()
+ clock:reset(blackboard.meta.timestamp)
+
+ option:set_handler(function(error)
+ action:warn("while fetch option: " .. error)
+ end)
+
+ runtime.ours_zone = true
+ runtime.switch_interval = read_option("fsm_switch_interval", 5.0)
+
+ configure_train_rule()
+ setup_edges()
+
+ if read_option("enable_goal_topic_forward", false) then
+ action:switch_topic_forward(true)
+ end
+ action:bind(scheduler)
+
+ local endpoint_fsm = create_endpoint_fsm()
+ scheduler:append_task(function()
+ while true do
+ endpoint_fsm:spin_once()
+ request:yield()
+ end
+ end)
+
+ scheduler:append_task(function()
+ while true do
+ request:sleep(1.0)
+ sync_train_region()
+ action:info(string.format(
+ "train position x=%.2f y=%.2f region=%s escape_route=%s",
+ blackboard.user.x,
+ blackboard.user.y,
+ runtime.region_name,
+ tostring(runtime.escape_route or select_escape_route())
+ ))
+ end
+ end)
+
+ -- BlackboardLogger.attach(scheduler, blackboard)
+
+ action:info(ascii.banner)
+ action:warn("train FSM endpoint loaded")
+end
+
+on_tick = function()
+ clock:update(blackboard.meta.timestamp)
+ edges:spin()
+ scheduler:spin_once()
+end
+
+on_exit = function()
+ clear_current_intent()
+ action:stop_navigation()
+end
+
+on_control = function(vx, vy, _)
+ action:update_chassis_vel(vx, vy)
+end
diff --git a/src/lua/intent/competion/cruise-to-kill.lua b/src/lua/intent/competion/cruise-to-kill.lua
new file mode 100644
index 0000000..75f4b5b
--- /dev/null
+++ b/src/lua/intent/competion/cruise-to-kill.lua
@@ -0,0 +1,11 @@
+local intent = {}
+
+function intent.new()
+ local details = {
+ a = 1,
+ b = 2,
+ }
+ return setmetatable(details, intent)
+end
+
+return intent
diff --git a/src/lua/intent/competion/escape-to-home.lua b/src/lua/intent/competion/escape-to-home.lua
new file mode 100644
index 0000000..d79d969
--- /dev/null
+++ b/src/lua/intent/competion/escape-to-home.lua
@@ -0,0 +1,172 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local fsm = require("util.fsm")
+local Region = require("region")
+local go_down_onestep = require("task.one-step.go-down-onestep")
+local cross_fluctuant_road = require("task.cross-fluctuant.cross-fluctuant-road")
+local navigate_to_point = require("task.navigate-to-point")
+
+local EscapeToHomeIntent = {}
+EscapeToHomeIntent.__index = EscapeToHomeIntent
+
+local State = {
+ descend_onestep = "descend_onestep",
+ cross_fluctuant = "cross_fluctuant",
+ to_resupply = "to_resupply",
+ done = "done",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+local function initial_state(route)
+ if route == "onestep" then
+ return State.descend_onestep
+ end
+ if route == "fluctuant_road" then
+ return State.cross_fluctuant
+ end
+ return State.to_resupply
+end
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.route) == "string", "args.route should be a string")
+
+ return setmetatable({
+ route = args.route,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, EscapeToHomeIntent)
+end
+
+function EscapeToHomeIntent:phase_name()
+ return self.phase
+end
+
+function EscapeToHomeIntent:create_machine(ctx)
+ local machine = fsm:new(initial_state(self.route))
+ local resupply_zone = blackboard.rule.resupply_zone.ours
+
+ machine:use({
+ state = State.descend_onestep,
+ enter = function()
+ self.phase = State.descend_onestep
+ action:info("escape-to-home: 开始走一级台阶回家")
+ ctx.run_job("escape_descend_onestep", function()
+ return go_down_onestep(true)
+ end)
+ end,
+ event = function(handle)
+ if not Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.to_resupply)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.to_resupply)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.cross_fluctuant,
+ enter = function()
+ self.phase = State.cross_fluctuant
+ action:info("escape-to-home: 开始走起伏路回家")
+ ctx.run_job("escape_cross_fluctuant", function()
+ return cross_fluctuant_road(true, false)
+ end)
+ end,
+ event = function(handle)
+ if Region.is_before_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.to_resupply)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.to_resupply)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.to_resupply,
+ enter = function()
+ self.phase = State.to_resupply
+ action:update_chassis_mode("SPIN")
+ ctx.run_job("escape_to_resupply", function()
+ return navigate_to_point(resupply_zone, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ end)
+ end,
+ event = function(handle)
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.done)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.done,
+ enter = function()
+ self.phase = State.done
+ self.status = "success"
+ action:info("escape-to-home: 已抵达补给点")
+ end,
+ event = function() end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "escape-to-home intent fsm init_ready failed")
+ return machine
+end
+
+function EscapeToHomeIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/competion/forward-press.lua b/src/lua/intent/competion/forward-press.lua
new file mode 100644
index 0000000..6bdb3d0
--- /dev/null
+++ b/src/lua/intent/competion/forward-press.lua
@@ -0,0 +1,160 @@
+local clock = require("util.clock")
+local fsm = require("util.fsm")
+local forward_press_in_one_step = require("task.forward-press.forward-press-in-one-step")
+local forward_press_in_two_step = require("task.forward-press.forward-press-in-two-step")
+
+local ForwardPressIntent = {}
+ForwardPressIntent.__index = ForwardPressIntent
+
+local State = {
+ one_step = "one_step",
+ two_step = "two_step",
+ hold = "hold",
+ done = "done",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+local function initial_state(mode)
+ if mode == "two_step" then
+ return State.two_step
+ end
+ return State.one_step
+end
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.mode) == "string", "args.mode should be a string")
+ assert(type(args.switch_interval) == "number", "args.switch_interval should be a number")
+ assert(args.switch_interval > 0, "args.switch_interval should be positive")
+
+ return setmetatable({
+ mode = args.mode,
+ switch_interval = args.switch_interval,
+ duration = args.duration or 30.0,
+ phase = "none",
+ status = "running",
+ started_at = nil,
+ machine = nil,
+ }, ForwardPressIntent)
+end
+
+function ForwardPressIntent:phase_name()
+ return self.phase
+end
+
+function ForwardPressIntent:elapsed()
+ return clock:now() - self.started_at
+end
+
+function ForwardPressIntent:create_machine(ctx)
+ local machine = fsm:new(initial_state(self.mode))
+
+ machine:use({
+ state = State.one_step,
+ enter = function()
+ self.phase = State.one_step
+ ctx.run_job("forward_press_in_one_step", function()
+ return forward_press_in_one_step()
+ end)
+ end,
+ event = function(handle)
+ if self:elapsed() >= self.duration then
+ ctx.cancel_job()
+ handle:set_next(State.done)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.hold)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.two_step,
+ enter = function()
+ self.phase = State.two_step
+ ctx.run_job("forward_press_in_two_step", function()
+ return forward_press_in_two_step(self.switch_interval)
+ end)
+ end,
+ event = function(handle)
+ if self:elapsed() >= self.duration then
+ ctx.cancel_job()
+ handle:set_next(State.done)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.done)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.hold,
+ enter = function()
+ self.phase = State.hold
+ end,
+ event = function(handle)
+ if self:elapsed() >= self.duration then
+ handle:set_next(State.done)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.done,
+ enter = function()
+ self.phase = State.done
+ self.status = "success"
+ end,
+ event = function() end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "forward-press intent fsm init_ready failed")
+ return machine
+end
+
+function ForwardPressIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.started_at == nil then
+ self.started_at = clock:now()
+ end
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/competion/guard-home.lua b/src/lua/intent/competion/guard-home.lua
new file mode 100644
index 0000000..c9bb789
--- /dev/null
+++ b/src/lua/intent/competion/guard-home.lua
@@ -0,0 +1,169 @@
+local fsm = require("util.fsm")
+local Region = require("region")
+local go_down_onestep = require("task.one-step.go-down-onestep")
+local cruise_in_front_of_base = require("task.guard-home.cruise-in-front-of-base")
+local occupy_fortress = require("task.guard-home.occupy-fortress")
+
+local GuardHomeIntent = {}
+GuardHomeIntent.__index = GuardHomeIntent
+
+local State = {
+ descend_onestep = "descend_onestep",
+ occupy_fortress = "occupy_fortress",
+ cruise_in_front_of_base = "cruise_in_front_of_base",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+local function target_state(ctx)
+ local target = ctx.guard_home_target()
+ if target == State.cruise_in_front_of_base then
+ return State.cruise_in_front_of_base
+ end
+ return State.occupy_fortress
+end
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, GuardHomeIntent)
+end
+
+function GuardHomeIntent:phase_name()
+ return self.phase
+end
+
+function GuardHomeIntent:create_machine(ctx)
+ local start_state = Region.is_after_fluctuant(ctx.region()) and State.descend_onestep
+ or target_state(ctx)
+ local machine = fsm:new(start_state)
+
+ machine:use({
+ state = State.descend_onestep,
+ enter = function()
+ self.phase = State.descend_onestep
+ ctx.run_job("guard_home_descend_onestep", function()
+ return go_down_onestep(self.ours_zone)
+ end)
+ end,
+ event = function(handle)
+ if not Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(target_state(ctx))
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(target_state(ctx))
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.occupy_fortress,
+ enter = function()
+ self.phase = State.occupy_fortress
+ ctx.run_job("occupy_fortress", function()
+ return occupy_fortress()
+ end)
+ end,
+ event = function(handle)
+ if Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.descend_onestep)
+ return
+ end
+
+ if target_state(ctx) == State.cruise_in_front_of_base then
+ if not ctx.job_state().done then
+ ctx.cancel_job()
+ end
+ handle:set_next(State.cruise_in_front_of_base)
+ return
+ end
+
+ local job = ctx.job_state()
+ if job.done and not job.success then
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.cruise_in_front_of_base,
+ enter = function()
+ self.phase = State.cruise_in_front_of_base
+ ctx.run_job("cruise_in_front_of_base", function()
+ return cruise_in_front_of_base(self.ours_zone)
+ end)
+ end,
+ event = function(handle)
+ if Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.descend_onestep)
+ return
+ end
+
+ if target_state(ctx) == State.occupy_fortress then
+ ctx.cancel_job()
+ handle:set_next(State.occupy_fortress)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ ctx.run_job("cruise_in_front_of_base", function()
+ return cruise_in_front_of_base(self.ours_zone)
+ end)
+ return
+ end
+
+ handle:set_next(State.failed)
+ end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "guard-home intent fsm init_ready failed")
+ return machine
+end
+
+function GuardHomeIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/competion/keep-cruise.lua b/src/lua/intent/competion/keep-cruise.lua
new file mode 100644
index 0000000..4785b5c
--- /dev/null
+++ b/src/lua/intent/competion/keep-cruise.lua
@@ -0,0 +1,90 @@
+local action = require("action")
+local fsm = require("util.fsm")
+local cruise_in_central_highlands = require("task.cruise-in-central-highland.cruise-in-central-highlands")
+
+local KeepCruiseIntent = {}
+KeepCruiseIntent.__index = KeepCruiseIntent
+
+local State = {
+ cruising = "cruising",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+ assert(type(args.switch_interval) == "number", "args.switch_interval should be a number")
+ assert(args.switch_interval > 0, "args.switch_interval should be positive")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ switch_interval = args.switch_interval,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, KeepCruiseIntent)
+end
+
+function KeepCruiseIntent:phase_name()
+ return self.phase
+end
+
+function KeepCruiseIntent:create_machine(ctx)
+ local machine = fsm:new(State.cruising)
+
+ machine:use({
+ state = State.cruising,
+ enter = function()
+ self.phase = State.cruising
+ ctx.run_job("keep_cruise", function()
+ action:info("keep-cruise: 进入中央高地持续巡航")
+ return cruise_in_central_highlands(self.ours_zone, self.switch_interval)
+ end)
+ end,
+ event = function(handle)
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ ctx.run_job("keep_cruise", function()
+ action:info("keep-cruise: 巡航任务提前结束,重新进入巡航")
+ return cruise_in_central_highlands(self.ours_zone, self.switch_interval)
+ end)
+ return
+ end
+
+ handle:set_next(State.failed)
+ end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "keep-cruise intent fsm init_ready failed")
+ return machine
+end
+
+function KeepCruiseIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/competion/start-cruise.lua b/src/lua/intent/competion/start-cruise.lua
new file mode 100644
index 0000000..18673af
--- /dev/null
+++ b/src/lua/intent/competion/start-cruise.lua
@@ -0,0 +1,144 @@
+local fsm = require("util.fsm")
+local Region = require("region")
+local cross_fluctuant_road = require("task.cross-fluctuant.cross-fluctuant-road")
+local navigate_to_fluctuant_begin = require("task.cross-fluctuant.navigate-to-fluctuant-begin")
+
+local StartCruiseIntent = {}
+StartCruiseIntent.__index = StartCruiseIntent
+
+local State = {
+ to_fluctuant_begin = "to_fluctuant_begin",
+ crossing_fluctuant = "crossing_fluctuant",
+ done = "done",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+local function initial_state(ctx)
+ if Region.is_after_fluctuant(ctx.region()) then
+ return State.done
+ end
+ if Region.is_on_fluctuant(ctx.region()) then
+ return State.crossing_fluctuant
+ end
+ return State.to_fluctuant_begin
+end
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, StartCruiseIntent)
+end
+
+function StartCruiseIntent:phase_name()
+ return self.phase
+end
+
+function StartCruiseIntent:create_machine(ctx)
+ local machine = fsm:new(initial_state(ctx))
+
+ machine:use({
+ state = State.to_fluctuant_begin,
+ enter = function()
+ self.phase = State.to_fluctuant_begin
+ ctx.run_job("navigate_to_fluctuant_begin", function()
+ return navigate_to_fluctuant_begin(self.ours_zone, true)
+ end)
+ end,
+ event = function(handle)
+ if Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.done)
+ return
+ end
+
+ if Region.is_on_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.crossing_fluctuant)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.crossing_fluctuant)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.crossing_fluctuant,
+ enter = function()
+ self.phase = State.crossing_fluctuant
+ ctx.run_job("cross_fluctuant", function()
+ return cross_fluctuant_road(self.ours_zone, true)
+ end)
+ end,
+ event = function(handle)
+ if Region.is_after_fluctuant(ctx.region()) then
+ ctx.cancel_job()
+ handle:set_next(State.done)
+ return
+ end
+
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.done)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.done,
+ enter = function()
+ self.phase = State.done
+ self.status = "success"
+ end,
+ event = function() end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "start-cruise intent fsm init_ready failed")
+ return machine
+end
+
+function StartCruiseIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/escape-to-home.lua b/src/lua/intent/escape-to-home.lua
deleted file mode 100644
index e69de29..0000000
diff --git a/src/lua/intent/train/cross-road.lua b/src/lua/intent/train/cross-road.lua
new file mode 100644
index 0000000..0a7b4b9
--- /dev/null
+++ b/src/lua/intent/train/cross-road.lua
@@ -0,0 +1,99 @@
+local action = require("action")
+local fsm = require("util.fsm")
+local cross_road_zone = require("task.cross-road.cross-road-zone")
+
+local CrossRoadIntent = {}
+CrossRoadIntent.__index = CrossRoadIntent
+
+local State = {
+ crossing = "crossing",
+ done = "done",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+ if args.forward_center == nil then
+ args.forward_center = true
+ end
+ assert(type(args.forward_center) == "boolean", "args.forward_center should be a boolean")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ forward_center = args.forward_center,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, CrossRoadIntent)
+end
+
+function CrossRoadIntent:phase_name()
+ return self.phase
+end
+
+function CrossRoadIntent:create_machine(ctx)
+ local machine = fsm:new(State.crossing)
+
+ machine:use({
+ state = State.crossing,
+ enter = function()
+ self.phase = State.crossing
+ ctx.run_job("train_cross_road", function()
+ action:info("train/cross-road: 开始通过公路区")
+ return cross_road_zone(self.ours_zone, self.forward_center)
+ end)
+ end,
+ event = function(handle)
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.done)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.done,
+ enter = function()
+ self.phase = State.done
+ self.status = "success"
+ action:info("train/cross-road: 已通过公路区")
+ end,
+ event = function() end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "train cross-road intent fsm init_ready failed")
+ return machine
+end
+
+function CrossRoadIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/train/escape-to-home.lua b/src/lua/intent/train/escape-to-home.lua
new file mode 100644
index 0000000..c52024d
--- /dev/null
+++ b/src/lua/intent/train/escape-to-home.lua
@@ -0,0 +1,177 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local fsm = require("util.fsm")
+local navigate_to_point = require("task.navigate-to-point")
+
+local EscapeToHomeIntent = {}
+EscapeToHomeIntent.__index = EscapeToHomeIntent
+
+local State = {
+ follow_route = "follow_route",
+ done = "done",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+local function select_point(point, ours_zone)
+ if type(point.x) == "number" and type(point.y) == "number" then
+ return point
+ end
+ return ours_zone and point.ours or point.them
+end
+
+function M.new(args)
+ args = args or {}
+ assert(type(args) == "table", "args should be a table")
+ if args.ours_zone == nil then
+ args.ours_zone = true
+ end
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ route = args.route or "ours_home",
+ tolerance = args.tolerance or 0.15,
+ timeout = args.timeout or 10.0,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, EscapeToHomeIntent)
+end
+
+function EscapeToHomeIntent:phase_name()
+ return self.phase
+end
+
+function EscapeToHomeIntent:create_route_targets()
+ local rule = blackboard.rule
+ local road_begin = select_point(rule.road_zone_begin, self.ours_zone)
+ local road_final = select_point(rule.road_zone_final, self.ours_zone)
+ local way_point_1 = select_point(rule.road_zone_way_point_1, self.ours_zone)
+ local way_point_2 = select_point(rule.road_zone_way_point_2, self.ours_zone)
+ local resupply_zone = select_point(rule.resupply_zone, self.ours_zone)
+
+ if self.route == "highland" then
+ return {
+ { name = "road_zone_final", point = road_final },
+ { name = "road_zone_way_point_2", point = way_point_2 },
+ { name = "road_zone_way_point_1", point = way_point_1 },
+ { name = "road_zone_begin", point = road_begin },
+ { name = "resupply_zone", point = resupply_zone },
+ }
+ end
+
+ if self.route == "road_region_final" then
+ return {
+ { name = "road_zone_way_point_2", point = way_point_2 },
+ { name = "road_zone_way_point_1", point = way_point_1 },
+ { name = "road_zone_begin", point = road_begin },
+ { name = "resupply_zone", point = resupply_zone },
+ }
+ end
+
+ if self.route == "road_region_2" then
+ return {
+ { name = "road_zone_way_point_1", point = way_point_1 },
+ { name = "road_zone_begin", point = road_begin },
+ { name = "resupply_zone", point = resupply_zone },
+ }
+ end
+
+ if self.route == "road_region_1" then
+ return {
+ { name = "road_zone_begin", point = road_begin },
+ { name = "resupply_zone", point = resupply_zone },
+ }
+ end
+
+ if self.route == "ours_home" or self.route == "road_region_begin" or self.route == "direct" then
+ return {
+ { name = "resupply_zone", point = resupply_zone },
+ }
+ end
+
+ error("unknown train escape route: " .. tostring(self.route))
+end
+
+function EscapeToHomeIntent:create_machine(ctx)
+ local machine = fsm:new(State.follow_route)
+
+ machine:use({
+ state = State.follow_route,
+ enter = function()
+ self.phase = State.follow_route
+ action:update_chassis_mode("SPIN")
+ ctx.run_job("train_escape_follow_route", function()
+ action:info("train/escape-to-home: 回家路径 -> " .. self.route)
+ for _, target in ipairs(self:create_route_targets()) do
+ action:info(string.format(
+ "train/escape-to-home: 导航到%s (x=%.2f, y=%.2f)",
+ target.name,
+ target.point.x,
+ target.point.y
+ ))
+ local ok = navigate_to_point(target.point, {
+ tolerance = self.tolerance,
+ timeout = self.timeout,
+ })
+ if not ok then
+ action:warn("train/escape-to-home: 导航到" .. target.name .. "失败")
+ return false
+ end
+ end
+ return true
+ end)
+ end,
+ event = function(handle)
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ handle:set_next(State.done)
+ else
+ handle:set_next(State.failed)
+ end
+ end,
+ })
+
+ machine:use({
+ state = State.done,
+ enter = function()
+ self.phase = State.done
+ self.status = "success"
+ action:info("train/escape-to-home: 已抵达补给点")
+ end,
+ event = function() end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "train escape-to-home intent fsm init_ready failed")
+ return machine
+end
+
+function EscapeToHomeIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/train/keep-cruise.lua b/src/lua/intent/train/keep-cruise.lua
new file mode 100644
index 0000000..e76f073
--- /dev/null
+++ b/src/lua/intent/train/keep-cruise.lua
@@ -0,0 +1,90 @@
+local action = require("action")
+local fsm = require("util.fsm")
+local cruise_in_central_highlands = require("task.cruise-in-central-highland.cruise-in-central-highlands")
+
+local KeepCruiseIntent = {}
+KeepCruiseIntent.__index = KeepCruiseIntent
+
+local State = {
+ cruising = "cruising",
+ failed = "failed",
+}
+
+local M = {
+ State = State,
+}
+
+function M.new(args)
+ assert(type(args) == "table", "args should be a table")
+ assert(type(args.ours_zone) == "boolean", "args.ours_zone should be a boolean")
+ assert(type(args.switch_interval) == "number", "args.switch_interval should be a number")
+ assert(args.switch_interval > 0, "args.switch_interval should be positive")
+
+ return setmetatable({
+ ours_zone = args.ours_zone,
+ switch_interval = args.switch_interval,
+ phase = "none",
+ status = "running",
+ machine = nil,
+ }, KeepCruiseIntent)
+end
+
+function KeepCruiseIntent:phase_name()
+ return self.phase
+end
+
+function KeepCruiseIntent:create_machine(ctx)
+ local machine = fsm:new(State.cruising)
+
+ machine:use({
+ state = State.cruising,
+ enter = function()
+ self.phase = State.cruising
+ ctx.run_job("train_keep_cruise", function()
+ action:info("train/keep-cruise: 进入中央高地巡航")
+ return cruise_in_central_highlands(self.ours_zone, self.switch_interval)
+ end)
+ end,
+ event = function(handle)
+ local job = ctx.job_state()
+ if not job.done then
+ return
+ end
+
+ if job.success then
+ ctx.run_job("train_keep_cruise", function()
+ action:info("train/keep-cruise: 巡航任务提前结束,重新进入巡航")
+ return cruise_in_central_highlands(self.ours_zone, self.switch_interval)
+ end)
+ return
+ end
+
+ handle:set_next(State.failed)
+ end,
+ })
+
+ machine:use({
+ state = State.failed,
+ enter = function()
+ self.phase = State.failed
+ self.status = "failed"
+ end,
+ event = function() end,
+ })
+
+ assert(machine:init_ready(State), "train keep-cruise intent fsm init_ready failed")
+ return machine
+end
+
+function KeepCruiseIntent:spin(ctx)
+ assert(type(ctx) == "table", "ctx should be a table")
+ if self.machine == nil then
+ self.machine = self:create_machine(ctx)
+ end
+ if self.status == "running" then
+ self.machine:spin_once()
+ end
+ return self.status
+end
+
+return M
diff --git a/src/lua/intent/train/start-cruise-train.lua b/src/lua/intent/train/start-cruise-train.lua
new file mode 100644
index 0000000..366df44
--- /dev/null
+++ b/src/lua/intent/train/start-cruise-train.lua
@@ -0,0 +1,21 @@
+local action = require("action")
+local cross_road_zone = require("task.cross-road.cross-road-zone")
+
+--- 训练专用旧入口兼容:
+--- 保持 train-decision.lua 旧的函数式调用契约,
+--- 内部桥接到当前 train 路线的公路区通过任务。
+--- @param ours_zone boolean
+--- @return boolean is_success
+return function(ours_zone)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ action:info("开始start-cruise-train")
+
+ local ok = cross_road_zone(ours_zone, true)
+ if not ok then
+ action:warn("start-cruise-train: 通过公路区训练路线失败")
+ return false
+ end
+
+ action:info("start-cruise-train: 已完成公路区训练路线")
+ return true
+end
diff --git a/src/lua/region.lua b/src/lua/region.lua
new file mode 100644
index 0000000..8d42739
--- /dev/null
+++ b/src/lua/region.lua
@@ -0,0 +1,77 @@
+local blackboard = require("blackboard").singleton()
+local Map = require("rmuc_map")
+local ReturnStage = require("util.return-stage")
+local RegionId = Map.Region
+
+local Phase = {
+ unknown = "unknown",
+ before_fluctuant = "before_fluctuant",
+ on_fluctuant = "on_fluctuant",
+ after_fluctuant = "after_fluctuant",
+}
+
+local M = {
+ Phase = Phase,
+}
+
+function M.current()
+ local map = Map.singleton()
+ local region = map:locate({
+ x = blackboard.user.x,
+ y = blackboard.user.y,
+ })
+ return region, map.names[region] or "unknown"
+end
+
+function M.phase(region)
+ if region == RegionId.OURS_HOME
+ or region == RegionId.THEM_HOME
+ or region == RegionId.OURS_ROAD_TO_FLUCTUANT
+ or region == RegionId.THEM_ROAD_TO_FLUCTUANT then
+ return Phase.before_fluctuant
+ end
+
+ if region == RegionId.OURS_FLUCTUANT or region == RegionId.THEM_FLUCTUANT then
+ return Phase.on_fluctuant
+ end
+
+ if region == RegionId.OURS_TRAPEZOIDAL_HIGHLAND
+ or region == RegionId.THEM_TRAPEZOIDAL_HIGHLAND
+ or region == RegionId.OURS_ROAD_TO_HIGHLAND
+ or region == RegionId.THEM_ROAD_TO_HIGHLAND
+ or region == RegionId.OURS_HIGHLAND
+ or region == RegionId.THEM_HIGHLAND then
+ return Phase.after_fluctuant
+ end
+
+ return Phase.unknown
+end
+
+function M.return_stage(region)
+ local phase = M.phase(region)
+ if phase == Phase.on_fluctuant then
+ return ReturnStage.on_fluctuant
+ end
+ if phase == Phase.after_fluctuant then
+ return ReturnStage.after_fluctuant
+ end
+ return ReturnStage.before_fluctuant
+end
+
+function M.escape_route(region)
+ return ReturnStage.resolve_escape_route(M.return_stage(region))
+end
+
+function M.is_before_fluctuant(region)
+ return M.phase(region) == Phase.before_fluctuant
+end
+
+function M.is_on_fluctuant(region)
+ return M.phase(region) == Phase.on_fluctuant
+end
+
+function M.is_after_fluctuant(region)
+ return M.phase(region) == Phase.after_fluctuant
+end
+
+return M
diff --git a/src/lua/rmuc_map.lua b/src/lua/rmuc_map.lua
new file mode 100644
index 0000000..6aa3b96
--- /dev/null
+++ b/src/lua/rmuc_map.lua
@@ -0,0 +1,170 @@
+local Region = {
+ WALL = 0,
+ OURS_HOME = 1,
+ THEM_HOME = 2,
+ OURS_FLUCTUANT = 3,
+ THEM_FLUCTUANT = 4,
+ OURS_ROAD_BEGIN = 5,
+ THEM_ROAD_BEGIN = 6,
+ OURS_TRAPEZOIDAL_HIGHLAND = 7,
+ THEM_TRAPEZOIDAL_HIGHLAND = 8,
+ OURS_ROAD_WAYPOINT_1 = 9,
+ THEM_ROAD_WAYPOINT_1 = 10,
+ OURS_ROAD_TO_FLUCTUANT = 13,
+ THEM_ROAD_TO_FLUCTUANT = 14,
+ OURS_ROAD_TO_HIGHLAND = 15,
+ THEM_ROAD_TO_HIGHLAND = 16,
+ OURS_HIGHLAND = 17,
+ THEM_HIGHLAND = 18,
+}
+
+local RegionName = {
+ [Region.WALL] = "wall",
+ [Region.OURS_HOME] = "ours_home",
+ [Region.THEM_HOME] = "them_home",
+ [Region.OURS_FLUCTUANT] = "ours_fluctuant",
+ [Region.THEM_FLUCTUANT] = "them_fluctuant",
+ [Region.OURS_ROAD_BEGIN] = "ours_road_begin",
+ [Region.THEM_ROAD_BEGIN] = "thems_road_begin",
+ [Region.OURS_TRAPEZOIDAL_HIGHLAND] = "ours_trapezoidal_highland",
+ [Region.THEM_TRAPEZOIDAL_HIGHLAND] = "them_trapezoidal_highland",
+ [Region.OURS_ROAD_WAYPOINT_1] = "ours_road_waypoint_1",
+ [Region.THEM_ROAD_WAYPOINT_1] = "them_road_waypoint_1",
+ [Region.OURS_ROAD_TO_FLUCTUANT] = "ours_road_to_fluctuant",
+ [Region.THEM_ROAD_TO_FLUCTUANT] = "them_road_to_fluctuant",
+ [Region.OURS_ROAD_TO_HIGHLAND] = "ours_road_to_highland",
+ [Region.THEM_ROAD_TO_HIGHLAND] = "them_road_to_highland",
+ [Region.OURS_HIGHLAND] = "ours_highland",
+ [Region.THEM_HIGHLAND] = "them_highland",
+}
+
+local Map = {}
+Map.__index = Map
+local DEFAULT_MAP_NAME = "rmuc"
+
+local function dirname(path)
+ return path:match("^(.*)/[^/]*$") or "."
+end
+
+local function source_dir()
+ local source = debug.getinfo(1, "S").source
+ if source:sub(1, 1) == "@" then
+ return dirname(source:sub(2))
+ end
+ return "."
+end
+
+local function load_map_data(name)
+ local lua_dir = source_dir()
+ local candidates = {
+ lua_dir .. "/../maps/" .. name .. ".lua",
+ lua_dir .. "/../../maps/" .. name .. ".lua",
+ }
+ local errors = {}
+
+ for _, path in ipairs(candidates) do
+ local chunk, err = loadfile(path)
+ if chunk then
+ return chunk()
+ end
+ errors[#errors + 1] = path .. ": " .. tostring(err)
+ end
+
+ error("failed to load region map " .. name .. ":\n" .. table.concat(errors, "\n"))
+end
+
+local function is_finite_number(value)
+ return type(value) == "number" and value == value and value ~= math.huge and value ~= -math.huge
+end
+
+local function is_positive_integer(value)
+ return is_finite_number(value) and value > 0 and math.floor(value) == value
+end
+
+local function validate_data(data)
+ assert(type(data) == "table", "region map data should be a table")
+ assert(is_positive_integer(data.width), "region map data.width should be a positive integer")
+ assert(is_positive_integer(data.height), "region map data.height should be a positive integer")
+ assert(is_finite_number(data.resolution) and data.resolution > 0, "region map data.resolution should be positive")
+ assert(type(data.origin) == "table", "region map data.origin should be a table")
+ assert(is_finite_number(data.origin.x), "region map data.origin.x should be finite")
+ assert(is_finite_number(data.origin.y), "region map data.origin.y should be finite")
+ assert(type(data.rows) == "table", "region map data.rows should be a table")
+
+ for y = 1, data.height do
+ local row = data.rows[y]
+ assert(type(row) == "table", "region map row " .. y .. " should be a table")
+ for x = 1, data.width do
+ assert(type(row[x]) == "number", "region map cell " .. y .. "," .. x .. " should be a number")
+ end
+ end
+end
+
+local function new_map(data)
+ validate_data(data)
+
+ return setmetatable({
+ width = data.width,
+ height = data.height,
+ resolution = data.resolution,
+ origin = data.origin,
+ names = data.names or RegionName,
+ rows = data.rows,
+ }, Map)
+end
+
+local function load_map(name)
+ return new_map(load_map_data(name))
+end
+
+function Map:locate(position)
+ assert(type(position) == "table", "position should be a table")
+ assert(type(position.x) == "number", "position.x should be a number")
+ assert(type(position.y) == "number", "position.y should be a number")
+
+ if not is_finite_number(position.x) or not is_finite_number(position.y) then
+ return Region.WALL
+ end
+
+ local column = math.floor((position.x - self.origin.x) / self.resolution) + 1
+ local row = self.height - math.floor((position.y - self.origin.y) / self.resolution)
+
+ if column < 1 or column > self.width or row < 1 or row > self.height then
+ return Region.WALL
+ end
+
+ local map_row = self.rows[row]
+ if map_row == nil then
+ return Region.WALL
+ end
+
+ return map_row[column] or Region.WALL
+end
+
+local singleton
+local singleton_name
+
+function Map.singleton(name)
+ if name ~= nil then
+ assert(type(name) == "string", "map name should be a string")
+ if singleton == nil or singleton_name ~= name then
+ singleton = load_map(name)
+ singleton_name = name
+ end
+ return singleton
+ end
+
+ if singleton == nil then
+ return Map.singleton(DEFAULT_MAP_NAME)
+ end
+
+ return singleton
+end
+
+function Map.current_name()
+ return singleton_name or DEFAULT_MAP_NAME
+end
+
+Map.Region = Region
+
+return Map
diff --git a/src/lua/task/cross-fluctuant/cross-fluctuant-road.lua b/src/lua/task/cross-fluctuant/cross-fluctuant-road.lua
new file mode 100644
index 0000000..2153e5e
--- /dev/null
+++ b/src/lua/task/cross-fluctuant/cross-fluctuant-road.lua
@@ -0,0 +1,53 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+--- @param ours_zone boolean
+--- @param forward_center boolean
+--- @return boolean is_success
+return function(ours_zone, forward_center)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ assert(type(forward_center) == "boolean", "forward_center should be a boolean")
+ action:info("开始cross-fluctuant-road")
+
+ local rule = blackboard.rule
+ local begin, final
+ if ours_zone then
+ begin = rule.fluctuant_road_begin.ours
+ final = rule.fluctuant_road_final.ours
+ else
+ begin = rule.fluctuant_road_begin.them
+ final = rule.fluctuant_road_final.them
+ end
+
+ local to, gimbal_yaw
+ if forward_center then
+ to = final
+ gimbal_yaw = 0
+ else
+ to = begin
+ gimbal_yaw = math.pi
+ end
+
+ action:update_chassis_mode("LAUNCH_RAMP")
+ action:info(string.format(
+ "cross-fluctuant-road: LAUNCH_RAMP 云台朝向=%.3f rad",
+ gimbal_yaw
+ ))
+ action:update_gimbal_direction(gimbal_yaw)
+ local ok = navigate_to_point(to, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ if not ok then
+ action:warn(string.format(
+ "cross-fluctuant-road: 导航到终点失败 (x=%.2f, y=%.2f)",
+ to.x,
+ to.y
+ ))
+ return false
+ end
+
+ action:update_chassis_mode("SPIN")
+ return true
+end
diff --git a/src/lua/task/cross-fluctuant/navigate-to-fluctuant-begin.lua b/src/lua/task/cross-fluctuant/navigate-to-fluctuant-begin.lua
new file mode 100644
index 0000000..e18554f
--- /dev/null
+++ b/src/lua/task/cross-fluctuant/navigate-to-fluctuant-begin.lua
@@ -0,0 +1,65 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+local function select_point(point, ours_zone)
+ if type(point.x) == "number" and type(point.y) == "number" then
+ return point
+ end
+ return ours_zone and point.ours or point.them
+end
+
+--- @param ours_zone boolean
+--- @param use_begin boolean|nil
+--- @return boolean is_success
+return function(ours_zone, use_begin)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ if use_begin == nil then
+ use_begin = true
+ end
+ assert(type(use_begin) == "boolean", "use_begin should be a boolean")
+
+ local rule = blackboard.rule
+ local targets
+ if use_begin then
+ targets = {
+ {
+ name = "road_zone_begin",
+ point = select_point(rule.road_zone_begin, ours_zone),
+ },
+ {
+ name = "road_zone_way_point_1",
+ point = select_point(rule.road_zone_way_point_1, ours_zone),
+ },
+ {
+ name = "fluctuant_road_begin",
+ point = select_point(rule.fluctuant_road_begin, ours_zone),
+ },
+ }
+ else
+ targets = {
+ {
+ name = "fluctuant_road_final",
+ point = select_point(rule.fluctuant_road_final, ours_zone),
+ },
+ }
+ end
+
+ for _, target in ipairs(targets) do
+ local ok = navigate_to_point(target.point, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ if not ok then
+ action:warn(string.format(
+ "navigate-to-fluctuant-begin: 导航到%s失败 (x=%.2f, y=%.2f)",
+ target.name,
+ target.point.x,
+ target.point.y
+ ))
+ return false
+ end
+ end
+
+ return true
+end
diff --git a/src/lua/task/cross-road/cross-road-zone.lua b/src/lua/task/cross-road/cross-road-zone.lua
new file mode 100644
index 0000000..76dc84f
--- /dev/null
+++ b/src/lua/task/cross-road/cross-road-zone.lua
@@ -0,0 +1,72 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+local function select_point(point, ours_zone)
+ if type(point.x) == "number" and type(point.y) == "number" then
+ return point
+ end
+ return ours_zone and point.ours or point.them
+end
+
+--- @param ours_zone boolean
+--- @param forward_center boolean
+--- @return boolean is_success
+return function(ours_zone, forward_center)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ assert(type(forward_center) == "boolean", "forward_center should be a boolean")
+ action:info("开始cross-road-zone")
+
+ local rule = blackboard.rule
+ local targets
+ if forward_center then
+ targets = {
+ {
+ name = "road_zone_way_point_1",
+ point = select_point(rule.road_zone_way_point_1, ours_zone),
+ },
+ {
+ name = "road_zone_way_point_2",
+ point = select_point(rule.road_zone_way_point_2, ours_zone),
+ },
+ {
+ name = "road_zone_final",
+ point = select_point(rule.road_zone_final, ours_zone),
+ },
+ }
+ else
+ targets = {
+ {
+ name = "road_zone_final",
+ point = select_point(rule.road_zone_final, ours_zone),
+ },
+ {
+ name = "road_zone_way_point_2",
+ point = select_point(rule.road_zone_way_point_2, ours_zone),
+ },
+ {
+ name = "road_zone_way_point_1",
+ point = select_point(rule.road_zone_way_point_1, ours_zone),
+ },
+ }
+ end
+
+ for _, target in ipairs(targets) do
+ local ok = navigate_to_point(target.point, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ if not ok then
+ action:warn(string.format(
+ "cross-road-zone: 导航到%s失败 (x=%.2f, y=%.2f)",
+ target.name,
+ target.point.x,
+ target.point.y
+ ))
+ return false
+ end
+ end
+
+ action:update_chassis_mode("SPIN")
+ return true
+end
diff --git a/src/lua/task/crossing-road-zone.lua b/src/lua/task/crossing-road-zone.lua
deleted file mode 100644
index aa72fcc..0000000
--- a/src/lua/task/crossing-road-zone.lua
+++ /dev/null
@@ -1,39 +0,0 @@
-local blackboard = require("blackboard").singleton()
-local request = require("util.scheduler").request
-local action = require("action")
-
---- @param ours_zone boolean
---- @param forward_center boolean
-return function(ours_zone, forward_center)
- local x = blackboard.user.x
- local y = blackboard.user.y
-
- local rule = blackboard.rule
- local begin, final
- if ours_zone then
- begin = rule.road_zone_begin.ours
- final = rule.road_zone_final.ours
- else
- begin = rule.road_zone_begin.them
- final = rule.road_zone_final.them
- end
-
- local from, to
- if forward_center then
- from = begin
- to = final
- else
- from = final
- to = begin
- end
-
- local condition = blackboard.condition
-
- action:navigate(from)
- local timeout = request:wait_until {
- monitor = function()
- return condition.near(from, 0.1)
- end,
- timeout = 10,
- }
-end
diff --git a/src/lua/task/cruise-in-central-highland/cruise-in-central-highlands.lua b/src/lua/task/cruise-in-central-highland/cruise-in-central-highlands.lua
new file mode 100644
index 0000000..a59b81a
--- /dev/null
+++ b/src/lua/task/cruise-in-central-highland/cruise-in-central-highlands.lua
@@ -0,0 +1,81 @@
+local blackboard = require("blackboard").singleton()
+local clock = require("util.clock")
+local request = require("util.scheduler").request
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+local function select_point(point, ours_zone)
+ if type(point.x) == "number" and type(point.y) == "number" then
+ return point
+ end
+ return ours_zone and point.ours or point.them
+end
+
+--- 中央高地巡航:按固定顺序在中央高地巡航点之间切换导航目标。
+--- @param ours_zone boolean
+--- @param switch_interval number 切换周期(秒)
+return function(ours_zone, switch_interval)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ assert(type(switch_interval) == "number", "switch_interval should be a number")
+ assert(switch_interval > 0, "switch_interval should be positive")
+ action:info("开始cruise-in-central-highlands")
+
+ local rule = blackboard.rule
+ local navigation_timeout = math.max(10.0, switch_interval * 2.0)
+ local near_fluctuant_road, middle, near_doghole
+ if ours_zone then
+ near_fluctuant_road = rule.central_highland_near_fluctuant_road.ours
+ near_doghole = rule.central_highland_near_doghole.ours
+ else
+ near_fluctuant_road = rule.central_highland_near_fluctuant_road.them
+ near_doghole = rule.central_highland_near_doghole.them
+ end
+ middle = select_point(rule.central_highland_middle, ours_zone)
+
+ local targets = {
+ {
+ name = "central_highland_near_fluctuant_road",
+ point = near_fluctuant_road,
+ },
+ {
+ name = "central_highland_middle",
+ point = middle,
+ },
+ {
+ name = "central_highland_near_doghole",
+ point = near_doghole,
+ },
+ }
+ local target_index = 1
+
+ while true do
+ local target = targets[target_index]
+ local phase_start = clock:now()
+ action:update_chassis_mode("SPIN")
+ local ok = navigate_to_point(target.point, {
+ tolerance = 0.4,
+ timeout = navigation_timeout,
+ })
+ if not ok then
+ action:warn(string.format(
+ "cruise-in-central-highlands: 导航到%s失败 (x=%.2f, y=%.2f, timeout=%.2fs)",
+ target.name,
+ target.point.x,
+ target.point.y,
+ navigation_timeout
+ ))
+ return false
+ end
+
+ -- 保持固定切换周期:若提前到达,则驻留到本周期结束后再切点。
+ local elapsed = clock:now() - phase_start
+ local remain = switch_interval - elapsed
+ if remain > 0 then
+ request:sleep(remain)
+ end
+
+ target_index = target_index % #targets + 1
+ end
+
+ return true
+end
diff --git a/src/lua/task/forward-press/forward-press-in-one-step.lua b/src/lua/task/forward-press/forward-press-in-one-step.lua
new file mode 100644
index 0000000..278a5b3
--- /dev/null
+++ b/src/lua/task/forward-press/forward-press-in-one-step.lua
@@ -0,0 +1,28 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+--- 前压至对方半场起伏路段终点
+--- @return boolean is_success
+return function()
+ action:info("开始forward-press-in-one-step")
+
+ local rule = blackboard.rule
+ local enemy_fluctuant_road_final = rule.fluctuant_road_final.them
+
+ action:update_chassis_mode("SPIN")
+ local ok = navigate_to_point(enemy_fluctuant_road_final, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ if not ok then
+ action:warn(string.format(
+ "forward-press-in-one-step: 导航到对方起伏路段终点失败 (x=%.2f, y=%.2f)",
+ enemy_fluctuant_road_final.x,
+ enemy_fluctuant_road_final.y
+ ))
+ return false
+ end
+
+ return true
+end
diff --git a/src/lua/task/forward-press/forward-press-in-two-step.lua b/src/lua/task/forward-press/forward-press-in-two-step.lua
new file mode 100644
index 0000000..448f486
--- /dev/null
+++ b/src/lua/task/forward-press/forward-press-in-two-step.lua
@@ -0,0 +1,61 @@
+local blackboard = require("blackboard").singleton()
+local clock = require("util.clock")
+local request = require("util.scheduler").request
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+--- 前压至对方高地在二级台阶侧与高地增益点之间巡航。
+--- @param switch_interval number 切换周期(秒)
+--- @return boolean is_success
+return function(switch_interval)
+ assert(type(switch_interval) == "number", "switch_interval should be a number")
+ assert(switch_interval > 0, "switch_interval should be positive")
+ action:info("开始forward-press-in-two-step")
+
+ local rule = blackboard.rule
+ local enemy_gain_point = rule.central_highland_gain_point.them
+ local enemy_near_two_steps_and_outpost = rule.central_highland_near_two_steps_and_outpost.them
+
+ local navigation_timeout = math.max(10.0, switch_interval * 2.0)
+ local targets = {
+ {
+ name = "central_highland_gain_point",
+ point = enemy_gain_point,
+ },
+ {
+ name = "central_highland_near_two_steps_and_outpost",
+ point = enemy_near_two_steps_and_outpost,
+ },
+ }
+ local target_index = 1
+
+ while true do
+ local target = targets[target_index]
+ local phase_start = clock:now()
+ action:update_chassis_mode("SPIN")
+ local ok = navigate_to_point(target.point, {
+ tolerance = 0.4,
+ timeout = navigation_timeout,
+ })
+ if not ok then
+ action:warn(string.format(
+ "forward-press-in-two-step: 导航到%s失败 (x=%.2f, y=%.2f, timeout=%.2fs)",
+ target.name,
+ target.point.x,
+ target.point.y,
+ navigation_timeout
+ ))
+ return false
+ end
+
+ local elapsed = clock:now() - phase_start
+ local remain = switch_interval - elapsed
+ if remain > 0 then
+ request:sleep(remain)
+ end
+
+ target_index = target_index % #targets + 1
+ end
+
+ return true
+end
diff --git a/src/lua/task/guard-home/cruise-in-front-of-base.lua b/src/lua/task/guard-home/cruise-in-front-of-base.lua
new file mode 100644
index 0000000..67eda34
--- /dev/null
+++ b/src/lua/task/guard-home/cruise-in-front-of-base.lua
@@ -0,0 +1,79 @@
+local blackboard = require("blackboard").singleton()
+local clock = require("util.clock")
+local request = require("util.scheduler").request
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+local switch_interval = 10.0
+
+local function distance_to(target)
+ local dx = target.x - blackboard.user.x
+ local dy = target.y - blackboard.user.y
+ return math.sqrt(dx * dx + dy * dy)
+end
+
+--- 在基地前方左右增益点之间按固定周期切换巡航。
+--- @param ours_zone boolean
+--- @return boolean is_success
+return function(ours_zone)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ action:info("开始cruise-in-front-of-base")
+
+ local rule = blackboard.rule
+ local left_gain_point, right_gain_point
+ if ours_zone then
+ left_gain_point = rule.base_left_gain_point.ours
+ right_gain_point = rule.base_right_gain_point.ours
+ else
+ left_gain_point = rule.base_left_gain_point.them
+ right_gain_point = rule.base_right_gain_point.them
+ end
+
+ local navigation_timeout = math.max(10.0, switch_interval * 2.0)
+ local targets = {
+ {
+ name = "base_left_gain_point",
+ point = left_gain_point,
+ },
+ {
+ name = "base_right_gain_point",
+ point = right_gain_point,
+ },
+ }
+ local target_index
+ if distance_to(targets[1].point) <= distance_to(targets[2].point) then
+ target_index = 1
+ else
+ target_index = 2
+ end
+
+ while true do
+ local target = targets[target_index]
+ local phase_start = clock:now()
+ action:update_chassis_mode("SPIN")
+ local ok = navigate_to_point(target.point, {
+ tolerance = 0.4,
+ timeout = navigation_timeout,
+ })
+ if not ok then
+ action:warn(string.format(
+ "cruise-in-front-of-base: 导航到%s失败 (x=%.2f, y=%.2f, timeout=%.2fs)",
+ target.name,
+ target.point.x,
+ target.point.y,
+ navigation_timeout
+ ))
+ return false
+ end
+
+ local elapsed = clock:now() - phase_start
+ local remain = switch_interval - elapsed
+ if remain > 0 then
+ request:sleep(remain)
+ end
+
+ target_index = target_index % #targets + 1
+ end
+
+ return true
+end
diff --git a/src/lua/task/guard-home/occupy-fortress.lua b/src/lua/task/guard-home/occupy-fortress.lua
new file mode 100644
index 0000000..baa417f
--- /dev/null
+++ b/src/lua/task/guard-home/occupy-fortress.lua
@@ -0,0 +1,27 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local navigate_to_point = require("task.navigate-to-point")
+
+--- @return boolean is_success
+return function()
+ action:info("开始occupy-fortress")
+
+ local rule = blackboard.rule
+ local fortress = rule.fortress.ours
+
+ action:update_chassis_mode("SPIN")
+ local is_success = navigate_to_point(fortress, {
+ tolerance = 0.4,
+ timeout = 10,
+ })
+ if not is_success then
+ action:warn(string.format(
+ "occupy-fortress: 导航到己方堡垒失败 (x=%.2f, y=%.2f)",
+ fortress.x,
+ fortress.y
+ ))
+ return false
+ end
+
+ return true
+end
diff --git a/src/lua/task/navigate-to-point.lua b/src/lua/task/navigate-to-point.lua
new file mode 100644
index 0000000..ac073e1
--- /dev/null
+++ b/src/lua/task/navigate-to-point.lua
@@ -0,0 +1,51 @@
+local blackboard = require("blackboard").singleton()
+local request = require("util.scheduler").request
+local action = require("action")
+
+--- @class NavigateToPointOptions
+--- @field tolerance? number|{x: number, y: number}
+--- @field timeout? number
+
+local function normalize_options(options)
+ options = options or {}
+ assert(type(options) == "table", "options should be a table")
+
+ local tolerance = options.tolerance or 0.1
+ if type(tolerance) == "number" then
+ assert(tolerance >= 0, "tolerance should be non-negative")
+ else
+ assert(type(tolerance) == "table", "tolerance should be number or {x, y}")
+ assert(type(tolerance.x) == "number", "tolerance.x should be a number")
+ assert(type(tolerance.y) == "number", "tolerance.y should be a number")
+ assert(tolerance.x >= 0 and tolerance.y >= 0, "tolerance.{x,y} should be non-negative")
+ end
+
+ local timeout = options.timeout or 10
+ assert(type(timeout) == "number", "timeout should be a number")
+ assert(timeout >= 0, "timeout should be non-negative")
+
+ return tolerance, timeout
+end
+
+--- 普通点位导航:设置目标点并等待到达(或超时)。
+--- @param point {x: number, y: number}
+--- @param options? NavigateToPointOptions
+--- @return boolean is_success
+return function(point, options)
+ assert(type(point) == "table", "point should be a table")
+ assert(type(point.x) == "number", "point.x should be a number")
+ assert(type(point.y) == "number", "point.y should be a number")
+ action:info("开始navigate-to-point")
+
+ local tolerance, timeout = normalize_options(options)
+ local condition = blackboard.condition
+
+ action:navigate(point)
+ local is_timeout = request:wait_until {
+ monitor = function()
+ return condition.near(point, tolerance)
+ end,
+ timeout = timeout,
+ }
+ return not is_timeout
+end
diff --git a/src/lua/task/one-step/go-down-onestep.lua b/src/lua/task/one-step/go-down-onestep.lua
new file mode 100644
index 0000000..574fd10
--- /dev/null
+++ b/src/lua/task/one-step/go-down-onestep.lua
@@ -0,0 +1,71 @@
+local blackboard = require("blackboard").singleton()
+local action = require("action")
+local Map = require("rmuc_map")
+local request = require("util.scheduler").request
+local navigate_to_point = require("task.navigate-to-point")
+
+--- 从当前位置依次经过一级台阶高点与低点。
+--- @param ours_zone boolean
+--- @return boolean is_success
+return function(ours_zone)
+ assert(type(ours_zone) == "boolean", "ours_zone should be a boolean")
+ action:info("开始go-down-onestep")
+
+ local rule = blackboard.rule
+ local one_step_high, one_step_low
+ if ours_zone then
+ one_step_high = rule.one_step_begin.ours
+ one_step_low = rule.one_step_final.ours
+ else
+ one_step_high = rule.one_step_begin.them
+ one_step_low = rule.one_step_final.them
+ end
+
+ local ok = navigate_to_point(one_step_high, {
+ tolerance = 0.1,
+ timeout = 10,
+ })
+ if not ok then
+ action:warn("go-down-onestep: 导航到一级台阶高点失败")
+ return false
+ end
+
+ action:update_chassis_mode("LAUNCH_RAMP")
+ local dx = one_step_low.x - one_step_high.x
+ local dy = one_step_low.y - one_step_high.y
+ local distance = math.sqrt(dx * dx + dy * dy)
+ if distance <= 0 then
+ action:warn("go-down-onestep: 一级台阶高点与低点重合,无法确定下台阶方向")
+ return false
+ end
+
+ local gimbal_yaw = math.atan(dy, dx)
+ local linear_speed = 2.0
+ local vx = dx / distance * linear_speed
+ local vy = dy / distance * linear_speed
+ action:info(string.format(
+ "go-down-onestep: 云台朝向=%.3f rad, 底盘速度=(%.3f, %.3f) m/s",
+ gimbal_yaw,
+ vx,
+ vy
+ ))
+ action:update_gimbal_direction(gimbal_yaw)
+
+ action:update_chassis_vel(vx, vy)
+ request:sleep(1.0)
+ local map = Map.singleton()
+ local expected_region = ours_zone and Map.Region.OURS_ROAD_TO_FLUCTUANT
+ or Map.Region.THEM_ROAD_TO_FLUCTUANT
+ ok = map:locate({
+ x = blackboard.user.x,
+ y = blackboard.user.y,
+ }) == expected_region
+ action:update_chassis_vel(0.0, 0.0)
+ if not ok then
+ action:warn("go-down-onestep: 导航到一级台阶低点失败")
+ return false
+ end
+ action:update_chassis_mode("SPIN")
+
+ return true
+end
diff --git a/src/lua/task/supply/supply-ammunition.lua b/src/lua/task/supply/supply-ammunition.lua
new file mode 100644
index 0000000..2d8bc9a
--- /dev/null
+++ b/src/lua/task/supply/supply-ammunition.lua
@@ -0,0 +1,39 @@
+local blackboard = require("blackboard").singleton()
+local request = require("util.scheduler").request
+local action = require("action")
+
+local POLL_INTERVAL = 0.2
+
+--- 在补给点等待,直到弹量达到 ready 阈值。
+--- @return boolean is_success
+return function()
+ local condition = blackboard.condition
+ local bullet_ready = blackboard.rule.bullet_ready
+ assert(type(condition.bullet_ready) == "function", "blackboard.condition.bullet_ready should be a function")
+ assert(type(bullet_ready) == "number", "blackboard.rule.bullet_ready should be a number")
+
+ if condition.bullet_ready() then
+ action:info(string.format(
+ "supply-ammunition: 当前已达到补弹完成阈值 (bullet=%s, bullet_ready=%s)",
+ tostring(blackboard.user.bullet),
+ tostring(bullet_ready)
+ ))
+ return true
+ end
+
+ action:info(string.format(
+ "supply-ammunition: 开始等待补弹 (bullet=%s, bullet_ready=%s)",
+ tostring(blackboard.user.bullet),
+ tostring(bullet_ready)
+ ))
+
+ while not condition.bullet_ready() do
+ request:sleep(POLL_INTERVAL)
+ end
+
+ action:info(string.format(
+ "supply-ammunition: 弹量已达到补弹完成阈值,结束等待 (bullet=%s)",
+ tostring(blackboard.user.bullet)
+ ))
+ return true
+end
diff --git a/src/lua/task/supply/supply-health.lua b/src/lua/task/supply/supply-health.lua
new file mode 100644
index 0000000..d57eae5
--- /dev/null
+++ b/src/lua/task/supply/supply-health.lua
@@ -0,0 +1,39 @@
+local blackboard = require("blackboard").singleton()
+local request = require("util.scheduler").request
+local action = require("action")
+
+local POLL_INTERVAL = 0.2
+
+--- 在补血点等待,直到血量达到 ready 阈值。
+--- @return boolean is_success
+return function()
+ local condition = blackboard.condition
+ local health_ready = blackboard.rule.health_ready
+ assert(type(condition.health_ready) == "function", "blackboard.condition.health_ready should be a function")
+ assert(type(health_ready) == "number", "blackboard.rule.health_ready should be a number")
+
+ if condition.health_ready() then
+ action:info(string.format(
+ "supply-health: 当前已达到补血完成阈值 (health=%s, health_ready=%s)",
+ tostring(blackboard.user.health),
+ tostring(health_ready)
+ ))
+ return true
+ end
+
+ action:info(string.format(
+ "supply-health: 开始等待补血 (health=%s, health_ready=%s)",
+ tostring(blackboard.user.health),
+ tostring(health_ready)
+ ))
+
+ while not condition.health_ready() do
+ request:sleep(POLL_INTERVAL)
+ end
+
+ action:info(string.format(
+ "supply-health: 血量已达到补血完成阈值,结束等待 (health=%s)",
+ tostring(blackboard.user.health)
+ ))
+ return true
+end
diff --git a/src/lua/task/switch-mode.lua b/src/lua/task/switch-mode.lua
new file mode 100644
index 0000000..6324a88
--- /dev/null
+++ b/src/lua/task/switch-mode.lua
@@ -0,0 +1,9 @@
+local action = require("action")
+
+--- @param mode string
+--- @return boolean is_success
+return function(mode)
+ assert(type(mode) == "string", "mode should be a string")
+ action:update_chassis_mode(mode)
+ return true
+end
diff --git a/src/lua/train_map.lua b/src/lua/train_map.lua
new file mode 100644
index 0000000..bed8922
--- /dev/null
+++ b/src/lua/train_map.lua
@@ -0,0 +1,150 @@
+local Region = {
+ WALL = 0,
+ OURS_HOME = 1,
+ ROAD_REGION_BEGIN = 2,
+ ROAD_REGION_1 = 3,
+ ROAD_REGION_2 = 4,
+ ROAD_REGION_FINAL = 5,
+ OURS_HIGHLAND = 6,
+}
+
+local RegionName = {
+ [Region.WALL] = "wall",
+ [Region.OURS_HOME] = "ours_home",
+ [Region.ROAD_REGION_BEGIN] = "road_region_begin",
+ [Region.ROAD_REGION_1] = "road_region_1",
+ [Region.ROAD_REGION_2] = "road_region_2",
+ [Region.ROAD_REGION_FINAL] = "road_region_final",
+ [Region.OURS_HIGHLAND] = "ours_highland",
+}
+
+local Map = {}
+Map.__index = Map
+local DEFAULT_MAP_NAME = "train_map"
+
+local function dirname(path)
+ return path:match("^(.*)/[^/]*$") or "."
+end
+
+local function source_dir()
+ local source = debug.getinfo(1, "S").source
+ if source:sub(1, 1) == "@" then
+ return dirname(source:sub(2))
+ end
+ return "."
+end
+
+local function load_map_data(name)
+ local lua_dir = source_dir()
+ local candidates = {
+ lua_dir .. "/../maps/" .. name .. ".lua",
+ lua_dir .. "/../../maps/" .. name .. ".lua",
+ }
+ local errors = {}
+
+ for _, path in ipairs(candidates) do
+ local chunk, err = loadfile(path)
+ if chunk then
+ return chunk()
+ end
+ errors[#errors + 1] = path .. ": " .. tostring(err)
+ end
+
+ error("failed to load region map " .. name .. ":\n" .. table.concat(errors, "\n"))
+end
+
+local function is_finite_number(value)
+ return type(value) == "number" and value == value and value ~= math.huge and value ~= -math.huge
+end
+
+local function is_positive_integer(value)
+ return is_finite_number(value) and value > 0 and math.floor(value) == value
+end
+
+local function validate_data(data)
+ assert(type(data) == "table", "region map data should be a table")
+ assert(is_positive_integer(data.width), "region map data.width should be a positive integer")
+ assert(is_positive_integer(data.height), "region map data.height should be a positive integer")
+ assert(is_finite_number(data.resolution) and data.resolution > 0, "region map data.resolution should be positive")
+ assert(type(data.origin) == "table", "region map data.origin should be a table")
+ assert(is_finite_number(data.origin.x), "region map data.origin.x should be finite")
+ assert(is_finite_number(data.origin.y), "region map data.origin.y should be finite")
+ assert(type(data.rows) == "table", "region map data.rows should be a table")
+
+ for y = 1, data.height do
+ local row = data.rows[y]
+ assert(type(row) == "table", "region map row " .. y .. " should be a table")
+ for x = 1, data.width do
+ assert(type(row[x]) == "number", "region map cell " .. y .. "," .. x .. " should be a number")
+ end
+ end
+end
+
+local function new_map(data)
+ validate_data(data)
+
+ return setmetatable({
+ width = data.width,
+ height = data.height,
+ resolution = data.resolution,
+ origin = data.origin,
+ names = data.names or RegionName,
+ rows = data.rows,
+ }, Map)
+end
+
+local function load_map(name)
+ return new_map(load_map_data(name))
+end
+
+function Map:locate(position)
+ assert(type(position) == "table", "position should be a table")
+ assert(type(position.x) == "number", "position.x should be a number")
+ assert(type(position.y) == "number", "position.y should be a number")
+
+ if not is_finite_number(position.x) or not is_finite_number(position.y) then
+ return Region.WALL
+ end
+
+ local column = math.floor((position.x - self.origin.x) / self.resolution) + 1
+ local row = self.height - math.floor((position.y - self.origin.y) / self.resolution)
+
+ if column < 1 or column > self.width or row < 1 or row > self.height then
+ return Region.WALL
+ end
+
+ local map_row = self.rows[row]
+ if map_row == nil then
+ return Region.WALL
+ end
+
+ return map_row[column] or Region.WALL
+end
+
+local singleton
+local singleton_name
+
+function Map.singleton(name)
+ if name ~= nil then
+ assert(type(name) == "string", "map name should be a string")
+ if singleton == nil or singleton_name ~= name then
+ singleton = load_map(name)
+ singleton_name = name
+ end
+ return singleton
+ end
+
+ if singleton == nil then
+ return Map.singleton(DEFAULT_MAP_NAME)
+ end
+
+ return singleton
+end
+
+function Map.current_name()
+ return singleton_name or DEFAULT_MAP_NAME
+end
+
+Map.Region = Region
+
+return Map
diff --git a/src/lua/util/blackboard_logger.lua b/src/lua/util/blackboard_logger.lua
new file mode 100644
index 0000000..f75f265
--- /dev/null
+++ b/src/lua/util/blackboard_logger.lua
@@ -0,0 +1,90 @@
+local action = require("action")
+
+local BlackboardLogger = {}
+
+function BlackboardLogger.attach(scheduler, blackboard)
+ local request = require("util.scheduler").request
+
+ scheduler:append_task(function()
+ while true do
+ request:sleep(1.0)
+
+ local u = blackboard.user
+ local g = blackboard.game
+ local p = blackboard.play
+ local m = blackboard.meta
+ local r = blackboard.referee
+ local rhp = r.robots_hp
+
+ action:info(string.format(
+ "BB| user: hp=%d bullet=%d pwr_limit=%d pwr=%.0f buf=%.0f out=%s pos=(%.2f,%.2f) yaw=%.1f mode=%s cool=%d heat_lim=%d 42mm=%d 17mm=%d spd=%d shoot_ts=%.1f",
+ u.health,
+ u.bullet,
+ u.chassis_power_limit,
+ u.chassis_power,
+ u.chassis_buffer_energy,
+ tostring(u.chassis_output_status),
+ u.x, u.y,
+ u.yaw,
+ u.mode,
+ u.shooter_cooling,
+ u.shooter_heat_limit,
+ u.bullet_42mm,
+ u.fortress_17mm_bullet,
+ u.initial_speed,
+ u.shoot_timestamp
+ ))
+
+ action:info(string.format(
+ "BB| game: stage=%s outpost=%d base=%d hero=%d eng=%d inf1=%d inf2=%d time=%d gold=%d ammo=%d dart=%s fort=%s bigE=%s smlE=%s pos_h=(%.1f,%.1f) pos_e=(%.1f,%.1f) pos_i1=(%.1f,%.1f) pos_i2=(%.1f,%.1f)",
+ g.stage,
+ g.outpost_health,
+ g.base_health,
+ g.hero_health,
+ g.engineer_health,
+ g.infantry_1_health,
+ g.infantry_2_health,
+ g.remaining_time,
+ g.gold_coin,
+ g.exchangeable_ammunition_quantity,
+ tostring(g.our_dart_nmber_of_hits),
+ tostring(g.fortress_occupied),
+ tostring(g.big_energy_mechanism_activated),
+ tostring(g.small_energy_mechanism_activated),
+ g.hero_position.x, g.hero_position.y,
+ g.engineer_position.x, g.engineer_position.y,
+ g.infantry_1_position.x, g.infantry_1_position.y,
+ g.infantry_2_position.x, g.infantry_2_position.y
+ ))
+
+ action:info(string.format(
+ "BB| referee: sync_ts=%d rid=%d rhp=(1=%d 2=%d 3=%d 4=%d 7=%d res=%d outpost=%d base=%d) free_rv=%s inst_rv=%s rv_cost=%d ex_bullet=%d ex_count=%d s_mode=%d e_activ=%s red=%d blue=%d",
+ r.sync_timestamp,
+ r.robot_id,
+ rhp.ally_1, rhp.ally_2, rhp.ally_3, rhp.ally_4,
+ rhp.ally_7, rhp.reserved,
+ rhp.outpost, rhp.base,
+ tostring(r.can_confirm_free_revive),
+ tostring(r.can_exchange_instant_revive),
+ r.instant_revive_cost,
+ r.exchanged_bullet,
+ r.remote_bullet_exchange_count,
+ r.sentry_mode,
+ tostring(r.energy_mechanism_activatable),
+ r.red_score,
+ r.blue_score
+ ))
+
+ action:info(string.format(
+ "BB| play: rs=%s ls=%s | meta: ts=%.1f fsm=%s ret=%s",
+ p.rswitch,
+ p.lswitch,
+ m.timestamp,
+ m.fsm_state,
+ m.fsm_return_stage
+ ))
+ end
+ end)
+end
+
+return BlackboardLogger
diff --git a/src/lua/util/native.lua b/src/lua/util/native.lua
index e132a86..a7798fa 100644
--- a/src/lua/util/native.lua
+++ b/src/lua/util/native.lua
@@ -2,7 +2,7 @@ local M = {}
---@param path string
---@return boolean
-function M.file_exists(path)
+function M.exist_filename(path)
local file = io.open(path, "r")
if file ~= nil then
file:close()
@@ -12,7 +12,7 @@ function M.file_exists(path)
end
---@return string|nil, string|nil
-function M.find_env_setup_bash()
+function M.search_setup_resource()
local home = os.getenv("HOME") or ""
local candidate_paths = {
home ~= "" and (home .. "/env_setup.bash") or nil,
@@ -20,7 +20,7 @@ function M.find_env_setup_bash()
}
for _, path in ipairs(candidate_paths) do
- if path ~= nil and M.file_exists(path) then
+ if path ~= nil and M.exist_filename(path) then
return path, nil
end
end
@@ -30,7 +30,7 @@ end
---@param command string
---@return boolean, string
-function M.run_command(command)
+function M.run(command)
local escaped_command = command:gsub("'", [['"'"']])
local success, reason, code = os.execute("bash -lc '" .. escaped_command .. "'")
if success == true or success == 0 then
@@ -41,9 +41,4 @@ function M.run_command(command)
return false, message
end
----@return string|nil, string|nil
-function M.search_setup_filename()
- return M.find_env_setup_bash()
-end
-
return M
diff --git a/src/lua/util/return-stage.lua b/src/lua/util/return-stage.lua
new file mode 100644
index 0000000..2c4f285
--- /dev/null
+++ b/src/lua/util/return-stage.lua
@@ -0,0 +1,21 @@
+local ReturnStage = {
+ before_fluctuant = "before_fluctuant",
+ on_fluctuant = "on_fluctuant",
+ after_fluctuant = "after_fluctuant",
+}
+
+function ReturnStage.resolve_escape_route(stage)
+ if stage == ReturnStage.before_fluctuant then
+ return "direct"
+ end
+ if stage == ReturnStage.on_fluctuant then
+ return "fluctuant_road"
+ end
+ if stage == ReturnStage.after_fluctuant then
+ return "onestep"
+ end
+
+ error("unknown return stage: " .. tostring(stage))
+end
+
+return ReturnStage