diff --git a/control/precision_landing.py b/control/precision_landing.py new file mode 100644 index 0000000..9bded13 --- /dev/null +++ b/control/precision_landing.py @@ -0,0 +1,37 @@ +import rospy +from geometry_msgs.msg import Twist, PoseStamped, TransformStamped +from tf2_ros import TransformListener, Buffer +import sys + +def local_pose_callback(data): + global local_pose + local_pose = data + +if __name__ == '__main__': + vehicle_type = sys.argv[1] + vehicle_id = sys.argv[2] + rospy.init_node(vehicle_type+'_'+vehicle_id+'_precision_landing') + tfBuffer = Buffer() + tflistener = TransformListener(tfBuffer) + cmd_vel_enu = Twist() + local_pose = PoseStamped() + Kp = 1.0 + land_vel = 0.5 + rospy.Subscriber(vehicle_type+'_'+vehicle_id+"/mavros/local_position/pose", PoseStamped, local_pose_callback) + cmd_vel_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd_vel_enu', Twist, queue_size=2) + rate = rospy.Rate(50) + while not rospy.is_shutdown(): + try: + tfstamped = tfBuffer.lookup_transform('tag_'+vehicle_id, 'map', rospy.Time(0)) + except: + cmd_vel_enu.linear.z = 0.0 + continue + # print('tf:',tfstamped.transform.translation.x) + # print(local_pose.pose.position.x) + cmd_vel_enu.linear.x = Kp * (tfstamped.transform.translation.x - local_pose.pose.position.x) + cmd_vel_enu.linear.y = Kp * (tfstamped.transform.translation.y - local_pose.pose.position.y) + cmd_vel_enu.linear.z = - land_vel + # print(cmd_vel_enu) + cmd_vel_pub.publish(cmd_vel_enu) + rate.sleep() + diff --git a/control/yolo_human_tracking.py b/control/yolo_human_tracking.py index 91fba66..d513cf3 100644 --- a/control/yolo_human_tracking.py +++ b/control/yolo_human_tracking.py @@ -65,12 +65,12 @@ if __name__ == "__main__": rospy.Subscriber("/uav_"+vehicle_id+"/darknet_ros/bounding_boxes", BoundingBoxes, darknet_callback) rospy.Subscriber(vehicle_type+'_'+vehicle_id+"/mavros/local_position/pose", PoseStamped, local_pose_callback) rospy.Subscriber('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cam_pose', PoseStamped, cam_pose_callback) - vel_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd_vel_flu', Twist, queue_size=2) + cmd_vel_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd_vel_flu', Twist, queue_size=2) cmd_pub = rospy.Publisher('/xtdrone/'+vehicle_type+'_'+vehicle_id+'/cmd', String, queue_size=2) rate = rospy.Rate(60) - while(True): + while not rospy.is_shutdown(): rate.sleep() - vel_pub.publish(twist) + cmd_vel_pub.publish(twist) cmd_pub.publish(cmd) if find_cnt - find_cnt_last == 0: if not get_time: diff --git a/sensing/object_detection_and_tracking/apriltag/config/rviz.rviz b/sensing/object_detection_and_tracking/apriltag/config/rviz.rviz new file mode 100644 index 0000000..aebb8d8 --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/config/rviz.rviz @@ -0,0 +1,207 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + Splitter Ratio: 0.5 + Tree Height: 355 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.5886790156364441 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Preferences: + PromptSaveOnExit: true +Toolbars: + toolButtonStyle: 2 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Class: rviz/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base_link: + Value: true + base_link_frd: + Value: true + camera_link: + Value: true + map: + Value: true + map_ned: + Value: true + my_bundle: + Value: true + odom: + Value: true + odom_ned: + Value: true + tag_0: + Value: true + tag_1: + Value: true + tag_2: + Value: true + ugv_0/back_left_wheel_link: + Value: true + ugv_0/back_right_wheel_link: + Value: true + ugv_0/base_link: + Value: true + ugv_0/camera_left_link: + Value: true + ugv_0/camera_right_link: + Value: true + ugv_0/front_laser_link: + Value: true + ugv_0/front_left_steering_link: + Value: true + ugv_0/front_left_wheel_link: + Value: true + ugv_0/front_right_steering_link: + Value: true + ugv_0/front_right_wheel_link: + Value: true + ugv_0/main_mass: + Value: true + ugv_0/odom: + Value: true + ugv_0/slamodom: + Value: true + ugv_0/triclops_link: + Value: true + ugv_0/velodyne_link: + Value: true + world: + Value: true + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: true + Tree: + map: + base_link: + base_link_frd: + {} + map_ned: + {} + Update Interval: 0 + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /tag_detections_image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Unreliable: false + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Default Light: true + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + - Class: rviz/FocusCamera + - Class: rviz/Measure + - Class: rviz/SetInitialPose + Theta std deviation: 0.2617993950843811 + Topic: /initialpose + X std deviation: 0.5 + Y std deviation: 0.5 + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Class: rviz/Orbit + Distance: 13.4510498046875 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.785398006439209 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398006439209 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 846 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000009fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000001ee000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261fb0000000a0049006d0061006700650100000231000000bc0000001600ffffff000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000002eb00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1200 + X: 437 + Y: 160 diff --git a/sensing/object_detection_and_tracking/apriltag/image/apriltag0-2.png b/sensing/object_detection_and_tracking/apriltag/image/apriltag0-2.png new file mode 100644 index 0000000..5342608 Binary files /dev/null and b/sensing/object_detection_and_tracking/apriltag/image/apriltag0-2.png differ diff --git a/sensing/object_detection_and_tracking/apriltag/image/target.pdf b/sensing/object_detection_and_tracking/apriltag/image/target.pdf new file mode 100644 index 0000000..918ccad Binary files /dev/null and b/sensing/object_detection_and_tracking/apriltag/image/target.pdf differ diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/materials/textures/Marker0.png b/sensing/object_detection_and_tracking/apriltag/model/marker0/materials/textures/Marker0.png new file mode 100755 index 0000000..686090d Binary files /dev/null and b/sensing/object_detection_and_tracking/apriltag/model/marker0/materials/textures/Marker0.png differ diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/meshes/Marker0.dae b/sensing/object_detection_and_tracking/apriltag/model/marker0/meshes/Marker0.dae new file mode 100644 index 0000000..9d7ea43 --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/model/marker0/meshes/Marker0.dae @@ -0,0 +1,126 @@ + + + + + Blender User + Blender 2.74.0 commit date:2015-03-31, commit time:13:39, hash:000dfc0 + + 2015-04-05T02:03:25 + 2015-04-05T02:03:25 + + Z_UP + + + + Marker0.png + + + + + + + + Marker0_png + + + + + Marker0_png-surface + + + + + + 0 0 0 1 + + + 0.9 0.9 0.9 1 + + + + + + 0.5 0.5 0.5 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 1 0.9999999 -9.41753e-6 1 -1 -9.41753e-6 -1 -0.9999998 -9.41753e-6 -0.9999997 1 -9.41753e-6 1 0.9999994 1.999991 0.9999994 -1.000001 1.999991 -1 -0.9999997 1.999991 -0.9999999 1 1.999991 + + + + + + + + + + 0 0 -1 0 0 1 1 -5.66244e-7 3.27825e-7 -4.76837e-7 -1 0 -1 2.38419e-7 -1.19209e-7 2.38419e-7 1 1.78814e-7 0 0 -1 0 0 1 1 0 -2.38419e-7 0 -1 -2.98023e-7 -1 2.38419e-7 0 2.98023e-7 1 2.38418e-7 + + + + + + + + + + 0 0 0 0 0 0 0 0 0 0 0 0 0.9999 0.9940189 9.96856e-5 0.9940189 1.00079e-4 9.97642e-5 0 0 0 0 0 0 9.96856e-5 0.9940191 9.98823e-5 9.96856e-5 0.9999004 9.98429e-5 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0.9999004 9.96856e-5 0.9999 0.9940189 1.00079e-4 9.97642e-5 0 0 0 0 0 0 0.9999004 0.9940191 9.96856e-5 0.9940191 0.9999004 9.98429e-5 0 0 0 0 0 0 + + + + + + + + + + + + + + + 3 3 3 3 3 3 3 3 3 3 3 3 +

0 0 0 1 0 1 2 0 2 7 1 3 6 1 4 5 1 5 4 2 6 5 2 7 1 2 8 5 3 9 6 3 10 2 3 11 2 4 12 6 4 13 7 4 14 0 5 15 3 5 16 7 5 17 3 6 18 0 6 19 2 6 20 4 7 21 7 7 22 5 7 23 0 8 24 4 8 25 1 8 26 1 9 27 5 9 28 2 9 29 3 10 30 2 10 31 7 10 32 4 11 33 0 11 34 7 11 35

+
+
+
+
+ + + + + 0.004999998 0 0 0 0 0.2499999 0 0 0 0 0.25 0 0 0 0 1 + + + + + + + + + + + + + + + +
diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_4.sdf b/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_4.sdf new file mode 100755 index 0000000..43a6f7d --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_4.sdf @@ -0,0 +1,15 @@ + + + + true + + + + + model://marker0/meshes/Marker0.dae + + + + + + diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_5.sdf b/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_5.sdf new file mode 100755 index 0000000..43a6f7d --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/model/marker0/model-1_5.sdf @@ -0,0 +1,15 @@ + + + + true + + + + + model://marker0/meshes/Marker0.dae + + + + + + diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/model.config b/sensing/object_detection_and_tracking/apriltag/model/marker0/model.config new file mode 100755 index 0000000..ba97dab --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/model/marker0/model.config @@ -0,0 +1,19 @@ + + + + Marker0 + 1.0 + model.sdf + model-1_5.sdf + model-1_4.sdf + + + Mikael Arguedas + mikael.arguedas@gmail.com + + + + A model of AR marker + + + diff --git a/sensing/object_detection_and_tracking/apriltag/model/marker0/model.sdf b/sensing/object_detection_and_tracking/apriltag/model/marker0/model.sdf new file mode 100755 index 0000000..6566090 --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/model/marker0/model.sdf @@ -0,0 +1,15 @@ + + + + true + + + + + model://marker0/meshes/Marker0.dae + + + + + + diff --git a/sensing/object_detection_and_tracking/apriltag/script/make_gazebo_model.py b/sensing/object_detection_and_tracking/apriltag/script/make_gazebo_model.py new file mode 100755 index 0000000..b0339f8 --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/script/make_gazebo_model.py @@ -0,0 +1,227 @@ +#! /usr/bin/env python +# Thanks for https://github.com/mikaelarguedas/gazebo_models +from __future__ import print_function + +import argparse +from xml.dom.minidom import parse +import os +import sys + +parser = argparse.ArgumentParser( + usage='generate gazebo models for AR tags', + formatter_class=argparse.ArgumentDefaultsHelpFormatter +) +parser.add_argument( + '-i', '--images-dir', + default="$HOME/gazebo_models/ar_tags/images", + help='directory where the marker images are located') +parser.add_argument( + '-g', '--gazebodir', + default="$HOME/.gazebo/models", + help='Gazebo models directory') +parser.add_argument( + '-s', '--size', + default=500, type=int, + help='marker size in mm') +parser.add_argument( + '-v', '--verbose', + dest='verbose', action='store_true', + help='verbose mode') + +parser.add_argument( + '-w', '--white-contour-size-mm', + default=0, type=int, + help='Add white contour around images, default to no contour') +parser.set_defaults(verbose=False) + +args = parser.parse_args() + +args.gazebodir = os.path.expandvars(args.gazebodir) +args.images_dir = os.path.expandvars(args.images_dir) +script_path = os.path.dirname(os.path.realpath(__file__)) +model_dir = os.path.join(os.path.dirname(script_path), 'model') +ORIGINAL_MARKER_SIZE_MM = 500 +ORIGINAL_IMAGE_SIZE_PX = 170 +white_contour_px = \ + args.white_contour_size_mm * ORIGINAL_IMAGE_SIZE_PX / args.size + +if not os.path.isdir(args.images_dir): + print("provided image directory '%s' is not a directory" % args.images_dir) + sys.exit() + +# Open every collada file +if args.verbose: + print(args.images_dir) + +# Copy marker0 directory into gazebo model directory +cp_marker0_cmd = "cp -r " + os.path.join(model_dir, 'marker0') + \ + " " + os.path.join(args.gazebodir, "marker0") +if args.verbose: + print(cp_marker0_cmd) +os.system(cp_marker0_cmd) + +file_list = sorted(os.listdir(args.images_dir)) +for image_file in file_list: + if not image_file.endswith('.png'): + continue + image_file_path = os.path.join(args.images_dir, image_file) + filename_without_ext = image_file[0:image_file.rfind('.')] + # ignore marker0 as it has already been copied above + if not filename_without_ext.lower() == 'marker0': + cmd = "cp -r " + os.path.join(args.gazebodir, "marker0") + \ + " " + os.path.join(args.gazebodir, filename_without_ext.lower()) + if args.verbose: + print(cmd) + os.system(cmd) + + cmd = "rm " + os.path.join( + args.gazebodir, filename_without_ext.lower(), + "materials", "textures", "Marker0.png") + if args.verbose: + print(cmd) + os.system(cmd) + image_dest_path = os.path.join( + args.gazebodir, + filename_without_ext.lower(), + "materials", "textures", image_file) + cmd = "cp " + image_file_path + " " + \ + image_dest_path + if args.verbose: + print(cmd) + os.system(cmd) + + # add white contour if applicable: + if white_contour_px > 0: + convert_cmd = "convert %s -bordercolor white -border %dx%d %s" % ( + image_dest_path, white_contour_px, + white_contour_px, image_dest_path) + if args.verbose: + print(convert_cmd) + os.system(convert_cmd) + + model_config_path = os.path.join( + args.gazebodir, filename_without_ext.lower(), "model.config") + if args.verbose: + print(model_config_path) + dom = parse(model_config_path) + # modify model.config + for node in dom.getElementsByTagName('name'): + node.firstChild.nodeValue = filename_without_ext + if args.verbose: + print(node.firstChild.nodeValue) + break + f = open(os.path.join( + args.gazebodir, filename_without_ext.lower(), "model.config"), 'w+') + # Write the modified xml file + f.write(dom.toxml()) + f.close() + + # modify model.sdf + model_noversion_sdf_path = os.path.join( + args.gazebodir, filename_without_ext.lower(), "model.sdf") + if args.verbose: + print("open model.sdf") + print(model_noversion_sdf_path) + dom = parse(model_noversion_sdf_path) + for node in dom.getElementsByTagName('model'): + node.attributes["name"].value = filename_without_ext + if args.verbose: + print("model tag found") + break + + scaleModified = False + scale = (args.size + 2 * args.white_contour_size_mm) / \ + float(ORIGINAL_MARKER_SIZE_MM) + for node in dom.getElementsByTagName('mesh'): + for child in node.childNodes: + if child.nodeName == "scale": + child.firstChild.nodeValue = \ + "{} {} {}".format(scale, scale, scale) + scaleModified = True + if child.nodeName == "uri": + child.firstChild.nodeValue = "model://" + os.path.join( + filename_without_ext.lower(), "meshes", + filename_without_ext + ".dae") + if args.verbose: + print("uri tag found") + print(node.firstChild.nodeValue) + if not scaleModified: + if args.verbose: + print("creating scale tag") + x = dom.createElement("scale") + y = dom.createTextNode("{} {} {}".format(scale, scale, scale)) + x.appendChild(y) + node.appendChild(x) + + f = open(model_noversion_sdf_path, 'w+') + # Write the modified xml file + f.write(dom.toxml()) + f.close() + + # modify model-1_4.sdf + model_sdf_path = os.path.join( + args.gazebodir, filename_without_ext.lower(), "model-1_4.sdf") + cmd = "cp " + model_noversion_sdf_path + " " + model_sdf_path + if args.verbose: + print(cmd) + os.system(cmd) + + if args.verbose: + print("open model-1_4.sdf") + print(model_sdf_path) + dom = parse(model_sdf_path) + for node in dom.getElementsByTagName('sdf'): + node.attributes["version"].value = "1.4" + break + f = open(model_sdf_path, 'w+') + # Write the modified xml file + f.write(dom.toxml()) + f.close() + + # modify model-1_5.sdf + model_sdf_path = os.path.join( + args.gazebodir, filename_without_ext.lower(), "model-1_5.sdf") + cmd = "cp " + model_noversion_sdf_path + \ + " " + model_sdf_path + if args.verbose: + print(cmd) + os.system(cmd) + + if args.verbose: + print("open model-1_5.sdf") + print(model_sdf_path) + dom = parse(model_sdf_path) + for node in dom.getElementsByTagName('sdf'): + node.attributes["version"].value = "1.5" + break + f = open(model_sdf_path, 'w+') + # Write the modified xml file + f.write(dom.toxml()) + f.close() + + meshes_dir = os.path.join( + args.gazebodir, filename_without_ext.lower(), "meshes") + if args.verbose: + print(os.path.join(meshes_dir, "Marker0.dae") + + " newname " + os.path.join( + meshes_dir, filename_without_ext + ".dae")) + os.rename( + os.path.join(meshes_dir, "Marker0.dae"), + os.path.join(meshes_dir, filename_without_ext + ".dae")) + + # modify ModelX.dae + if args.verbose: + print("open ModelX.dae") + print(os.path.join(meshes_dir, filename_without_ext + ".dae")) + dom = parse(os.path.join(meshes_dir, filename_without_ext + ".dae")) + for node in dom.getElementsByTagName('init_from'): + node.firstChild.nodeValue = image_file + if args.verbose: + print("init_from tag found") + break + + f = open(os.path.join( + meshes_dir, filename_without_ext + ".dae"), 'w+') + # Write the modified xml file + f.write(dom.toxml()) + f.close() \ No newline at end of file diff --git a/sensing/object_detection_and_tracking/apriltag/script/make_tag.py b/sensing/object_detection_and_tracking/apriltag/script/make_tag.py new file mode 100644 index 0000000..9eee595 --- /dev/null +++ b/sensing/object_detection_and_tracking/apriltag/script/make_tag.py @@ -0,0 +1,186 @@ +#!/usr/bin/python +# Thomas Schneider, Sept 2013 +# Codes from AprilTags C++ Library (http://people.csail.mit.edu/kaess/apriltags/) + +from pyx import * +import argparse +import sys +import importlib + +import math +import numpy as np + +class AprilTagCodes: + t16h5=[0x231b, 0x2ea5, 0x346a, 0x45b9, 0x79a6, 0x7f6b, 0xb358, 0xe745, 0xfe59, 0x156d, 0x380b, 0xf0ab, 0x0d84, 0x4736, 0x8c72, 0xaf10, 0x093c, 0x93b4, 0xa503, 0x468f, 0xe137, 0x5795, 0xdf42, 0x1c1d, 0xe9dc, 0x73ad, 0xad5f, 0xd530, 0x07ca, 0xaf2e] + t25h7=[0x4b770d, 0x11693e6, 0x1a599ab, 0xc3a535, 0x152aafa, 0xaccd98, 0x1cad922, 0x2c2fad, 0xbb3572, 0x14a3b37, 0x186524b, 0xc99d4c, 0x23bfea, 0x141cb74, 0x1d0d139, 0x1670aeb, 0x851675, 0x150334e, 0x6e3ed8, 0xfd449d, 0xaa55ec, 0x1c86176, 0x15e9b28, 0x7ca6b2, 0x147c38b, 0x1d6c950, 0x8b0e8c, 0x11a1451, 0x1562b65, 0x13f53c8, 0xd58d7a, 0x829ec9, 0xfaccf1, 0x136e405, 0x7a2f06, 0x10934cb, 0x16a8b56, 0x1a6a26a, 0xf85545, 0x195c2e4, 0x24c8a9, 0x12bfc96, 0x16813aa, 0x1a42abe, 0x1573424, 0x1044573, 0xb156c2, 0x5e6811, 0x1659bfe, 0x1d55a63, 0x5bf065, 0xe28667, 0x1e9ba54, 0x17d7c5a, 0x1f5aa82, 0x1a2bbd1, 0x1ae9f9, 0x1259e51, 0x134062b, 0xe1177a, 0xed07a8, 0x162be24, 0x59128b, 0x1663e8f, 0x1a83cb, 0x45bb59, 0x189065a, 0x4bb370, 0x16fb711, 0x122c077, 0xeca17a, 0xdbc1f4, 0x88d343, 0x58ac5d, 0xba02e8, 0x1a1d9d, 0x1c72eec, 0x924bc5, 0xdccab3, 0x886d15, 0x178c965, 0x5bc69a, 0x1716261, 0x174e2cc, 0x1ed10f4, 0x156aa8, 0x3e2a8a, 0x2752ed, 0x153c651, 0x1741670, 0x765b05, 0x119c0bb, 0x172a783, 0x4faca1, 0xf31257, 0x12441fc, 0x0d3748, 0xc21f15, 0xac5037, 0x180e592, 0x7d3210, 0xa27187, 0x2beeaf, 0x26ff57, 0x690e82, 0x77765c, 0x1a9e1d7, 0x140be1a, 0x1aa1e3a, 0x1944f5c, 0x19b5032, 0x169897, 0x1068eb9, 0xf30dbc, 0x106a151, 0x1d53e95, 0x1348cee, 0xcf4fca, 0x1728bb5, 0xdc1eec, 0x69e8db, 0x16e1523, 0x105fa25, 0x18abb0c, 0xc4275d, 0x6d8e76, 0xe8d6db, 0xe16fd7, 0x1ac2682, 0x77435b, 0xa359dd, 0x3a9c4e, 0x123919a, 0x1e25817, 0x02a836, 0x1545a4, 0x1209c8d, 0xbb5f69, 0x1dc1f02, 0x5d5f7e, 0x12d0581, 0x13786c2, 0xe15409, 0x1aa3599, 0x139aad8, 0xb09d2a, 0x54488f, 0x13c351c, 0x976079, 0xb25b12, 0x1addb34, 0x1cb23ae, 0x1175738, 0x1303bb8, 0xd47716, 0x188ceea, 0xbaf967, 0x1226d39, 0x135e99b, 0x34adc5, 0x2e384d, 0x90d3fa, 0x232713, 0x17d49b1, 0xaa84d6, 0xc2ddf8, 0x1665646, 0x4f345f, 0x2276b1, 0x1255dd7, 0x16f4ccc, 0x4aaffc, 0xc46da6, 0x85c7b3, 0x1311fcb, 0x9c6c4f, 0x187d947, 0x8578e4, 0xe2bf0b, 0xa01b4c, 0xa1493b, 0x7ad766, 0xccfe82, 0x1981b5b, 0x1cacc85, 0x562cdb, 0x15b0e78, 0x8f66c5, 0x3332bf, 0x12ce754, 0x096a76, 0x1d5e3ba, 0x27ea41, 0x14412df, 0x67b9b4, 0xdaa51a, 0x1dcb17, 0x4d4afd, 0x6335d5, 0xee2334, 0x17d4e55, 0x1b8b0f0, 0x14999e3, 0x1513dfa, 0x765cf2, 0x56af90, 0x12e16ac, 0x1d3d86c, 0xff279b, 0x18822dd, 0x99d478, 0x8dc0d2, 0x34b666, 0xcf9526, 0x186443d, 0x7a8e29, 0x19c6aa5, 0x1f2a27d, 0x12b2136, 0xd0cd0d, 0x12cb320, 0x17ddb0b, 0x05353b, 0x15b2caf, 0x1e5a507, 0x120f1e5, 0x114605a, 0x14efe4c, 0x568134, 0x11b9f92, 0x174d2a7, 0x692b1d, 0x39e4fe, 0xaaff3d, 0x96224c, 0x13c9f77, 0x110ee8f, 0xf17bea, 0x99fb5d, 0x337141, 0x02b54d, 0x1233a70] + t25h9=[0x155cbf1, 0x1e4d1b6, 0x17b0b68, 0x1eac9cd, 0x12e14ce, 0x3548bb, 0x7757e6, 0x1065dab, 0x1baa2e7, 0xdea688, 0x81d927, 0x51b241, 0xdbc8ae, 0x1e50e19, 0x15819d2, 0x16d8282, 0x163e035, 0x9d9b81, 0x173eec4, 0xae3a09, 0x5f7c51, 0x1a137fc, 0xdc9562, 0x1802e45, 0x1c3542c, 0x870fa4, 0x914709, 0x16684f0, 0xc8f2a5, 0x833ebb, 0x59717f, 0x13cd050, 0xfa0ad1, 0x1b763b0, 0xb991ce] + t36h11=[0xd5d628584, 0xd97f18b49, 0xdd280910e, 0xe479e9c98, 0xebcbca822, 0xf31dab3ac, 0x056a5d085, 0x10652e1d4, 0x22b1dfead, 0x265ad0472, 0x34fe91b86, 0x3ff962cd5, 0x43a25329a, 0x474b4385f, 0x4e9d243e9, 0x5246149ae, 0x5997f5538, 0x683bb6c4c, 0x6be4a7211, 0x7e3158eea, 0x81da494af, 0x858339a74, 0x8cd51a5fe, 0x9f21cc2d7, 0xa2cabc89c, 0xadc58d9eb, 0xb16e7dfb0, 0xb8c05eb3a, 0xd25ef139d, 0xd607e1962, 0xe4aba3076, 0x2dde6a3da, 0x43d40c678, 0x5620be351, 0x64c47fa65, 0x686d7002a, 0x6c16605ef, 0x6fbf50bb4, 0x8d06d39dc, 0x9f53856b5, 0xadf746dc9, 0xbc9b084dd, 0xd290aa77b, 0xd9e28b305, 0xe4dd5c454, 0xfad2fe6f2, 0x181a8151a, 0x26be42c2e, 0x2e10237b8, 0x405cd5491, 0x7742eab1c, 0x85e6ac230, 0x8d388cdba, 0x9f853ea93, 0xc41ea2445, 0xcf1973594, 0x14a34a333, 0x31eacd15b, 0x6c79d2dab, 0x73cbb3935, 0x89c155bd3, 0x8d6a46198, 0x91133675d, 0xa708d89fb, 0xae5ab9585, 0xb9558a6d4, 0xb98743ab2, 0xd6cec68da, 0x1506bcaef, 0x4becd217a, 0x4f95c273f, 0x658b649dd, 0xa76c4b1b7, 0xecf621f56, 0x1c8a56a57, 0x3628e92ba, 0x53706c0e2, 0x5e6b3d231, 0x7809cfa94, 0xe97eead6f, 0x5af40604a, 0x7492988ad, 0xed5994712, 0x5eceaf9ed, 0x7c1632815, 0xc1a0095b4, 0xe9e25d52b, 0x3a6705419, 0xa8333012f, 0x4ce5704d0, 0x508e60a95, 0x877476120, 0xa864e950d, 0xea45cfce7, 0x19da047e8, 0x24d4d5937, 0x6e079cc9b, 0x99f2e11d7, 0x33aa50429, 0x499ff26c7, 0x50f1d3251, 0x66e7754ef, 0x96ad633ce, 0x9a5653993, 0xaca30566c, 0xc298a790a, 0x8be44b65d, 0xdc68f354b, 0x16f7f919b, 0x4dde0e826, 0xd548cbd9f, 0xe0439ceee, 0xfd8b1fd16, 0x76521bb7b, 0xd92375742, 0xcab16d40c, 0x730c9dd72, 0xad9ba39c2, 0xb14493f87, 0x52b15651f, 0x185409cad, 0x77ae2c68d, 0x94f5af4b5, 0x0a13bad55, 0x61ea437cd, 0xa022399e2, 0x203b163d1, 0x7bba8f40e, 0x95bc9442d, 0x41c0b5358, 0x8e9c6cc81, 0x0eb549670, 0x9da3a0b51, 0xd832a67a1, 0xdcd4350bc, 0x4aa05fdd2, 0x60c7bb44e, 0x4b358b96c, 0x067299b45, 0xb9c89b5fa, 0x6975acaea, 0x62b8f7afa, 0x33567c3d7, 0xbac139950, 0xa5927c62a, 0x5c916e6a4, 0x260ecb7d5, 0x29b7bbd9a, 0x903205f26, 0xae72270a4, 0x3d2ec51a7, 0x82ea55324, 0x11a6f3427, 0x1ca1c4576, 0xa40c81aef, 0xbddccd730, 0x0e617561e, 0x969317b0f, 0x67f781364, 0x610912f96, 0xb2549fdfc, 0x06e5aaa6b, 0xb6c475339, 0xc56836a4d, 0x844e351eb, 0x4647f83b4, 0x0908a04f5, 0x7f51034c9, 0xaee537fca, 0x5e92494ba, 0xd445808f4, 0x28d68b563, 0x04d25374b, 0x2bc065f65, 0x96dc3ea0c, 0x4b2ade817, 0x07c3fd502, 0xe768b5caf, 0x17605cf6c, 0x182741ee4, 0x62846097c, 0x72b5ebf80, 0x263da6e13, 0xfa841bcb5, 0x7e45e8c69, 0x653c81fa0, 0x7443b5e70, 0x0a5234afd, 0x74756f24e, 0x157ebf02a, 0x82ef46939, 0x80d420264, 0x2aeed3e98, 0xb0a1dd4f8, 0xb5436be13, 0x7b7b4b13b, 0x1ce80d6d3, 0x16c08427d, 0xee54462dd, 0x1f7644cce, 0x9c7b5cc92, 0xe369138f8, 0x5d5a66e91, 0x485d62f49, 0xe6e819e94, 0xb1f340eb5, 0x09d198ce2, 0xd60717437, 0x0196b856c, 0xf0a6173a5, 0x12c0e1ec6, 0x62b82d5cf, 0xad154c067, 0xce3778832, 0x6b0a7b864, 0x4c7686694, 0x5058ff3ec, 0xd5e21ea23, 0x9ff4a76ee, 0x9dd981019, 0x1bad4d30a, 0xc601896d1, 0x973439b48, 0x1ce7431a8, 0x57a8021d6, 0xf9dba96e6, 0x83a2e4e7c, 0x8ea585380, 0xaf6c0e744, 0x875b73bab, 0xda34ca901, 0x2ab9727ef, 0xd39f21b9a, 0x8a10b742f, 0x5f8952dba, 0xf8da71ab0, 0xc25f9df96, 0x06f8a5d94, 0xe42e63e1a, 0xb78409d1b, 0x792229add, 0x5acf8c455, 0x2fc29a9b0, 0xea486237b, 0xb0c9685a0, 0x1ad748a47, 0x03b4712d5, 0xf29216d30, 0x8dad65e49, 0x0a2cf09dd, 0x0b5f174c6, 0xe54f57743, 0xb9cf54d78, 0x4a312a88a, 0x27babc962, 0xb86897111, 0xf2ff6c116, 0x82274bd8a, 0x97023505e, 0x52d46edd1, 0x585c1f538, 0xbddd00e43, 0x5590b74df, 0x729404a1f, 0x65320855e, 0xd3d4b6956, 0x7ae374f14, 0x2d7a60e06, 0x315cd9b5e, 0xfd36b4eac, 0xf1df7642b, 0x55db27726, 0x8f15ebc19, 0x992f8c531, 0x62dea2a40, 0x928275cab, 0x69c263cb9, 0xa774cca9e, 0x266b2110e, 0x1b14acbb8, 0x624b8a71b, 0x1c539406b, 0x3086d529b, 0x0111dd66e, 0x98cd630bf, 0x8b9d1ffdc, 0x72b2f61e7, 0x9ed9d672b, 0x96cdd15f3, 0x6366c2504, 0x6ca9df73a, 0xa066d60f0, 0xe7a4b8add, 0x8264647ef, 0xaa195bf81, 0x9a3db8244, 0x014d2df6a, 0x0b63265b7, 0x2f010de73, 0x97e774986, 0x248affc29, 0xfb57dcd11, 0x0b1a7e4d9, 0x4bfa2d07d, 0x54e5cdf96, 0x4c15c1c86, 0xcd9c61166, 0x499380b2a, 0x540308d09, 0x8b63fe66f, 0xc81aeb35e, 0x86fe0bd5c, 0xce2480c2a, 0x1ab29ee60, 0x8048daa15, 0xdbfeb2d39, 0x567c9858c, 0x2b6edc5bc, 0x2078fca82, 0xadacc22aa, 0xb92486f49, 0x51fac5964, 0x691ee6420, 0xf63b3e129, 0x39be7e572, 0xda2ce6c74, 0x20cf17a5c, 0xee55f9b6e, 0xfb8572726, 0xb2c2de548, 0xcaa9bce92, 0xae9182db3, 0x74b6e5bd1, 0x137b252af, 0x51f686881, 0xd672f6c02, 0x654146ce4, 0xf944bc825, 0xe8327f809, 0x76a73fd59, 0xf79da4cb4, 0x956f8099b, 0x7b5f2655c, 0xd06b114a6, 0xd0697ca50, 0x27c390797, 0xbc61ed9b2, 0xcc12dd19b, 0xeb7818d2c, 0x092fcecda, 0x89ded4ea1, 0x256a0ba34, 0xb6948e627, 0x1ef6b1054, 0x8639294a2, 0xeda3780a4, 0x39ee2af1d, 0xcd257edc5, 0x2d9d6bc22, 0x121d3b47d, 0x37e23f8ad, 0x119f31cf6, 0x2c97f4f09, 0xd502abfe0, 0x10bc3ca77, 0x53d7190ef, 0x90c3e62a6, 0x7e9ebf675, 0x979ce23d1, 0x27f0c98e9, 0xeafb4ae59, 0x7ca7fe2bd, 0x1490ca8f6, 0x9123387ba, 0xb3bc73888, 0x3ea87e325, 0x4888964aa, 0xa0188a6b9, 0xcd383c666, 0x40029a3fd, 0xe1c00ac5c, 0x39e6f2b6e, 0xde664f622, 0xe979a75e8, 0x7c6b4c86c, 0xfd492e071, 0x8fbb35118, 0x40b4a09b7, 0xaf80bd6da, 0x70e0b2521, 0x2f5c54d93, 0x3f4a118d5, 0x09c1897b9, 0x079776eac, 0x084b00b17, 0x3a95ad90e, 0x28c544095, 0x39d457c05, 0x7a3791a78, 0xbb770e22e, 0x9a822bd6c, 0x68a4b1fed, 0xa5fd27b3b, 0x0c3995b79, 0xd1519dff1, 0x8e7eee359, 0xcd3ca50b1, 0xb73b8b793, 0x57aca1c43, 0xec2655277, 0x785a2c1b3, 0x75a07985a, 0xa4b01eb69, 0xa18a11347, 0xdb1f28ca3, 0x877ec3e25, 0x31f6341b8, 0x1363a3a4c, 0x075d8b9ba, 0x7ae0792a9, 0xa83a21651, 0x7f08f9fb5, 0x0d0cf73a9, 0xb04dcc98e, 0xf65c7b0f8, 0x65ddaf69a, 0x2cf9b86b3, 0x14cb51e25, 0xf48027b5b, 0x0ec26ea8b, 0x44bafd45c, 0xb12c7c0c4, 0x959fd9d82, 0xc77c9725a, 0x48a22d462, 0x8398e8072, 0xec89b05ce, 0xbb682d4c9, 0xe5a86d2ff, 0x358f01134, 0x8556ddcf6, 0x67584b6e2, 0x11609439f, 0x08488816e, 0xaaf1a2c46, 0xf879898cf, 0x8bbe5e2f7, 0x101eee363, 0x690f69377, 0xf5bd93cd9, 0xcea4c2bf6, 0x9550be706, 0x2c5b38a60, 0xe72033547, 0x4458b0629, 0xee8d9ed41, 0xd2f918d72, 0x78dc39fd3, 0x8212636f6, 0x7450a72a7, 0xc4f0cf4c6, 0x367bcddcd, 0xc1caf8cc6, 0xa7f5b853d, 0x9d536818b, 0x535e021b0, 0xa7eb8729e, 0x422a67b49, 0x929e928a6, 0x48e8aefcc, 0xa9897393c, 0x5eb81d37e, 0x1e80287b7, 0x34770d903, 0x2eef86728, 0x59266ccb6, 0x0110bba61, 0x1dfd284ef, 0x447439d1b, 0xfece0e599, 0x9309f3703, 0x80764d1dd, 0x353f1e6a0, 0x2c1c12dcc, 0xc1d21b9d7, 0x457ee453e, 0xd66faf540, 0x44831e652, 0xcfd49a848, 0x9312d4133, 0x3f097d3ee, 0x8c9ebef7a, 0xa99e29e88, 0x0e9fab22c, 0x4e748f4fb, 0xecdee4288, 0xabce5f1d0, 0xc42f6876c, 0x7ed402ea0, 0xe5c4242c3, 0xd5b2c31ae, 0x286863be6, 0x160444d94, 0x5f0f5808e, 0xae3d44b2a, 0x9f5c5d109, 0x8ad9316d7, 0x3422ba064, 0x2fed11d56, 0xbea6e3e04, 0x04b029eec, 0x6deed7435, 0x3718ce17c, 0x55857f5e2, 0x2edac7b62, 0x085d6c512, 0xd6ca88e0f, 0x2b7e1fc69, 0xa699d5c1b, 0xf05ad74de, 0x4cf5fb56d, 0x5725e07e1, 0x72f18a2de, 0x1cec52609, 0x48534243c, 0x2523a4d69, 0x35c1b80d1, 0xa4d7338a7, 0x0db1af012, 0xe61a9475d, 0x05df03f91, 0x97ae260bb, 0x32d627fef, 0xb640f73c2, 0x45a1ac9c6, 0x6a2202de1, 0x57d3e25f2, 0x5aa9f986e, 0x0cc859d8a, 0xe3ec6cca8, 0x54e95e1ae, 0x446887b06, 0x7516732be, 0x3817ac8f5, 0x3e26d938c, 0xaa81bc235, 0xdf387ca1b, 0x0f3a3b3f2, 0xb4bf69677, 0xae21868ed, 0x81e1d2d9d, 0xa0a9ea14c, 0x8eee297a9, 0x4740c0559, 0xe8b141837, 0xac69e0a3d, 0x9ed83a1e1, 0x5edb55ecb, 0x07340fe81, 0x50dfbc6bf, 0x4f583508a, 0xcb1fb78bc, 0x4025ced2f, 0x39791ebec, 0x53ee388f1, 0x7d6c0bd23, 0x93a995fbe, 0x8a41728de, 0x2fe70e053, 0xab3db443a, 0x1364edb05, 0x47b6eeed6, 0x12e71af01, 0x52ff83587, 0x3a1575dd8, 0x3feaa3564, 0xeacf78ba7, 0x0872b94f8, 0xda8ddf9a2, 0x9aa920d2b, 0x1f350ed36, 0x18a5e861f, 0x2c35b89c3, 0x3347ac48a, 0x7f23e022e, 0x2459068fb, 0xe83be4b73] + # t36h9=[0x131b29eda, 0x16c41a49f, 0x1a6d0aa64, 0x1e15fb029, 0x21beeb5ee, 0x2567dbbb3, 0x2910cc178, 0x340b9d2c7, 0x37b48d88c, 0x42af5e9db, 0x4a013f565, 0x54fc106b4, 0x58a500c79, 0x6748c238d, 0x6e9aa2f17, 0x75ec83aa1, 0x799574066, 0x7d3e6462b, 0x80e754bf0, 0x88393577a, 0x8be225d3f, 0x9a85e7453, 0x9e2ed7a18, 0xa580b85a2, 0xa929a8b67, 0xacd29912c, 0xb07b896f1, 0xb42479cb6, 0xbb765a840, 0xbf1f4ae05, 0xc6712b98f, 0xca1a1bf54, 0xd514ed0a3, 0xd8bddd668, 0xf60560490, 0xf9ae50a55, 0x085212169, 0x0bfb0272e, 0x1e47b4407, 0x294285556, 0x2ceb75b1b, 0x37e646c6a, 0x4a32f8943, 0x552dc9a92, 0x58d6ba057, 0x677a7b76b, 0x6b236bd30, 0x72754c8ba, 0x81190dfce, 0x84c1fe593, 0x886aeeb58, 0x8c13df11d, 0x970eb026c, 0xad045250a, 0xb45633094, 0xc6a2e4d6d, 0xca4bd5332, 0xd19db5ebc, 0xd546a6481, 0xdc988700b, 0xe3ea67b95, 0xe7935815a, 0xeee538ce4, 0x0131ea9bd, 0x0c2cbbb0c, 0x0fd5ac0d1, 0x137e9c696, 0x17278cc5b, 0x22225ddaa, 0x2d1d2eef9, 0x346f0fa83, 0x3f69e0bd2, 0x4312d1197, 0x4e0da22e6, 0x51b6928ab, 0x590873435, 0x5cb1639fa, 0x605a53fbf, 0x67ac34b49, 0x6b552510e, 0x6efe156d3, 0x764ff625d, 0x889ca7f36, 0x8c45984fb, 0x939779085, 0x97406964a, 0xa5e42ad5e, 0xc6d49e14b, 0xce267ecd5, 0xd9214fe24, 0xdcca403e9, 0xe7c511538, 0xf668d2c4c, 0x13b055a74, 0x29a5f7d12, 0x2d4ee82d7, 0x3849b9426, 0x3bf2a99eb, 0x43448a575, 0x46ed7ab3a, 0x51e84bc89, 0x6b86de4ec, 0x6f2fceab1, 0x72d8bf076, 0x7681af63b, 0x852570d4f, 0x8c77518d9, 0x93c932463, 0x9ec4035b2, 0xad67c4cc6, 0xb110b528b, 0xb4b9a5850, 0xcaaf47aee, 0xce58380b3, 0xd5aa18c3d, 0xe0a4e9d8c, 0xe44dda351, 0xe7f6ca916, 0xef48ab4a0, 0xf2f19ba65, 0xf69a8c02a, 0x10391e88d, 0x1b33ef9dc, 0x262ec0b2b, 0x29d7b10f0, 0x2d80a16b5, 0x312991c7a, 0x3c2462dc9, 0x437643953, 0x521a05067, 0x55c2f562c, 0x6466b6d40, 0x730a78454, 0x76b368a19, 0x7a5c58fde, 0x7e05495a3, 0x85572a12d, 0x9051fb27c, 0x97a3dbe06, 0x9ef5bc990, 0xa29eacf55, 0xa6479d51a, 0xb1426e669, 0xb4eb5ec2e, 0xb8944f1f3, 0xce89f1491, 0xd5dbd201b, 0xd984c25e0, 0xe0d6a316a, 0xf32354e43, 0xfa75359cd, 0x0918f70e1, 0x106ad7c6b, 0x17bcb87f5, 0x22b789944, 0x38ad2bbe2, 0x4750ed2f6, 0x4af9dd8bb, 0x6f934126d, 0x8931d3ad0, 0x8cdac4095, 0x9083b465a, 0x9b7e857a9, 0xa2d066333, 0xa679568f8, 0xadcb37482, 0xb8c6085d1, 0xc017e915b, 0xc769c9ce5, 0xe85a3d0d2, 0xec032d697, 0xefac1dc5c, 0xf3550e221, 0xfaa6eedab, 0x01f8cf935, 0x22e942d22, 0x4782a66d4, 0x4b2b96c99, 0x4ed48725e, 0x5d7848972, 0x64ca294fc, 0x687319ac1, 0x6fc4fa64b, 0x736deac10, 0x7abfcb79a, 0x85ba9c8e9, 0x89638ceae, 0xa6ab0fcd6, 0xaa540029b, 0xb1a5e0e25, 0xbca0b1f74, 0xc049a2539, 0xcb4473688, 0xceed63c4d, 0xd29654212, 0xdd9125361, 0xe13a15926, 0xe88bf64b0, 0xec34e6a75, 0xfad8a8189, 0xfe819874e, 0x097c6989d, 0x26c3ec6c5, 0x2a6cdcc8a, 0x2e15cd24f, 0x31bebd814, 0x4b5d50077, 0x5a011178b, 0x5daa01d50, 0x6c4dc3464, 0x6ff6b3a29, 0x7748945b3, 0x89954628c, 0x90e726e16, 0xa333d8aef, 0xa6dcc90b4, 0xc07b5b917, 0xc4244bedc, 0xcb762ca66, 0xd670fdbb5, 0xe16bced04, 0xf76170fa2, 0x14a8f3dca, 0x1bfad4954, 0x2a9e96068, 0x2e478662d, 0x31f076bf2, 0x39425777c, 0x52e0e9fdf, 0x5689da5a4, 0x5ddbbb12e, 0x68d68c27d, 0x94c1d07b9, 0x986ac0d7e, 0x9fbca1908, 0xa36591ecd, 0xaab772a57, 0xc0ad14cf5, 0xcba7e5e44, 0xd2f9c69ce, 0xd6a2b6f93, 0xda4ba7558, 0xddf497b1d, 0xec9859231, 0xfee50af0a, 0x0636eba94, 0x14daad1a8, 0x397410b5a, 0x40c5f16e4, 0x4817d226e, 0x655f55096, 0x69084565b, 0x94f389b97, 0x989c7a15c, 0x9fee5ace6, 0xaae92be35, 0xb98ced549, 0xcbd99f222, 0xd32b7fdac, 0xecca1260f, 0xf07302bd4, 0x02bfb48ad, 0x0a1195437, 0x0dba859fc, 0x18b556b4b, 0x2eaaf8de9, 0x35fcd9973, 0x3d4eba4fd, 0x4bf27bc11, 0x56ed4cd60, 0x61e81deaf, 0x6939fea39, 0x82d89129c, 0x917c529b0, 0x952542f75, 0xa3c904689, 0xa771f4c4e, 0xb26cc5d9d, 0xc4b977a76, 0xcfb448bc5, 0xdaaf19d14, 0xe952db428, 0xf44dac577, 0x153e1f964, 0x278ad163d, 0x3285a278c, 0x39d783316, 0x487b44a2a, 0x5e70e6cc8, 0x6219d728d, 0x696bb7e17, 0x746688f66, 0x830a4a67a, 0x91ae0bd8e, 0xa051cd4a2, 0xab4c9e5f1, 0xb6476f740, 0xbd99502ca, 0xc89421419, 0xcc3d119de, 0xd737e2b2d, 0xe5dba4241, 0xf82855f1a, 0x156fd8d42, 0x1cc1b98cc, 0x2b657afe0, 0x32b75bb6a, 0x36604c12f, 0x53a7cef57, 0x5ea2a00a6, 0x86e4f401d, 0x9931a5cf6, 0xa42c76e45, 0xaf2747f94, 0xb67928b1e, 0xbdcb096a8, 0xc8c5da7f7, 0xcc6ecadbc, 0xd3c0ab946, 0xdebb7ca95, 0xe2646d05a, 0x11f8a1b5b, 0x244553834, 0x3de3e6097, 0x48deb71e6, 0x53d988335, 0x5782788fa, 0x69cf2a5d3, 0x71210b15d, 0x8716ad3fb, 0x9d0c4f699, 0xb301f1937, 0xc1a5b304b, 0x122a5af39, 0x2bc8ed79c, 0x331ace326, 0x4cb960b89, 0x540b41713, 0x62af02e27, 0x6657f33ec, 0x6da9d3f76, 0xa0e6f903c, 0xabe1ca18b, 0xaf8aba750, 0xc1d76c429, 0xc9294cfb3, 0xf8bd81ab4, 0x0b0a3378d, 0x3e4758853, 0x5f37cbc40, 0x6689ac7ca, 0x6a329cd8f, 0x6ddb8d354, 0xb365640f3, 0xb70e546b8, 0xbe6035242, 0xc5b215dcc, 0xc95b06391, 0xcd03f6956, 0xd0ace6f1b, 0xe6a2891b9, 0xf19d5a308, 0x128dcd6f5, 0x1636bdcba, 0x2c2c5ff58, 0x3727310a7, 0x5bc094a59, 0x5f698501e, 0x6312755e3, 0x87abd8f95, 0x8b54c955a, 0x99f88ac6e, 0xac453c947, 0xc23adebe5, 0xd487908be, 0xea7d32b5c, 0x0072d4dfa, 0x07c4b5984, 0x12bf86ad3, 0x250c387ac, 0x2c5e19336, 0x3b01daa4a, 0x50f77cce8, 0x54a06d2ad, 0x58495d872, 0x71e7f00d5, 0x8434a1dae, 0x87dd92373, 0xa5251519b, 0xb01fe62ea, 0xc61588588, 0xf952ad64e, 0x0f484f8ec, 0x253df1b8a, 0x28e6e214f, 0x4285749b2, 0x462e64f77, 0x54d22668b, 0x5c2407215, 0x6ac7c8929, 0x80bd6abc7, 0x9a5bfd42a, 0xa1adddfb4, 0xa556ce579, 0xb3fa8fc8d, 0xc64741966, 0xcd99224f0, 0xeae0a5318, 0xf5db76467, 0x306a7c0b7, 0x4a090e91a, 0x58acd002e, 0x6ea2722cc, 0xacda684e1, 0xcdcadb8ce, 0xe7696e131, 0xf60d2f845, 0x25a164346, 0x344525a5a, 0x3b97065e4, 0x42e8e716e, 0x4de3b82bd, 0x553598e47, 0x5c87799d1, 0x6b2b3b0e5, 0x8120dd383, 0x84c9cd948, 0xbf58d3598, 0xdca0563c0, 0xeeed08099, 0x1ad84c5d5, 0x46c390b11, 0x606223374, 0x7a00b5bd7, 0xa994ea6d8, 0xb0e6cb262, 0xce2e4e08a, 0x2d56b768c, 0x434c5992a, 0x643cccd17, 0x6f379de66, 0x76897e9f0, 0x88d6306c9, 0xa9c6a3ab6, 0xb86a651ca, 0xd208f7a2d, 0x29df804a5, 0x646e860f5, 0x6f6957244, 0x7a6428393, 0xa9f85ce94, 0xada14d459, 0xe830530a9, 0x2a1139883, 0x4758bc6ab, 0x8939a2e85, 0x8ce29344a, 0x908b83a0f, 0xadd306837, 0xb524e73c1, 0xc3c8a8ad5, 0x353dc3db0, 0x6129082ec, 0x687ae8e76, 0x771eaa58a, 0x94662d3b2, 0x9f60fe501, 0xd29e235c7, 0x147f09da1, 0x2322cb4b5, 0x406a4e2dd, 0x4b651f42c, 0x615ac16ca, 0x68aca2254, 0x9840d6d55, 0xb9314a142, 0xd678ccf6a, 0xddcaadaf4, 0xf76940357, 0x1859b3744, 0x1fab942ce, 0x2aa66541d, 0x4b96d880a, 0x5691a9959, 0x6c874bbf7, 0xae68323d1, 0xc0b4e40aa, 0xcf58a57be, 0xd6aa86348, 0xe54e47a5c, 0x40cdc0a99, 0x5a6c532fc, 0x82aea7273, 0x94fb58f4c, 0xa7480ac25, 0xaaf0fb1ea, 0xb5ebcc339, 0xb994bc8fe, 0xd3334f161, 0xda852fceb, 0xe1d710875, 0x0dc254db1, 0x2760e7614, 0x2b09d7bd9, 0x3604a8d28, 0x61efed264, 0x6598dd829, 0x6941cddee, 0x98d6028ef, 0xa3d0d3a3e, 0xab22b45c8, 0xb27495152, 0x06a22d605, 0x1545eed19, 0x4fd4f4969, 0x746e5831b, 0x7f692946a, 0x955ecb708, 0xa4028ce1c, 0xab546d9a6, 0xb2a64e530, 0xc89bf07ce, 0xe5e3735f6, 0x4162ec633, 0x5006add47, 0x57588e8d1, 0x8a95b3997, 0x959084ae6, 0xa434461fa, 0xba29e8498, 0xbdd2d8a5d, 0x27f6131ae, 0x2b9f03773, 0x32f0e42fd, 0x4194a5a11, 0x48e68659b, 0x787abb09c, 0x7c23ab661, 0x83758c1eb, 0xaf60d0727, 0xd7a32469e, 0xe646e5db2, 0x0ae049764, 0x3e1d6e82a, 0x665fc27a1, 0x6db1a332b, 0x715a938f0, 0x750383eb5, 0x83a7455c9, 0xa0eec83f1, 0xb33b7a0ca, 0xc5882bda3, 0xc9311c368, 0xccda0c92d, 0xe6789f190, 0xedca7fd1a, 0x1263e36cc, 0x19b5c4256, 0x2c0275f2f, 0x4949f8d57, 0x509bd98e1, 0xa4c971d94, 0xd0b4b62d0, 0x079acb95b, 0x12959caaa, 0x21395e1be, 0x33860fe97, 0x5f71543d3, 0x7566f6671, 0x840ab7d85, 0x8f0588ed4, 0xa4fb2b172, 0xb39eec886, 0xbe99bd9d5, 0xc9948eb24, 0xe33321387, 0x1a1936a12, 0x425b8a989, 0x5bfa1d1ec, 0xe70dcad2a, 0xee5fab8b4, 0x4d8814eb6, 0x7973593f2, 0x9311ebc55, 0x21ce89d58, 0x5162be859, 0x58b49f3e3, 0x6eaa41681, 0xbb85f8faa, 0xd5248b80d, 0x4a42970ad, 0x678a19ed5, 0x6b330a49a, 0x762ddb5e9, 0xa5c2100ea, 0xca5b73a9c, 0xeb4be6e89, 0xf29dc7a13, 0xfd9898b62, 0x17372b3c5, 0x25daecad9, 0x556f215da, 0x975007db4, 0xa5f3c94c8, 0xa99cb9a8d, 0x0c6e13654, 0x29b59647c, 0x55a0da9b8, 0x7a3a3e36a, 0x9781c1192, 0x9b2ab1757, 0x9ed3a1d1c, 0xad7763430, 0xcabee6258, 0xef5849c0a, 0x1eec7e70b, 0x4ad7c2c47, 0x731a16bbe, 0x8566c8897, 0xe0e6418d4, 0xf332f35ad, 0x267018673, 0x3513d9d87, 0x3c65ba911, 0x4eb26c5ea, 0x56044d174, 0x64a80e888, 0x7e46a10eb, 0xbc7e97300, 0x4040642b4, 0x43e954879, 0x4b3b35403, 0xaa639ea05, 0x232a9a86a, 0x47c3fe21c, 0x825303e6c, 0xa34377259, 0xc433ea646, 0xddd27cea9, 0xe5245da33, 0x0d66b19aa, 0x5deb59898, 0x653d3a422, 0xa37530637, 0xb5c1e2310, 0xcbb7845ae, 0xd6b2556fd, 0xeca7f799b, 0xfef4a9674, 0x06468a1fe, 0x4f7951562, 0x98ac188c6, 0xff2662a52, 0x0a2133ba1, 0x11731472b, 0x326387b18, 0x3d5e58c67, 0x69499d1a3, 0x77ed5e8b7, 0xb27c64507, 0xc4c9161e0, 0x11a4cdb09, 0x329540ef6, 0x572ea48a8, 0xa40a5c1d1, 0xaf052d320, 0xb2ae1d8e5, 0xb6570deaa, 0xd39e90cd2, 0xd74781297, 0x157f774ac, 0x4c658cb37, 0xed6edc913, 0x0e5f4fd00, 0x74d999e8c, 0x7c2b7aa16, 0xba6370c2b, 0x2bd88bf06, 0x2f817c4cb, 0x750b5326a, 0x95fbc6657, 0xe6806e545, 0x2fb3358a9, 0x335c25e6e, 0x7c8eed1d2, 0xafcc12298, 0xb3750285d, 0x19ef4c9e9, 0x3736cf811, 0x3e88b039b, 0x582742bfe, 0x5f7923788, 0x8f0d58289, 0x9db11999d, 0xa15a09f62, 0xaffdcb676, 0xc99c5ded9, 0xee35c188b, 0x376888bef, 0xa8dda3eca, 0xd4c8e8406, 0x0baefda91, 0x21a49fd2f, 0x3eec22b57, 0x797b287a7, 0x9a6b9bb94, 0xc9ffd0695, 0xdc4c8236e, 0x37cbfb3ab, 0x3b74eb970, 0x516a8dc0e, 0x84a7b2cd4, 0xb7e4d7d9a, 0xd8d54b187, 0x1ab631961, 0x1e5f21f26, 0x25b102ab0, 0xa220eeeda, 0x13960a1b5, 0x34867d5a2, 0x3bd85e12c, 0x1ec2946e2, 0x26147526c, 0x88e5cee33, 0xa62d51c5b, 0xb12822daa, 0xb87a03934, 0xcac6b560d, 0xce6fa5bd2, 0x34e9efd5e, 0x3fe4c0ead, 0x6f78f59ae, 0x76cad6538, 0x97bb49925, 0xcea15efb0, 0xd24a4f575, 0xd5f33fb3a, 0x01de84076, 0x3c6d89cc6, 0x4b114b3da, 0x6858ce202, 0x8949415ef, 0x9b95f32c8, 0xd27c08953, 0xd624f8f18, 0xd9cde94dd, 0x4b43047b8, 0x90ccdb557, 0xbcb81fa93, 0xe4fa73a0a, 0x0993d73bc, 0x39280bebd, 0x89acb3dab, 0x90fe94935, 0xda315bc99, 0xddda4c25e, 0x40aba5e25, 0xb5c9b16c5, 0xb972a1c8a, 0xcbbf53963, 0xda6315077, 0x02a568fee, 0x09f749b78, 0x1fecebe16, 0x2e90ad52a, 0x4bd830352, 0x5a7bf1a66, 0x950af76b6, 0xaea989f19, 0xf08a706f3, 0x201ea51f4, 0x23c7957b9, 0x4c09e9730, 0x5704ba87f, 0x77f52dc6c, 0xa7896276d, 0xb62d23e81, 0x0a5abc334, 0x623144dac, 0x9cc04a9fc, 0x242b07f75, 0x32cec9689, 0xa7ecd4f29, 0xc18b6778c, 0x07153e52b, 0x0e671f0b5, 0x8ad70b4df, 0xbe14305a5, 0xc1bd20b6a, 0xe9ff74ae1, 0x4cd0ce6a8, 0x62c670946, 0x7c65031a9, 0x960395a0c, 0xafa22826f, 0x0eca91871, 0x3363f5223, 0x5ba64919a, 0xd816355c4, 0x164e2b7d9, 0x2148fc928, 0x87c346ab4, 0xd49efe3dd, 0x9a41b1b6b, 0xa193926f5, 0xb03753e09, 0x37a211382, 0x4645d2a96, 0x673645e83, 0xb411fd7ac, 0x4a207c439, 0x96fc33d62, 0x9e4e148ec, 0x3f57646c8, 0x46a945252, 0x81384aea2, 0x972ded140, 0xa97a9ee19, 0xca6b12206, 0x29937b808, 0x6f1d525a7, 0x766f33131, 0x177882f0d, 0x1eca63a97, 0x55b079122, 0x8c968e7ad, 0xb881d2ce9, 0xbc2ac32ae, 0xd2206554c, 0x22a50d43a, 0x2d9fde589, 0x3fec90262, 0x60dd0364f, 0xbc5c7c68c, 0x64b7acff2, 0x9f46b2c42, 0x59ee95281, 0x6c3b46f5a, 0xaa733d16f, 0x2a8c19b5e, 0x31ddfa6e8, 0xb59fc769c, 0xf780ade76, 0x06246f58a, 0x56a917478, 0x7047a9cdb, 0x91381d0c8, 0xda6ae442c, 0x61d5a19a5, 0xa3b68817f, 0xb25a49893, 0xc4a6fb56c, 0xd6f3ad245, 0xde458ddcf, 0x1182b2e95, 0x2eca35cbd, 0x327326282, 0x4c11b8ae5, 0x570c89c34, 0x5ab57a1f9, 0xcfd385a99, 0xcc5c4e8b2, 0xff9973978, 0xa7f4a42de, 0xdedab9969, 0x1d12afb7e, 0x74e9385f6, 0x99829bfa8, 0xc916d0aa9, 0xd7ba921bd, 0x0af7b7283, 0x2f911ac35, 0x6dc910e4a, 0x8767a36ad, 0xb352e7be9, 0xd4435afd6, 0x2c19e3a4e, 0x2fc2d4013, 0x6a51d9c63, 0xea6ab6652, 0xf1bc971dc, 0xfcb76832b, 0x49931fc54, 0xa8bb89256, 0x3b211791e, 0x4272f84a8, 0xbee2e48d2, 0xd4d886b70, 0x2caf0f5e8, 0x3b52d0cfc, 0x5fec346ae, 0x932959774, 0x16eb26728, 0x76138fd2a, 0xd53bf932c, 0x9adeacaba, 0x3f90ece5b, 0x4a8bbdfaa, 0x901594d49, 0xbfdb82c28, 0x17b20b6a0, 0x143ad44b9, 0x2dd966d1c, 0x61168bde2, 0xa6a062b81, 0xcee2b6af8, 0xe8814935b, 0x0d1aacd0d, 0x7ae6d7a23, 0xd2bd6049b, 0xe8b302739, 0xf3add3888, 0x05fa85561, 0x567f2d44f, 0xdde9ea9c8, 0xe192daf8d, 0xf7887d22b, 0x77a159c1a, 0x94e8dca42, 0xa38c9e156, 0x7b7c035bd, 0xc857baee6, 0x44c7a7310, 0x6d09fb287, 0x745bdbe11, 0x8a517e0af, 0xa79900ed7, 0xb66e7b9c9, 0xcc641dc67, 0x1596e4fcb, 0x661b8ceb9, 0x8ab4f086b, 0xa453830ce, 0x8ae6a9c49, 0x0ea876bfd, 0x3341da5af, 0x5f2d1eaeb, 0xea40cc629, 0x5bb5e7904, 0xa4e8aec68, 0xac3a8f7f2, 0xb73560941, 0xbade50f06, 0xbe87414cb, 0xc23031a90, 0xcd2b02bdf, 0x6a8b623f6, 0x6e34529bb, 0x8f24c5da8, 0x9dc8874bc, 0xa17177a81, 0xdfa96dc96, 0x511e88f71, 0x96a85fd10, 0xd4e055f25, 0xead5f81c3, 0x933128b29, 0xcdc02e779, 0x0fa114f53, 0x72726eb1a, 0x970bd24cc, 0x0880ed7a7, 0x973d8b8aa, 0xeb6b23d5d, 0x1aff5885e, 0x1ea848e23, 0x29a319f72, 0x852292faf, 0x88cb83574, 0x0c8d50528, 0x3126b3eda, 0xf320770a3, 0x4af6ffb1b, 0x4e9ff00e0, 0x5d43b17f4, 0x733953a92, 0x9080d68ba, 0xa67678b58, 0xdd5c8e1e3, 0x22e664f82, 0x05d09b538, 0x14745cc4c, 0x8d3b58ab1, 0xd66e1fe15, 0x40915a566, 0x4b8c2b6b5, 0x911602454, 0xe5439a907, 0xe1cc63720, 0x5a935f585, 0x7431f1de8, 0x7b83d2972, 0x8dd08464b, 0xa76f16eae, 0xde552c539, 0x153b41bc4, 0x2787f389d, 0x98fd0eb78, 0xaef2b0e16, 0x2b629d240, 0x0aa3e3231, 0x836adf096, 0xb2ff13b97, 0xd79877549, 0xf888ea936, 0x540863973, 0x62ac25087, 0xc9266f213, 0xd42140362, 0x877741e17, 0x3e7633e91, 0x50c2e5b6a, 0x12bca8d33, 0x758e028fa, 0x92d585722, 0x12ee62111, 0xbb4992a77, 0xc9ed5418b, 0xd4e8252da, 0x6af6a3f67, 0x76232e494, 0xb45b246a9, 0xc6a7d6382, 0x3bc5e1c22, 0x640835b99, 0x8c4a89b10, 0x8ff37a0d5, 0xa2402bdae, 0x437b34f68, 0x646ba8355, 0x6bbd88edf, 0xc39411957, 0xcae5f24e1, 0xf32846458, 0x8cdfb56aa, 0x9088a5c6f, 0xadd028a97, 0xe4b63e122, 0x094fa1ad4, 0x17f3631e8, 0x40677053d, 0x0d5c04855, 0xa71373aa7, 0x0292ecae4, 0x1136ae1f8, 0x8dd853a00, 0xb61aa7977, 0x363384366, 0x5723f7753, 0xf48456f6a, 0xdec06e0aa, 0x0aabb25e6, 0xa80c11dfd, 0xf890b9ceb, 0x3a71a04c5, 0x7157b5b50, 0xdb7af02a1, 0x57eadc6cb, 0xac1874b7e, 0x3ad512c81, 0x2c630a94b, 0x87e283988, 0x169f21a8b, 0x7d196bc17, 0x1e22bb9f3, 0xd8ca9e032, 0x1e862e1af, 0xbbe68d9c6, 0xce64f8a7d, 0x8cb5cb681, 0xce96b1e5b, 0x057cc74e6, 0x64d6e9ec6, 0x687fda48b, 0xd64c051a1, 0x2327bcaca, 0x31cb7e1de, 0x7afe45542, 0x7ea735b07, 0xddcf9f109, 0x2aab56a32, 0x56969af6e, 0x029abbe99, 0x61c32549b, 0x656c15a60, 0xcf8f501b1, 0xde64caca3, 0xf45a6cf41, 0x9cb59d8a7, 0x5b06704ab, 0x6d5322184, 0xbdd7ca072, 0x48eb77bb0, 0x4c9468175, 0xc55b63fda, 0xd7a815cb3, 0x20dadd017, 0x6a0da437b, 0xea2680d6a, 0x19bab586b, 0xdbb478a34, 0x50d2842d4, 0x6350ef38b, 0x54dee7055, 0x2d000589a, 0x4a47886c2, 0xad18e2289, 0xf9f499bb2, 0x1e8dfd564, 0x2988ce6b3, 0x9afde998e, 0x76963f3ba, 0xebb44ac5a, 0xe83d13a73, 0x0cd677425, 0x52604e1c4, 0x9f3c05aed, 0xaa36d6c3c, 0xbc8388915, 0xcb274a029, 0x7b06148f7, 0xc46a95039, 0x9c59fa4a0, 0xb9a17d2c8, 0x39ba59cb7, 0xc4ce077f5, 0xf0b94bd31, 0x3a1dcc473, 0x57654f29b, 0x2f866dae0, 0x57c8c1a57, 0xdb8a8ea0b, 0x423691f75, 0x66cff5927, 0xcd4a3fab3, 0xe71a8b6f4, 0x21a991344, 0x304d52a58, 0x6733680e3, 0x307f0be36, 0xb440d8dea, 0xfd73a014e, 0x3459b57d9, 0x3f5486928, 0xe46a39485, 0xd9d2daaf2, 0xe8a8555e4, 0xa35037c23, 0xc472643ee, 0x239acd9f0, 0xb9db05a5b, 0xcc27b7734, 0x364af1e85, 0xc8b08054d, 0x8e84ed0b9, 0x36e01da1f, 0xafa719884, 0xbb055d18f, 0xf93d533a4, 0x6ab26e67f, 0xe3796a4e4, 0xf21d2bbf8, 0x464ac40ab, 0xe75413e87, 0x676cf0876, 0xe785cd265, 0xdcbcb54f4, 0x5cd591ee3, 0xb1032a396, 0xa9e302bea, 0xb886c42fe, 0x523e33550, 0xb50f8d117, 0x1b89d72a3, 0x1bbb90681, 0xf753e60ad, 0x4f2a6eb25, 0x03159c174, 0x06be8c739, 0xd03be986a, 0x0acaef4ba, 0x7fe8fad5a, 0x50867f637, 0x78c8d35ae, 0x2875e4a9e, 0x78fa8c98c, 0xac37b1a52, 0xb0125b3f5, 0xa54943684, 0xa1d20c49d, 0xd8e9daf06, 0xdcc4848a9, 0xf6631710c, 0x851fb520f, 0xa9b918bc1, 0xb13cb2b29, 0xef74a8d3e, 0xf6c6898c8, 0xaa1c8b37d, 0xb5175c4cc, 0x64c46d9bc, 0xcee7a810d, 0x05cdbd798, 0xfb04a5a27, 0x73fd5ac6a, 0xecc456acf, 0x56e791220, 0x693442ef9, 0xc10acb971, 0x44cc98925, 0x5ac23abc3, 0x7bb2adfb0, 0x2064ee351, 0x4c81ebc6b, 0xaf84fec10, 0xa112f68da, 0x078d40a66, 0xa144afcb8, 0xb73a51f56, 0xe6ce86a57, 0xf94cf1b0e, 0x7213ed973, 0xfd595488f, 0xb45846909, 0x1b3603251, 0x90540eaf1, 0xebd387b2e, 0x8933e7345, 0xb8c81be46, 0x4b2daa50e, 0xe13c2919b, 0x4c2648864, 0xb64982fb5, 0xa0e90c8b1, 0x5f39df4b5, 0xac1596dde, 0xf5485e142, 0xc9f2457a0, 0x60327d80b, 0x225df9db2, 0x35a349de1, 0xb5bc267d0, 0x9c8106729, 0xa029f6cee, 0xaecdb8402, 0x44dc3708f, 0x0e27dade2, 0x48b6e0a32, 0x9d16322c3, 0x5f0ff548c, 0x3010ec525, 0x0f83eb8f4, 0x1e27ad008, 0x9345b88a8, 0xa24cec778, 0x4e510d6a3, 0xb8d7ba5b0, 0x1f83bdb1a, 0x53560e77a, 0xed0d7d9cc, 0x78b6570a4, 0x07a4ae585, 0x498594d5f, 0x9a0a3cc4d, 0xdc1cdc805, 0xe717ad954, 0xa1bf8ff93, 0xb063516a7, 0xc6bc66101, 0xd93ad11b8, 0xe435a2307, 0xe7de928cc, 0x60a58e731, 0x769b309cf, 0x0ca9af65c, 0x97bd5d19a, 0x560e2fd9e, 0x1f59d3af1, 0xbcebec6e6, 0x14f42e53c, 0xb62f376f6, 0xe31319f88, 0x66d4e6f3c, 0x6e26c7ac6, 0xee3fa44b5, 0x80a532b7d, 0xe3768c744, 0xd15b93e49, 0xb09cd9e3a, 0x642494ccd, 0xf6ed95b51, 0x7769e4cfc, 0x779b9e0da, 0x3995612a3, 0xbd572e257, 0x0a32e5b80, 0x5ae946e4c, 0x8e266bf12, 0x36819c878, 0x41ae26da5, 0x0af9caaf8, 0x542c91e5c, 0x57d582421, 0x6a22340fa, 0xac668d090, 0x6e6050259, 0xbb3c07b82, 0xee792cc48, 0xb072efe11, 0xbf486a903, 0x88940e656, 0xa98481a43, 0x7a53bf6fe, 0x40bd57e04, 0x2ea25f509, 0x745def686, 0xc88b87b39, 0xc8bd40f17, 0x9d356f197, 0xf8b4e81d4, 0x0b0199ead, 0x1d4e4bb86, 0x78cdc4bc3, 0x54661a5ef, 0x79313737f, 0x3ed3eab0d, 0x6f2f04586, 0x9b4c01ea0, 0x4b2acc76e, 0x52e01fab4, 0x9c12e6e18, 0x2acf84f1b, 0xc0de03ba8, 0x362dc8826, 0x15a0c7bf5, 0xd07a63612, 0x57e520b8b, 0x2c2b95a2d, 0x0f47853c1, 0x465f53e2a, 0xa96266dcf, 0xf32a59ccd, 0xd6a9bbe1d, 0x5e1479396, 0x39accedc2, 0xbd6e9bd76, 0x5ea9a4f30, 0x4c8eac635, 0xa83fdea50, 0xafc3789b8, 0x0b42f19f5, 0x1dc15caac, 0x6acecd7b3, 0x135bb74f7, 0x3b9e0b46e, 0x34af9d0a0, 0x76908387a, 0xb9384efcc, 0x4b9ddd694, 0x8a078cc87, 0xd7aa29528, 0x073e5e029, 0x24b79a22f, 0x3f4ecade8, 0xd9063a03a, 0xce3d222c9, 0x226aba77c, 0x93dfd5a57, 0xb1bc84419, 0xb90e64fa3, 0x52f78d5d3, 0xbd4c81102, 0x2ec19c3dd, 0x8352a704c, 0xbde1acc9c, 0x875f09dcd, 0xd49e33eb2, 0x5fe39adce, 0x638c8b393, 0xb099fc09a, 0xdc85405d6, 0x42ff8a762, 0x6ba550e95, 0xd9717bbab, 0x10894a614, 0x5d6501f3d, 0x445b9b274, 0x89e572013, 0x11502f58c, 0x533115d66, 0x98baecb05, 0x95a7280da, 0xdfa0d43b6, 0xc28b0a96c, 0xe7246e31e, 0x046bf1146, 0x3b52067d1, 0x601d23561, 0x08dbc6683, 0x13d6977d2, 0x29cc39a70, 0x105f605eb, 0x3c4aa4b27, 0x736273590, 0x985f496fe, 0xec8ce1bb1, 0x9fe2e3666, 0x065d2d7f2, 0x91d44daec, 0xa7c9efd8a, 0x3a2f7e452, 0x6d9e5c8f6, 0xa0db819bc, 0xf50919e6f, 0x667e3514a, 0x9393d0dba, 0x614f4a04a, 0x77da17e82, 0xc8f3eb90a, 0xa4bdfa714, 0x967dab7bc, 0xf22eddbd7, 0x8be64ce29, 0xb1dbc12ed, 0xd6a6de07d, 0x690c6c745, 0xb5e82406e, 0x484db2736, 0x46328c061, 0xad10489a9, 0x9af5500ae, 0xd9c271e5d, 0xe4bd42fac, 0x3198fa8d5, 0xd9f42b23b, 0x7ea66b5dc, 0xcf2b134ca, 0xe1a97e581, 0x535052c3a, 0x37016e168, 0x7cbcfe2e5, 0xa1881b075, 0x42916ae51, 0x884cfafce, 0x3bd4b5e61, 0x72ec848ca, 0xb187ed29b, 0x279e96e91, 0x07434f63e, 0xf17f6677e, 0x19f373ad3, 0x58c095882, 0xc315893b1, 0x0559e2347, 0x38970740d, 0xfecee6735, 0x2054856bc, 0x994d3a8ff, 0x9607bcaf6, 0xe00168dd2, 0x25eeb232d, 0x1ece8ab81, 0x2ece5cda7, 0x82fbf525a, 0xb388c80b1, 0xf569ae88b, 0x8f52d6ebb, 0x58d033fec, 0xfd827438d, 0x3f9513f45, 0xf6c5bf39d, 0x6491ea0b3, 0xebfca762c, 0x736764ba5, 0xa707fc427, 0x44685bc3e, 0x3a02b6689, 0x5404bb6a8, 0xf50e0b484, 0x2505b2741, 0xb0ae8be19, 0xf2c12b9d1, 0x46eec3e84, 0x053f96a88, 0xd5dd1b365, 0x2a6e25fd4, 0x3911e76e8, 0xe1d08a80a, 0x39d8cc660, 0x3a0a85a3e, 0x91e10e4b6, 0xf85b58642, 0xe2976f782, 0x3e16e87bf, 0xccd3868c2, 0x8f30bc247, 0xd51e057a2, 0xb839f5136, 0x2355cdbdd, 0xa591a0056, 0xfd6828ace, 0xca8e761c4, 0x435572029, 0x7e1631057, 0xaa332e971, 0xb1b6c88d9, 0xaafa138e9, 0x92b791b98, 0xfd0c856c7, 0xe4984a598, 0xe121133b1, 0xda32a4fe3, 0x40dea854d, 0xab970e838, 0x1d0c29b13, 0x454e7da8a, 0x039f5068e, 0x7c98058d1, 0xb37e1af5c, 0x6769485ab, 0x58f740275, 0x3fedd95ac, 0x1f9291d59, 0x7b757d552, 0x95daf4d2d, 0x4930f67e2, 0xea3a465be, 0xd949a53f7, 0x2da8f6c88, 0x6117d512c, 0x736486e05, 0x7e5f57f54, 0x689b6f094, 0x53093f5b2, 0xc107236a6, 0x74c097917, 0xe28cc262d, 0xbaade0e72, 0xcd2c4bf29, 0x8f260f0f2, 0xb79a1c447, 0xd2c678b9a, 0x5e0bdfab6, 0x864e33a2d, 0x40f61606c, 0x98fe57ec2, 0xe5da0f7eb, 0x783f9deb3, 0x072df5394, 0x2f704930b, 0x4565eb5a9, 0x0f7874274, 0x6ea0dd876, 0x9e3512377, 0xab52d8f50, 0x2f14a5f04, 0xb6e2d5c39, 0x6e1381091, 0xe73def6b2, 0x93a582d99, 0x2d8eab3c9, 0x0644f57a8, 0xa408c777b, 0x0a8311907, 0x41cc9974e, 0x6a40a6aa3, 0xcd43b9a48, 0x12cd907e7, 0x54ae76fc1, 0xb532f10d5, 0x6888f2b8a, 0xa349b1bb8, 0xb2b458244, 0x75118dbc9, 0xe686a8ea4, 0x3e5d3191c, 0x6702f804f, 0xb3deaf978, 0x931ff5969, 0xb06778791, 0xe81472d94, 0x3178f34d6, 0x70a987a41, 0x5393bdff7, 0x8add45e3e, 0xf5323996d, 0x19fd566fd, 0xf1ecbbb64, 0x13a413ec9, 0xae2268093, 0x567d989f9, 0xcbff16a55, 0x246acb067, 0x8b48879af, 0x929a68539, 0x4d7403f56, 0x6aed4015c, 0xb82c6a241, 0xb10c42a95, 0xb4b53305a, 0x4ac3b1ce7, 0x2722ec68b, 0x20c9a9e57, 0x493db71ac, 0xeb3fa52de, 0xe8f2c582b, 0x32258cb8f, 0x89fc15607, 0x96213de8a, 0x297f6a8a8, 0x6bf57cc1c, 0xb559fd35e, 0xc0868788b, 0x09eb07fcd, 0xc0e9fa047, 0x076c6f13c, 0xbf008cd50, 0xad1f1cbe8, 0x60d890e59, 0x98e8fdc18, 0xf21b971a2, 0x05f612d6b, 0x65503574b, 0x2e9bd949e, 0xed1e65480, 0x1cb299f81, 0xc164da322, 0xfc2599350, 0x88c710d7e, 0xae27596a8, 0xa0adef6c8, 0x8b1bbfbe6, 0x9a22f3ab6, 0xa6481c339, 0x4ea34cc9f, 0xcb76ab885, 0xb0521e4e7, 0x3b65cc025, 0xbf8b0b795, 0xe9297021e, 0x70c5e6b75, 0x1cca07aa0, 0x0e89b8b48, 0xee2e712f5, 0x0ba7ad4fb, 0x21cf08b77, 0xeec39ce8f, 0x6194c8c7c, 0x63544bf4a, 0x045d9bd26, 0xfd6f2d958, 0x5d2cc2af4, 0x8cf2b09d3, 0xcf68c2d47, 0xf218b9402, 0x7d5e2031e, 0xa2293d0ae, 0x819c3c47d, 0xaa73bbf8e, 0x14c8afabd, 0x673e94057, 0x6ef3e739d, 0x4eca58f28, 0x536be7843, 0x06c1e92f8, 0x44f9df50d, 0x4ff4b065c, 0x075714e92, 0xee4dae1c9, 0xb4b7468cf, 0xc0dc6f152, 0xac42dd9c6, 0x799ae449a, 0x08ecae137, 0x69a2e1629, 0xfd32c7425, 0xb431b949f, 0xfa82751b6, 0xe553b7e90, 0xd529fbc41, 0x457c8eb9d, 0xac2892107, 0xb034f4e88, 0xb7ea481ce, 0xd90c74999, 0x903d1fdf1, 0x73590f785, 0xf1250c6c1, 0x03a377778, 0x751892a53, 0x83bc54167, 0x8c388c425, 0xbf75b14eb, 0xc3821426c, 0xb5d6f0eae, 0x249bb9f1a, 0xe5ac7d4f7, 0xdebe0f129, 0x5b5fb4931, 0x07f9013f6, 0x54d4b8d1f, 0xeab94d983, 0x28f143b98, 0x6b6755f0c, 0xca0262d29, 0x85712a2e0, 0x89af4643f, 0xa7ef675bd, 0xb7285486b, 0xc6f66d6b3, 0x2dd429ffb, 0x9f49452d6, 0x396426ce4, 0xdeb361fd4, 0x4219e7735, 0x0debf36ce, 0xe4b8d07b6, 0xb8402fa95, 0x73e0b042a, 0xc8d52d855, 0x16145793a, 0xd15165b13, 0x1a842ce77, 0x5329c57d0, 0x27a1f3a50, 0x0abde33e4, 0x82309daec, 0x396148f44, 0xda6a98d20, 0x8eeaf1f09, 0x6394d9567, 0xacc7a08cb, 0xd59f203dc, 0x9d64c95f4, 0x5f9045b9b, 0x3f0344f6a, 0x1035f53e1, 0xd9e50b8f0, 0x74635faba, 0x7248393e5, 0x25cff4278, 0x590d1933e, 0x6407ea48d, 0xa306c561a, 0x1b4064c9a, 0x715f397f9, 0x6a3f1204d, 0x840f5dc8e, 0x6350a3c7f, 0x12fdb516f, 0x9ed847c25, 0x38f329633, 0x5a470f1dc, 0x4ccda51fc, 0x666c37a5f, 0xc2e44edf2, 0xf6e858e30, 0x6517f6302, 0x53f59bd5d, 0xba6fe5ee9, 0x25bd77d6e, 0xb4dd8862d, 0x439a26730, 0x85acc62e8, 0x56adbd381, 0xb3ecb968c, 0xb0a73b883, 0x7b1d36d0a, 0xa3f4b681b, 0x02c17ca16, 0x98a61167a, 0x57ef825d4, 0x79436817d, 0xd119f0bf5, 0x4669b5873, 0x0fb5595c6, 0x3fad00883, 0x3c6782a7a, 0xdd70d2856, 0x18634ac62, 0x235e1bdb1, 0x831bb0f4d, 0x8edd67014, 0x0657f0ad1, 0xa41bc2aa4, 0xdeaac86f4, 0xdbc8bd0a7, 0x75b1e56d7, 0x51adad8bf, 0x5a5b9ef5b, 0x6efcffa9c, 0xbbd8b73c5, 0xf2f085e2e, 0x1edbca36a, 0x494113d6b, 0x1635a8083, 0x1ad73699e, 0x038d52fa3, 0x8b29c98fa, 0xc5b8cf54a, 0x67babd67c, 0x76c1f154c, 0x7b31c6a89, 0x2c6ca1e69, 0x25e97560c, 0x7a7a8027b, 0xae1b17afd, 0x5ef280721, 0x969f7ad24, 0x4e01df55a, 0xb47c296e6, 0x8d642cea3, 0xee4c19773, 0x1a375dcaf, 0x46b7cdd85, 0x4e3b67ced, 0xa8669f5cd, 0x1eaf025a1, 0xc9f40d909, 0x896f37c41, 0xe46154499, 0xeb894affa, 0x01b0a6676, 0xaa3d903ba, 0x286cffab2, 0xd944686d6, 0xeb911a3af, 0x4029f43d3, 0xc111850ef, 0x5ea39dce4, 0x4eab9ae73, 0xd083fab30, 0xdfc4b7193, 0xab6509d4e, 0x1d3d977e5, 0xc9a52aecc, 0x957736e65, 0x95daa9621, 0xea0841ad4, 0xa859146d8, 0x0b8de0a5b, 0xf252c09b4, 0x8172d1273, 0xb88a9fcdc, 0x6993c1cde, 0xcc96d4c83, 0xd1ff48516, 0xb1408e507, 0x097a8973b, 0x7496621e2, 0x03b672aa1, 0xdc3b03aa2, 0xae3498e91, 0xcf250c27e, 0x6160b091d, 0x96c0cb46d, 0xced13822c, 0x26d97a082, 0x8fda2c454, 0x9e85bcf1d, 0x689845be8, 0x06f143755, 0x9204f1293, 0x1d4a581af, 0xbee8d3b25, 0x8146094aa, 0x349c0af5f, 0xb1a8f22d8, 0x774ba5a66, 0x6ce6004b1, 0xf450bda2a, 0x930d2dd53, 0x68e16cae5, 0x8b91631a0, 0xb3d3b7117, 0x666aa3009, 0x5fadee019, 0x9de5e422e, 0x58bf7fc4b, 0xd52f6c075, 0x13fc8de24, 0xd6eeef343, 0x364911d23, 0x2d713665e, 0xa9e8f1e3d, 0x84c231ca6, 0xd9e8684af, 0xf72feb2d7, 0x5ea2d37b9, 0xfc66a578c, 0x812110a96, 0x936dc276f, 0x84fbba439, 0x17f67469b, 0xb7481055e, 0x96ecc8d0b, 0x8d7fc1aac, 0x0ec2f5bcf, 0xc24ab0a62, 0xd1839dd10, 0x8fd470914, 0x6cfa90230, 0x205091ce5, 0xdaf874324, 0xf15958133, 0x1158fc57f, 0xf0cbfb94e, 0xca17718c7, 0x18b2ac4be, 0xa92ecd88f, 0x228af528e, 0x774db92db, 0x21fd98aa9, 0x8e7582062, 0xbb59648f4, 0xfd9dbd88a, 0x389035c96, 0x1114c6c97, 0xf49428de7, 0x669e6fc5c, 0x1dd6ea469, 0x882bddf98, 0xfed7b3728, 0x25309a3a8, 0xb04c1729b, 0xeb3e8f6a7, 0x7468cfeee, 0x1a1b7d99a, 0x3eb4e134c, 0x43566fc67, 0xb1e97f8f5, 0xdb562afa0, 0xedd496057, 0x5ccb184a1, 0xe3da32613, 0x25ecd21cb, 0xdedd008f1, 0x45ec76617, 0x73fab05dd, 0xb2645fbd0, 0x78cdf82d6, 0x66e4b8db9, 0xc83017e45, 0x86b2a3e27, 0xc6dbd66e8, 0x00b395b2a, 0x1c11ab65b, 0x888994c14, 0x111ea98c1, 0xae86d848d, 0x54c6e271e, 0xb13ef9ab1, 0x2ed93d60f, 0xa4efe7205, 0xe70286dbd, 0xd2cc67ded, 0x2b0663021, 0x95f851a9f, 0xf67ccbbb3, 0x267c42225, 0x2be4b5ab8, 0x8a7fc28d5, 0x0e418f889, 0x1a34fed2e, 0x65590273e, 0x574a6cbc4, 0x3e0f4cb1d, 0xb7cee6cd8, 0x5627e4845, 0xadfe6d2bd, 0x568b57001, 0xd4ec7fad7, 0xad3f576fa, 0x497d2eb92, 0x0fe6c7298, 0x16161faa3, 0x16799225f, 0xf30a85fe1, 0x52f9d455b, 0x130a2a42d, 0x598c9f522, 0x78c55e9f6, 0x7646c5b65, 0x7a53288e6, 0xb2c707e61, 0x134b81f75, 0x6d76b9855, 0x78a343d82, 0x2e4df469f, 0xf89236748, 0xf57e71d1d, 0x10dc8784e, 0x70fd8f1a6, 0x937bcc483, 0xf4c72b50f, 0x10ba6cbda, 0x077f1ed59, 0x66d941739, 0x04ceccaea, 0x015795903, 0xe53a6a20f, 0x3999bbaa0, 0x1281bf25d, 0x7337f274f, 0xcb40345a5, 0x68d24d19a, 0xd2fd56ca0, 0x0d30b94e9, 0xbb57cfe9e, 0xd74b11569, 0xe2db0e252, 0x5fe026216, 0xb47130e85, 0xfe076a9a5, 0x9415e9632, 0x3367854f5, 0x50af0831d, 0x49f25332d, 0x7739a837b, 0x099f36a43, 0xc8537be03, 0x3e06b323d, 0xf9a733bd2, 0x312a441ac, 0x335508feb, 0x7db227a83, 0x3ebb1bcab, 0x7a1106873, 0x5486d3f20, 0xa1628b849, 0xb64543ed2, 0xe293fabca, 0xd1d512de1, 0x47884a21b, 0x4a406b83f, 0x7aa35466d, 0x6542ddf69, 0x348c210e9, 0x2aed60aac, 0xe9d35f24a, 0x2bbc14dd9, 0xf2891fc9b, 0x72a9cba3f, 0x409ecd462, 0x712ba02b9, 0x1b149ab0f, 0xaf6b65883, 0xf68306512, 0x20e84ff13, 0x88beaabb1, 0x7456d2803, 0xa04216d3f, 0x83f33226d, 0x394a0eb38, 0x65670c452, 0xa5903ed13, 0x473689a3e, 0x142b1dd56, 0x53bf24a7d, 0x88585a655, 0xe62c824fa, 0x1bc6257dd, 0x266d228da, 0x9d18f806a, 0x26a6ab06d, 0xb90c39735, 0xd844f8c09, 0x4ebf14fbb, 0x5c720772e, 0xe033d46e2, 0x2d72fe7c7, 0x11878c4b1, 0xa075e3992, 0xf4dd045d8, 0x9caad8759, 0xf5b387cba, 0x20dfb6633, 0xe7511e0ee, 0xc3e9e1225, 0xf6d332299, 0x43aee9bc2, 0x4882318bb, 0x958fa25c2, 0x6c9dd71f2, 0xda71d12bd, 0xead515c9f, 0x5622a7b24, 0xb1a220b61, 0x5e3b6d626, 0x95533c08f, 0xaf093c411, 0x364a0f961, 0x6dc550b86, 0x43cb48cf6, 0x01331bd0e, 0x55926d59f, 0xddfd98223, 0x509d0ac32, 0xdd3e82660, 0x72f15dee6, 0x114a5ba53, 0x70d637811, 0xbf7172408, 0xca9dfc935, 0x2b082b18a, 0x9e227de74, 0x084d8797a, 0xd91cc5635, 0xd9b9c0584, 0xe6a5cdd7f, 0x606567f3a, 0x30121d876, 0xed40680fb, 0x9e498a0fd, 0xf6e6f7aed, 0x7bd31c1d5, 0x7fadc5b78, 0x430399853, 0xd6937f64f, 0xe9755cec2, 0x336f0919e, 0x62d953c76, 0x6eccc311b, 0xa7725ba74, 0x6b2ba1f0b, 0xd9c680f4e, 0x0b4bf20fb, 0x7d247fb92, 0xe2dfb415b, 0xaa41eabb7, 0xdde282439, 0x19cd98b9b, 0xc169b393e, 0x7057af26b, 0x621760313, 0x091e4f51c, 0x712e3294d, 0xba60f9cb1, 0xcac43e693, 0x49ba92d03, 0x3ec790f69, 0x6b4fd03f4, 0x1753f131f, 0x140e73516, 0xb235b7ca5, 0x1d27a6723, 0x3102222ec, 0xc0b75e745, 0x3a1b554f9, 0xc313dc962, 0xa323d6c80, 0xccca0aabe, 0xa61580a37, 0xea4b16079, 0x6b2ad79e0, 0xb766b661a, 0xe22f727d7, 0xe4304d5ed, 0x24376523a, 0xf853f00b3, 0x6592be5e4, 0x553748fb7, 0x6852aefbd, 0x73e2abca6, 0x5fb45c08b, 0x635d4c650, 0x0e0d2be1e, 0x60ee51f29, 0x38ddb7390, 0xa300f1ae1, 0x22efe44a7, 0x628bba583, 0x4b17ecb5f, 0x55c6b9011, 0xe1a14bac7, 0xe427b3d0d, 0x46100dce8, 0x04cc2245d, 0x84c2e41d8, 0x0919dcd26, 0x8d1d01822, 0x2e26515fe, 0xf7ab7dae4, 0x7768b70cc, 0xe94913f18, 0x0f3e883dc, 0x3b8d3f0d4, 0xd67ea41c4, 0x99d477e9f, 0x3fb10f974, 0x02a370e93, 0x17768adb2, 0xd6329f527, 0x3bbc1a712, 0x1b052fab8, 0x1a4619ef5, 0x00b725dfc, 0x78f0c547c, 0xadbbb4432, 0xe1cf5cbda, 0xd70644e69, 0xab4cb9d0b, 0x5fcd12ef4, 0xe396af25d, 0x2d9ff9ca3, 0x4ef3df84c, 0xc7ec94a8f, 0x6b18da2f5, 0xa63d0badf, 0xf91662835, 0x3410a9ff6, 0x7ed13b24a, 0xf95f89732, 0xce74b2901, 0x695679287, 0x4843eb226, 0x5a66b2ed6, 0xa86cc1f33, 0x16d5e7b98, 0x748025a14, 0x3397dd590, 0x7bafeb92a, 0xb45584283, 0xd54dc6a25, 0xaf2e68538, 0x220f32a8f, 0x44f8b18dd, 0x51814c91c, 0x8bb4af165, 0xbcd6adb56, 0x82e4a2e55, 0xcd4990ca2, 0xef32a23e5, 0x688ec9de4, 0x2aba4638b, 0x16f7382e1, 0xbdfe274ea, 0x2164acc4b, 0xaad044fda, 0x64559f29a, 0x5a9c9339e, 0x6a0739a2a, 0x8f993b732, 0xa90de3f6c, 0xace88d90f, 0x36a7f9cf0, 0xdbef65c2b, 0x69bb34d8d, 0x6f095cd61, 0x3bdbd6405, 0x34600b852, 0x0d1e24fe6, 0xcc994f31e, 0xccfcc1ada, 0x106b721a4, 0xad3e751d6, 0xab0903242, 0xb60ba3746, 0xc5b7a191a, 0xc7da973a4, 0xf45b0747a, 0xba92e67a2, 0xb93ea5045, 0x011d2ac4c, 0x564361455, 0x420d42485, 0x47e0f7889, 0x110a80968, 0x7a3cec118, 0xd058e2ed7, 0x1dc9c639a, 0x42de0a027, 0xe5530907f, 0xaffabd8e4, 0xb08fe947e, 0x5ba33b408, 0xd5f80115d, 0xe6298c761, 0x893b86708, 0x85b1d3017, 0xf2ac6bc60, 0xfa9378384, 0x3f538c40b, 0x21b0661dc, 0xe762b80d4, 0x16f6ecbd5, 0x1264fca24, 0xf39f4e476, 0x51cc3b982, 0x757c9f748, 0x311d200dd, 0x2563393cb, 0x1b05631cb, 0x9a547cea2, 0x35fd287a0, 0x25460fd6c, 0x8d4e23de8, 0xd56e01537, 0x4714d5bf0, 0xce7f93169, 0xf16142c02, 0xf88939763, 0x42b49ee1d, 0x8495855f7, 0xade7e53e3, 0xea99e0abd, 0xd5a4abf2a, 0xe8868979d, 0xde8c25d59, 0x24796f2b4, 0x588d17a5c, 0x23446aa2b, 0xd7930a836, 0xa1ad628b6, 0x8502da9dd, 0x1abd85618, 0x044a252ff, 0xd33f9442d, 0x0711e508d, 0xb8548f822, 0x9298a3af1, 0x397d78086, 0x26d522fa6, 0x744606469, 0xab2c1baf4, 0x24568a115, 0x233bd114b, 0x68f7612c8, 0x391ef6edf, 0x03c6ab744, 0xe248dbb72, 0x7511dc9f6, 0x53309a668, 0x5438d7128, 0x57e1c76ed, 0x61c9aec27, 0x4b1219026, 0x6d5e9cf25, 0x2242688ca, 0xaa10985ff, 0x8454ac8ce, 0x23a648791, 0xb8d396be7, 0x482d2fc39, 0x62fde8f85, 0x84bd1069f, 0x1aa1a5303, 0x434f3adeb, 0xc99f3f39a, 0x744f1eb68, 0x9cd2ca627, 0x472428c4e, 0xdbacacda0, 0x310c6bd3c, 0xa84d6d066, 0x6ba340d41, 0x7aaa74c11, 0xe21d5d0f3, 0x8e84f07da, 0x3b260c654, 0xdb704686d, 0xf197a1ee9, 0xcb4e599d3, 0x2c67ff681, 0xedaa7c03c, 0xb859ffc56, 0x320eeccbc, 0x8014fbd19, 0x32e57039e, 0x5e196e0cc, 0xa02c0dc84, 0x29f06b67a, 0xe48da0b64, 0x47f4262c5, 0x3abc13e2d, 0x57afc2c03, 0x9437d42b4, 0x57f8e9b00, 0xd0644255e, 0xb9f0e2245, 0xf68892060, 0x11b4ee7b3, 0x26f34a243, 0xd92e92d2e, 0xc3c36f4d5, 0x057a6bc86, 0xc1e1d1593, 0xf36f11af5, 0x926cd9966, 0x66fc75705, 0x6cc85b754, 0x373e56bdb, 0x9a7322f5e, 0x948cf1650, 0x11f57bdd0, 0x662314283, 0x8e2901cc7, 0x9a5dc8cb4, 0x3b6718a90, 0xfa4d1722e, 0x19d6cc9b4, 0x0fa2e07dd, 0xe0483446f, 0xcee973997, 0xcab326bed, 0x8653a7582, 0x07d8331ed, 0x916db55a5, 0xac0cb5513, 0x445d66afe, 0x265e9d4c8, 0x543b1e0b0, 0xfc6c649ed, 0x02a38c5ad, 0xae31be812, 0x46f85eac3, 0x38b531dcb, 0x046cf24a5, 0xf77637b55, 0xf07d1c632, 0xe05b2f798, 0x10d5860e5, 0xe42b2bfe6, 0xbfc381a12, 0xad645382f, 0x762a6a152, 0x58336fed1, 0x5c88f9b4f, 0x64b15ddbb, 0x9cd938699, 0xf3c6c1525, 0x2362c53db, 0xd40874c21, 0x2fc1763f1, 0xfbf6f4b46, 0xe9fb3911f, 0x692346b6d, 0x52e96efe7, 0xbe0d16e43, 0xcd144ad13, 0xd497e4c7b, 0x280b58b80, 0x443ff1d93, 0x2f528c5b5, 0x3ef6bb3d4, 0xb806de136, 0x9600a3394, 0x0bdae6a57, 0x7ac6bbd4c, 0x17364c5c2, 0xec5344b46, 0x0bf745b8b, 0x72718fd17, 0xe2fdab406, 0x7cc4b8dc2, 0x4f5379d4b, 0xde49a05e1, 0x5e9c05763, 0xed58a3866, 0x80535dac8, 0x6affa7d8e, 0x4e7f09ede, 0xee0a2e534, 0x7519486a6, 0xf9b9680f1, 0xabbb28449, 0x5a2396946, 0x7fd4d5522, 0x542319779, 0x3caf4bd55, 0xfd740a695, 0x68c96b8cf, 0xab1593c1a, 0x42b1dc797, 0x4acaa2299, 0x2e27e9775, 0x4f157edc2, 0xb068ad203, 0x437ad4f84, 0xb8e9d6ad6, 0xa6439526b, 0xbfe227ace, 0xd32f46eb2, 0x404bfa76f, 0xb7beb4e77, 0x1874e8369, 0x879d23b91, 0xd9bf340d9, 0x714131397, 0x16a00adf1, 0xb9b9d414d, 0x2631bd706, 0xa2a978ee5, 0xe8fa34bfc, 0xaf9d55a95, 0x70a649cbd, 0x754fa798d, 0x59cf771e8, 0x6814b7755, 0x36efdafc4, 0x305a3225d, 0xadf19801b, 0xa38bf2a66, 0x44de6973f, 0x62f4a0894, 0xcf4a6f1d9, 0x0b358593b, 0x18583db29, 0x2891984e2, 0x7702e90b0, 0x91a1e901e, 0x64ff5e2d4, 0xbf9da6ada, 0x02e26d17b, 0xf89c04a9a, 0x4b43a2412, 0x31de98342, 0x28c287395, 0xc3362e40a, 0xe5bc3aa9c, 0x9e48f6a06, 0x733435bac, 0xa43be8cde, 0x5c653248c, 0xe2931bdc7, 0x02c4795f1, 0x62bb96f20, 0xb2f43a171, 0x19d1f6ab9, 0x433ea2164, 0x137da589a, 0x28fd58e72, 0x202d4cb62, 0xf03d74c5a, 0xf6112a05e, 0x1527ce8be, 0xd27556017, 0xf1bdb3c55, 0xc081699a5, 0xd8368ef11, 0xa1ed747d5, 0xd833b1171, 0x2e161f79d, 0xf2d7a26f4, 0xffb902d9a, 0x6c62a5731, 0x914cff395, 0x849a7a32d, 0x787d20e5f, 0x873080cdd, 0x902f6862b, 0xa2ef2b22a, 0xbc6ba2e19, 0x27fa8c7e6, 0x3b7964fa8, 0x99d80b892, 0xa9d7ddab8, 0x0e6dabf62, 0x19b1a3fae, 0xdabcaba4b, 0x465086a2d, 0xaf9290947, 0x3f16139c2, 0xf5eb1ba13, 0x5be4c9d84, 0xb491d5ede, 0xecb1e1407, 0xe2bf4cd78, 0xe9ba7bb10, 0xbe6954783, 0xd3a7b0213, 0x50de815b5, 0xddc150b2b, 0xf83e35e25, 0x06bcfeb25, 0xd446be9d7, 0xb8f07825b, 0x0938b9c16, 0x5dc6e6ae5, 0x3d8adc166, 0x6deae71f4, 0x748581570, 0xf2d14fd9c, 0xde56fb4e4, 0x23852ee7c, 0x7663771e7, 0xac04e987f, 0x10c77faf2, 0x84f4bc3f1, 0xb54fd5e6a, 0x5b315ef54, 0x60cb8bbc5, 0xbd8cc9e55, 0xab5f55050, 0xdddd64553, 0x6cd38ade9, 0xf0f5ec7b9, 0x96da53643, 0x3bb39fc6d, 0x2b2884ad7, 0xaa26a84fc, 0x8a2bf56c5, 0xb68a4ab27, 0x4962ea115, 0xd4f9472e3, 0x975e4c01d, 0xa82cd2570, 0xb6433749f, 0x7234ae0e6, 0x14cbc7db2, 0x22d77fb8c, 0xac098f788, 0x7762cecbb, 0x2e715f49f, 0xa529f55f9, 0x935054846, 0x999c0c185, 0xf6a94f0b2, 0x6bdec8471, 0x290d12cf6, 0x73b35868b, 0x5e9c08e84, 0x35d427add, 0x4decbf805, 0xb1218bb88, 0xcf15a8069, 0x44d59fe6d, 0x48cf866e4, 0xd85fca129, 0xa81c1e1cf, 0x25be310e2, 0xe57ab2f62, 0x22c1da1d6, 0x6a2a71117, 0xd60d2eb36, 0x3f3f9a2e6, 0x6d1c1aece, 0x9b831a4fb, 0xd64ba88de, 0x968db7b8e, 0x073910151, 0x3e5d9f584, 0x8fdae57c8, 0xb0cb58bb5, 0x8bc3d58f2, 0x01188bb85, 0x226c7172e, 0xed7f67b04, 0x63c7caad8, 0xf6768009d, 0x06e193e34, 0x2021a54f0, 0xd4437d532, 0x82ce066a3, 0x260bfdee8, 0x26b0c81ec, 0x081503c67, 0x18be917a6, 0x3aac944fe, 0x5a91ed08b, 0xd93c3ca5e, 0x4ba9f608f, 0xf9d10ca44, 0x314c4dc69, 0x8acfdd4a5, 0x69e73946d, 0xa103f94eb, 0xe708b0565, 0x4ebcf058f, 0x3385e6ce7, 0xdbbc1ec39, 0xd13c2ddc5, 0x3df56eec6, 0x50fe589c2, 0x5e7f91d57, 0x411dc3670, 0xa1785375b, 0x8d710fdc9, 0xe767b052b, 0x950939ab0, 0x7b7767c17, 0x5d24ca58f, 0x409e70b9f, 0x02d1bc4fb, 0xddec53eac, 0xa05158be6, 0xb64eca239, 0x88794e4db, 0x815926d2f, 0xa109e873e, 0x87b47cdd8, 0xc48d8473b, 0x4a2e11891, 0x355819bd2, 0x23f9590fa, 0x95a7fcb68, 0x325115b71, 0x42d0b9687, 0xc63bd4849, 0xe6d873be4, 0xf48b66357, 0xb29fd2a28, 0x5cafd9507, 0x09b467b3d, 0xe2dae50a2, 0x0ba7b7a5e, 0x4b2172ec6, 0x49795d717, 0x6c9495943, 0xd257992c1, 0x96d7c46d0, 0x0266ae09d, 0x241b28662, 0xc1ee98d9f, 0x50132d568, 0x07d90455a, 0xc2e459355, 0x42bdf1a71, 0xc662953c6, 0x4cfdd40e7, 0xd5fe2a905, 0x5339ed2bc, 0xc9603561c, 0x47c64f707, 0x8110b2364, 0x1b3b324dc, 0xc665f1f85, 0x74299617e, 0x4216c87ec, 0xc675906ef, 0x2dcb4f572, 0x6fd55584a, 0xa0c4d0932, 0x19ab0966b, 0x883e192f9, 0x5fa021f7b, 0x266d2ce3d, 0xe90bba30a, 0x782bcabc9, 0x6d40981e4, 0x5b98b080f, 0xc21fbb365, 0xc574d78d8, 0xb2b236f39, 0x80cb66e45, 0x669c9a05d, 0xbd6808275, 0x21f8e510a, 0x437ba62f1, 0xc5224cbd0, 0xcb441a4e6, 0x59aa067f7, 0xa9d51eb53, 0xdc294402d, 0x33abf8a53, 0x2bc9dd944, 0xc3f8742bb, 0xc72b75bba, 0x17cf5a97c, 0x08f42434a, 0xec593abdb, 0x120a797b7, 0x6cdc8ec10, 0xd0a686b2d, 0x81a4fb9da, 0x44facf6b5, 0xbec238c25, 0x6c12019cd, 0x1aac292a8, 0xe88bd0a21, 0x959a41c81, 0x432c2ca9c, 0x6c0b7b962, 0x385867bd6, 0x8068a6bbb, 0x09a777181, 0xc27d59fe8, 0xa04074853, 0xa50631657, 0xba7b37ada, 0xd9872f1e5, 0x949f449aa, 0xd2aa72df6, 0xbcc9608d7, 0x93d9a8d7c, 0x5e5495818, 0xbc9bce5e3, 0xc3875ec11, 0x97ea32be7, 0x41c5a2548, 0xe64df88c0, 0x2e21d1372, 0x0630736ad, 0x226cdbc75, 0x609746f95, 0xe7cd6d390, 0x3ee9d185a, 0xd8cd3e34a, 0xab785e407, 0x93addebf1, 0x854b75025, 0x26f1bfd50, 0x598394aa7, 0xdfdb6840b, 0x6ea7a4c78, 0x6b4faa965, 0xa7aaf424d, 0xc694d0ce4, 0xfdab0acf7, 0x582738889, 0xb30ea7f8c, 0xc1af8b900, 0xe26889dcf, 0x5ffd11ded, 0xf6b05ad7e, 0x35cb9503f, 0x8b86f73e2, 0x8d467a6b0, 0x91f7a7735, 0x214693632, 0x106d5ff8a, 0xb9cdef610, 0x3dfafe135, 0x0fa5b0ae7, 0x26cd7986e, 0xc6fd681c8, 0x6b4188c58, 0xa3ba597e8, 0x85f518945, 0xf365a0254, 0x2048b85bb, 0x0f3dcbb35, 0xd3e5031cd, 0x54de45ec8, 0x2af3dc7a2, 0xe08932e15, 0x7734ac9f1, 0x322d852e2, 0xcdbdf8b96, 0x806696a67, 0x8cd4e61e7, 0xe057f8856, 0x4d9e9613c, 0xb82f25c73, 0x93c8c49e9, 0x7aace1816, 0x646f619c5, 0x6aae5893a, 0x84d48be42, 0xe4a98eafd, 0xd7f42bcf5, 0xa8017604d, 0xcd715d0e1, 0x11abe3d38, 0xacd8e4e30, 0x623790ab0, 0x39f25ed99, 0x8aef091c2, 0x7a2574284, 0x108cb8578, 0xd7a2ea337, 0xf13e9edfa, 0x5a80a8d14, 0x748f6e6fd, 0x1e4ba118a, 0x546ce5112, 0x1703a322a, 0x894c63e47, 0x3f403b661, 0xed4d06757, 0x5b9902d5d, 0xdf86cd5af, 0x1ba88e704, 0x4f148ee08, 0x1eb0dbaaf, 0xb377d99a9, 0xf480a804b, 0x477b4f4ea, 0x0a9c8c047, 0x7e4c0a8cb, 0x4a89583d5, 0x6fc78608b, 0x7b59965e9, 0x7dcaa4585, 0x4002e14f6, 0x14c436673, 0x98ed9cecd, 0x092ad5b7f, 0x19088d131, 0xdec2ae3de, 0x3ac6ea320, 0x4352c0d48, 0x47ad3bfdb, 0x469a523c6, 0xf529ccb4c, 0xf663c29ea, 0x9a225604a, 0xb71dd41d5, 0xee5201d72, 0xd06cb9ad0, 0x91b427aa0, 0x7ef2d044b, 0x61bfdd3a2, 0x33a4184e7, 0xc875c3536, 0x5c5e6e999, 0x8fb237053, 0x2143558ae, 0xe77b34bd6, 0xe5b1047b3, 0x729ad8bb3, 0x9d2efdbf2, 0x6a5d1a69d, 0xeab0c8b69, 0x24ced1108, 0x9488901ff, 0xbf910f4ae, 0xf89e416ad, 0x9eb3973ea, 0x9fac35740, 0x1fc51212f, 0x2a106be25, 0xcd5bee55f, 0x4b78e174d, 0x231194dc2, 0xf094cec09, 0xbc94ebcb5, 0x9980b8913, 0xe6cca33c2, 0x4bcdb33dd, 0x1a6f4e4b9, 0x097ead2f2, 0x6f4980025, 0x7b9d83ee6, 0x61ab1d631, 0x522dfaa9b, 0xd58e68b08, 0x6dd894088, 0xa43851db8, 0xdb3da4317, 0xf1d8108b9, 0x0257b43cf, 0xa36dc4b75, 0x586b118ae, 0x4d292d0d7, 0xd5dd7ec58, 0x2961da611, 0x8e1eb4d44, 0xbdaf4157a, 0x783587d64, 0xb89073a03, 0xf2a98a98d, 0x8e6e953bf, 0x82728c63a, 0x08cf515b3, 0x192019a8b, 0x199feb37b, 0x4747d4de5, 0xbad74c26a, 0xa3eb1f4eb, 0x3a3fe72d5, 0xa24fca706, 0xac295c820, 0xdf8707b04, 0x240d933f8, 0x40d3afeda, 0x08967b352, 0xdb5908f2e, 0x0eb77e73d, 0x55e3af14b, 0x7e2af46d7, 0x2ad8069f0, 0x1c94d9cf8, 0xad3fd6707, 0xd527d05c1, 0x0e9661707, 0x5434c8225, 0x8b17ffb10, 0x6f4bca6ce, 0xe3d99b9e9, 0xb3f192e96, 0x4fe4ae9db, 0x3e986a40d, 0xabebc86bd, 0xacec35dc8, 0xbff455399, 0x34ea8a485, 0x5c603d944, 0xf9228c5d5, 0x630b74068, 0xcc087e16f, 0xdcded3a77, 0x18e36b56d, 0x745c5e53f, 0xe54b21ebf, 0x8d71bb6a7, 0x804669bd9, 0x78a8843b2, 0xa841aa4c8, 0x7c1721cb9, 0x9a83406d5, 0xa896c7864, 0x04bb0aba5, 0x3c11533b6, 0x328444d58, 0x39bbda023, 0x8b36424c7, 0xf6120c770, 0x185bb28cf, 0x28319aacc, 0x44125fc8d, 0x9bd0b06bb, 0x77e3e63c2, 0x92cc0d22d, 0x6471ce5ca, 0xa5cd27974, 0x821216a59, 0xb44bf0674, 0x91c306242, 0x59ddcc7f6, 0x8a49cdd23, 0x4126a5129, 0x5dae47e63, 0x5ae91a769, 0x1167709c8, 0xf72905476, 0x7f714af5b, 0xe1156f64e, 0xf043af7a7, 0xda86cb771, 0xefe9556ea, 0xe93191d0f, 0xc57680df4, 0xd6731845a, 0x40a0357d5, 0x369846e9c, 0x55c37b47b, 0xc1a35b0fa, 0x53ac7be90, 0x85eb470c0, 0x3181486da, 0xf0e227153, 0x324271b12, 0x87850744f, 0x2e2d754b1, 0xe6eb202ce, 0xb0704c7b4, 0xa67db8125, 0x711fb0e4a, 0x37c2d1ce3, 0x6aea9caff, 0x443334cd8, 0x69e4738b4, 0x0d0afd5da, 0x9ab6c533d, 0xcca49a2bb, 0xc4d4fb6b6, 0x0e4b2ddd7, 0xda2509125, 0xe9c86da19, 0xc7274b59d, 0x2f4bbe74d, 0x96ac2a725, 0x1f30d673d, 0x425fd41bd, 0xa575e248b, 0xa41df8a63, 0x850967a78, 0x580a6f3fc, 0x3e7fa23ed, 0x77d9a37b4, 0xaac2f4828, 0xd5afdeece, 0x463bfa5bd, 0x8d8c594b4, 0xd5c3a4722, 0xc26bd81e9, 0xa25f27cc7, 0xb0a959849, 0xed63242d8, 0xf2a5d4c2c, 0xe55b4628a, 0x0b2dd55af, 0xc8738d953, 0x8a7cef286, 0xcc7c48409, 0x043816c4b, 0x85a74860c, 0x48fc51dbc, 0xee8237a9f, 0xdb101fca7, 0xa22651a66, 0xe15eb5386, 0xd43085b18, 0x651931da4, 0x9326a183f, 0x6f8dab598, 0x0e51eac76, 0x6e2623406, 0x9f935c569, 0x99d04350d, 0x2bfb7ef17, 0x9408845a8, 0x36e8c5171, 0x8af933fc5, 0x36ecec25b, 0xc90ec3e5a, 0x84942ea05, 0xfb5493f14, 0xd81204353, 0xd5060ecdd, 0xddfda6095, 0x5cafc4e1d, 0x7754ff6ea, 0xc257672a5, 0x27299bc82, 0x4ca1520cb, 0xe1de3ec8b, 0xfb5ab687a, 0x88f4cc5fe, 0x5c83fac92, 0x18bdce2ab, 0x87fa99852, 0xeafdac7f7, 0xa095e0c0a, 0x1de9110e0, 0xabee689d5, 0x917d79b7a, 0xdb13b369a, 0x56aa3e642, 0xaaaf35e16, 0x9c0896962, 0x32ed98cd1, 0x40befdded, 0x733f9f984, 0xab7ee7d81, 0x38e744727, 0x7501364c7, 0xfd3421d02, 0x8d492864c, 0xb25d6c2d9, 0xb88708fa4, 0x66ca7ea8d, 0x53b061dd1, 0xbfe629317, 0xe48ccc4b2, 0x529e75dfa, 0x02ce3697a, 0xbe76866c4, 0xce03c67e3, 0x3c79ace12, 0xabb5ade8e, 0x5510819d4, 0x1853d91a5, 0xd99655b60, 0x47729ddff, 0x3c8c5ca2f, 0x1b819dd83, 0xdacb0ecdd, 0xbf430f183, 0x829af66d3, 0xd1e2ca983, 0x779105c39, 0xb192af0a4, 0xd5098a6d7, 0x15cb456f1, 0x8481b933d, 0x409d19fad, 0x1f5c2f72d, 0x53673e5f5, 0x65e6a72ea, 0x0527da518, 0xeaddf7946, 0xb2617eaeb, 0x691892fb2, 0xdcd129f35, 0xccb42e6b0, 0xdbc331935, 0x8867aa36e, 0xd7cd26a9c, 0x67a19fdc9, 0x20952b0ae, 0x6026d2e54, 0x98963fbd9, 0xa8b64c911, 0x97fd9f487, 0x7d3c848a5, 0x147a4c27b, 0x18c9cecad, 0x046eb72c9, 0xc88d38085, 0xb25dc1f48, 0x61790445d, 0xc125e5258, 0xfbeb9589b, 0xaecade15f, 0xda4f86a33, 0x6cf66cc43, 0xef65417e4, 0xdc50e0668, 0x8810cbcab, 0x4aafd7f97, 0x6c5c831a7, 0xb83ed224f, 0x64f1a00a8, 0x8db3c590f, 0x68ce5d2c0, 0xfd51258d2, 0xe2c5eb1b8, 0x59df15d2e, 0x700ebf57e, 0x3be89a8cc, 0x47fb46c45, 0xa923c0b32, 0xd88bac689, 0x27683edc8, 0x2eba1f952, 0x7102542c6, 0xd049fa79c, 0xcc0622afd, 0x693120c6b, 0x396461615, 0x2f1f4227e, 0x26b4bbf9f, 0xe8f7a6065, 0xecdf103d2, 0x708691ac7, 0x51941b750, 0xd33cd58a4, 0x95f2d0890, 0x3440d5b9c, 0x00afdca84, 0x625eae2cc, 0x2c36e42d9, 0x3f5f89ac8, 0x5649578c6, 0xbba60ace8, 0xe344ddca5, 0x128c435de, 0x02c52f620, 0x4db779c52, 0xaac4bcb7f, 0xf13e98394, 0x696f9e134, 0x179733908, 0x2c9580b9a, 0xa6f7072b9, 0x3358704e9, 0x7182449f1, 0x86eeb1594, 0x82b9adb34, 0x0ee258afc, 0xe122b5e67, 0x42ed1c2b8, 0x8633f61ce, 0xe8e335121, 0x525874e76, 0x96901dd2d, 0xda22fc8e0, 0xa72387097, 0x4f5d9a9c7, 0x88a87c443, 0x33b056d4d, 0x62d064cf1, 0x5e7c243bd, 0x18213a370, 0xf7bd5923d, 0x815aaa9aa, 0x84aa0b3dd, 0x1ee0819f4, 0x847cf7f08, 0xf120ded5f, 0x9a76c1290, 0x082b32d7b, 0xc8b59e9fd, 0x2d4dff53b, 0x293d29fc4, 0x08701ab95, 0xfd7fab48f, 0xf4cbfe2b3, 0xcbca4906d, 0x99cc8a279, 0x34251b504, 0x89092fc9a, 0x9e1c0ccab, 0xf697de846, 0x055fce443, 0x6b0cad5ec, 0x87923cab1, 0x8b4e2839f, 0x0a44b0122, 0xfb3909a5c, 0xa16fafee2, 0x1778046b8, 0xba9808373, 0x064852931, 0xb79d2dec4, 0x50cb67a1b, 0xbbfb05d16, 0xf0139fad3, 0xccbb36e49, 0xa2cd25458, 0x49343b972, 0x112efab27, 0x53d9d772c, 0x40bda71fb, 0xf8e62647e, 0xdee732912, 0x53500b219, 0x7e47a2a14, 0xe11cd7fb9, 0xfcaca6ec8, 0x6c2da7d57, 0xd93abceaa, 0x01bb3f4bd, 0x67dcf76f5, 0xb5b63e989, 0x5bae6b067, 0x9b6eee44b, 0xb7f96ef25, 0xf4d97b712, 0x930dff68a, 0xa40a96cf0, 0x0d5683834, 0x647e13c72, 0x2a5c63408, 0x395fef00d, 0xb4f5afa8a, 0x017bfe90b, 0xc9042b9b9, 0x2c9ad5aa2, 0x047a51093, 0xea341678c, 0x546838991, 0x09858cac9, 0x6061e2795, 0xce7d6ed07, 0x91b7626cd, 0x5805e4fe9, 0x119b5c832, 0x954f9e8f1, 0x6d1580b55, 0xf43091166, 0x0d5a7e04d, 0xe191d35a4, 0xd8ca15468, 0x0a708b652, 0xcc15b029e, 0xff5aa4719, 0x8e74f9498, 0xf9d92e911, 0x477e5d846, 0x042650770, 0x1e5730dcd, 0xa0e8eab0d, 0xddce6772e, 0x75a090773, 0xa19aa8eee, 0xdcfe9d7ca, 0xa0676c7ce, 0x17197c8bd, 0xa87af55af, 0xe2d1706aa, 0xa43dd708e, 0x26503e2fd, 0x123d37bdf, 0x68c7362b6, 0xea30ac137, 0xb01b70b8b, 0xb8d1315dc, 0x96824e75c, 0x98d141a84, 0x74aa24acd, 0xb4776887b, 0x8fdb27129, 0x70d84811d, 0xcb8b9f4c1, 0xa3a424426, 0xdd2531a76, 0xb29c389ab, 0xbd1835e48, 0x47f3a453d, 0x8dfe4a80a, 0xa4b0a36ea, 0x4e886ad80, 0xe92d00ca8, 0xd7c6efc3a, 0xa5941aea9, 0x161a7aa58, 0x9ed69b98e, 0x64eda938c, 0x5588a6847, 0xd92d4a19c, 0xc9bd66def, 0x95b20c81b, 0x3e9ec0a50, 0xd957e66f7, 0x2251d77fa, 0xa018cb128, 0x50bdb0443, 0xebebfa885, 0x05eb8892a, 0x294e078f1, 0x4c54e34b1, 0xc2ac1a6c4, 0x73e62b579, 0x95d24e16f, 0xd5edf5b3b, 0x9085ee304, 0xaa71ceb4e, 0xa51325eec, 0x2c0bd017d, 0xbf7101a25, 0x78d932686, 0x1bd9f946d, 0x4e18c469d, 0x61b4f9bd1, 0x9cc6aeeb1, 0xf457ec40a, 0x3a54d40cf, 0xf37fd42d2, 0xdca9017fd, 0x2018fb211, 0x0583139a2, 0xed794feb9, 0x2671f2339, 0x0a9dedb42, 0x00a59d973, 0xeeb0e6dd6, 0x27c5e838a, 0x15b92ceb6, 0xfaa9e1dc9, 0x691c2012d, 0xa700422f0, 0x42ce65421, 0xf36c2d8b9, 0xdd3255d33, 0xf16927235, 0xcea8c7ee5, 0x8b405217a, 0xa937cb21a, 0x1972d865e, 0x3dd15253a, 0x8e12c277e, 0x05f4e5ae1, 0x5cc68e658, 0x43dbcda4b, 0xa65e44bd5, 0xc2b21acbc, 0xd683fcfa5, 0x3f6a63ab8, 0x07da47408, 0xe8b12669e, 0x32a0a4644, 0xa9825a29c, 0x49b66fce0, 0xfa9a992ce, 0xd2b5fbfd3, 0x14a5b69ec, 0x74a030eda, 0x8e50a8e2f, 0x0a95167da, 0x80202bd54, 0xe8318bbe2, 0xa3ab33a01, 0xde35c6e5b, 0xa1226c83a, 0xb6c43aa86, 0xedc5e4d1a, 0xd5944aa7d, 0x478a80992, 0x47811cb87, 0xb95d85ffc, 0xe2360374b, 0xa9a9ec186, 0x74de32ca5, 0x04a66a427, 0xd4a65cf9d, 0xd8d75502d, 0x1c3b585a2, 0x795d13255, 0xd451f5854, 0xc70f36267, 0xc29959ade, 0x0c5da4711, 0x32123feac, 0xb7fdbc068, 0xae25f20b7, 0x25e3e6f31, 0x20232ce56, 0x74f543f01, 0x185cda063, 0x97d611476, 0x13f15f323, 0x173612c01, 0x3d616758d, 0x4737d01fb, 0x0d5d33019, 0x259e9f133, 0x5eae970d9, 0x4ac96e3bb, 0x2242e4b5c, 0x118f28ce7, 0x2f7cbf15d, 0x8a7d644e8, 0x80ef8b95f, 0x1be972336, 0xf42d2a60e, 0x42a580066, 0x9a911767c, 0x3a4b9612f, 0xdb0f1bbcd, 0x3ac93c1b1, 0xcfec5c2d1, 0x452d01604, 0x4f3f3998d, 0x8aa4775b3, 0x32fd7c6ab, 0xe3e43832d, 0xe774f08a8, 0x25b8dcf5c, 0xc0f10d6e9, 0x23874a0c7, 0xc7e7c9c8b, 0x6470db895, 0x6a458e8d7, 0x886e29f3d, 0x4b6531365, 0x8eccc4bac, 0xeed4c9f8f, 0x7d0685f48, 0xf6e8b9b96, 0x524d9bc08, 0x8ba35deec, 0x127a38c15, 0x07d5ce1ac, 0x8496b0888, 0x9589e40e3, 0x9f123483f, 0x0a7f03598, 0x57342da57, 0xdbaa17d6d, 0x4c068d8f3, 0xf76ad5b2f, 0xb398e63bc, 0x102afd902, 0x4877b8bfb, 0x790f6c2ba, 0xc7655b992, 0x4e0d5b07d, 0xb02afe708, 0xa8875d3a1, 0x750681812, 0x77a9c79ab, 0x02ad0c854, 0xc5cc6924f, 0x25e9c88dc, 0x877356004, 0xc67444a06, 0x12d72f8c9, 0xffa5a50ee, 0x931d865b3, 0xd5b7c6e10, 0x3d0aa7ef3, 0x92ce0cd5e, 0xa0f27b9a1, 0xd74b04855, 0xac4596a59, 0xa2b5aa65b, 0x88d45ef6d, 0x7294cb8a7, 0xeec1cb733, 0x964498855, 0x2279b8adb, 0x922c72d48, 0xf994172bd, 0x3e047e3dc, 0x317053d24, 0x42c8f55b7, 0xfa9d550dc, 0x91a2dd669, 0xa81f56081, 0x3fd3a6c56, 0xdf850d00a, 0xbe3e03545, 0x407ec6fd3, 0xbd016301a, 0x916a7194f, 0x11a49ea87, 0xc5d123c1e, 0x9a807b6b0, 0x0593ba877, 0x018d46d49, 0xa7a3e5dd0, 0x9686fbc5f, 0x22769d2b3, 0xb1395dd1c, 0x77e0a5c9f, 0x890a050ce, 0x49f50576c, 0xb43273783, 0xf909f5329, 0x9bb92f046, 0x4712ca12d, 0xe74059b06, 0x119424c3b, 0x08b0d1ef6, 0x636ed63ef, 0x75fb4b1ba, 0x64f15c372, 0x77d9f6a84, 0x007ae9bd7, 0xe00da4c99, 0x7a5814217, 0x117097acd, 0x5549740d1, 0x9f3aba1e0, 0x2ceeb811e, 0xed5f8aa13, 0x667486d91, 0x31472697e, 0x71fa40e6c, 0x29d3f8dcc, 0x74e5ff0f1, 0xb18e969c0, 0x331847353, 0x95471db9e, 0x9e3816ef2, 0xc7bdacb19, 0xd33a176c1, 0xc15810741, 0x230e1a526, 0x3e7d17b0b, 0xfaf6ae216, 0x428e9f5b4, 0xbeb6ade2b, 0xde276103c, 0x6928c5d83, 0x685ca40ea, 0xc0d875c85, 0x8096f3381, 0xed453bc21, 0xfbda5c809, 0xa6542bb1d, 0x2e1a744a4, 0x9e5a72efd, 0xedfee81f2, 0xb48280aab, 0x7586536cc, 0xd46c9ac5b, 0x9f228c8e7, 0x2137d18f6, 0x513747f68, 0x88ae16997, 0x6e30cdf98, 0xa67eea5d4, 0x27bf40957, 0xf11c7e690, 0x25449ebbe, 0x0db5bb3b0, 0x7d784749a, 0x51a7cd63c, 0xe23ca5876, 0x4cdd52936, 0x326eaaa63, 0xf8c9d5d50, 0x0ed014396, 0xcf8a25b81, 0x2dbdcc80b, 0xc4aa9df2f, 0x6f6c2f6dc, 0x59e8ef553, 0x0f6c484db, 0x9ec72a877, 0x2cc4e64ca, 0x58899d59c, 0x0bfe119fa, 0x8361ac7b7, 0xb3615653c, 0x541ea167b, 0xfdb2fd954, 0xcf4fd9d05, 0x48f5aab41, 0x22d74d9b3, 0x9b3270e8f, 0x2fff128d0, 0xca0170b88, 0x6ca810fc5, 0x90b6aa826, 0xb1b09d138, 0x02b238b76, 0x98f2254d5, 0xbbb2d3652, 0x3427c35ce, 0xf559d72f4, 0xf982e7fd6, 0xf102bc341, 0xf13b625b0, 0xc6f04c475, 0x7523d80e8, 0x44a0e7ebb, 0xafd06e1bd, 0x68808e0e5, 0x90621d64e, 0xe05e5a36c, 0x83131c4b6, 0x97eb76817, 0xd9cc44ff8, 0x8b36f9654, 0x0245dde9b, 0x520e35f6d, 0xd4cceb189, 0xc2b894013, 0xaeb641c96, 0x7af4d8aea, 0xad2618e25, 0xabe43bbd9, 0xef52ec2a3, 0xb73c6029f, 0x6a3807c97, 0xddfb4bd6f, 0xf3d8e96d6, 0x2aa6fa42a, 0x43a2f1918, 0x3a90c3595, 0x2cd912f20, 0x9adc1bd3c, 0x7b9ac2f88, 0xc5833c0a4, 0xbd9b65455, 0xcb1c9e7ea, 0x63a0524fd, 0xf4c384b5a, 0xe8e524253, 0xc22b11d9f, 0x68422fc45, 0xa68c0b54c, 0x26f6c3e32, 0x6d33234dd, 0x3249aeef8, 0xa44768ab6, 0x799b27147, 0xc2d133071, 0x97db182d3, 0x86eb74d4a, 0xe937414e1, 0xa7a7bb500, 0xbb9745c67, 0x598c8590c, 0x0daa06872, 0x1630a0579, 0xed748567f, 0x985b0f840, 0x65fbf1b05, 0x2ac24e078, 0x8e44e7201, 0x73dea54fb, 0xec53fc29d, 0x17eb2107b, 0x0623990cd, 0xe8d2b249a, 0x3e53f5292, 0xb31e481fa, 0xbd28c91c7, 0xc95853493, 0x4cf19e5a3, 0x13dd03e15, 0xe420f8b60, 0x0aba216f1, 0xfc949ce77, 0x12cc4c8b0, 0xda1af11cb, 0x95e51047d, 0x239712b3f, 0xdd8c9ff85, 0x3b7c11327, 0x03706c9cd, 0x4a5428a10, 0xf9ff29dac, 0x6880bb16e, 0x39ce35cc3, 0x348a6f738, 0x481ebd8be, 0x312f67693, 0x066d19548, 0x252c908b8, 0x93dd489c4, 0x2e916877e, 0x4f03ba3eb, 0x8332640a5, 0xb5418976c, 0x43e45adcf, 0x5ad03c442, 0xc5c651faa, 0xe9e22aff4, 0xe3e84f5ac, 0xfa27e6393, 0x5c2975ff6, 0xeb28706c1, 0xbc16eb250, 0xb230ff592, 0xe01b41ea3, 0x550beeb62, 0x3acc6d9d9, 0xfee57e361, 0x0e47f1f33, 0xa13c0e131, 0x8c28e5a14, 0x7d201d0ee, 0x72377cd9d, 0xc2d4903e8, 0xd865c90ce, 0x5159115fe, 0x70d91786d, 0xa6859de80, 0xfb7b97d08, 0x5844a534d, 0x902dba777, 0x36d28050e, 0x01bc8a4f9, 0x6c810239d, 0x1b8bdbc1d, 0xed019746d, 0xb2e22db8b, 0xce20242c4, 0x277835081, 0x55c421fe5, 0x1c3d0d749, 0x26bd653e3, 0xd7ed2ff69, 0x10c6fc33b, 0x9ea03e399, 0x5b22ed1a3, 0x99ced9f23, 0x6ac377418, 0x9129d7dd6, 0x43ace647b, 0x7c4b49f58, 0x900ae344a, 0x2b8959613, 0x47fc08ec9, 0x21d67379e, 0xd89df08fa, 0x37d955225, 0xcc10979b9, 0x6621b1eb7, 0x0de2fc4a2, 0x745cfaf22, 0x8d46a9619, 0x61b1ceee4, 0x675b9a2bf, 0x40058aafa, 0x05d25b9c4, 0xefcb86566, 0xc13e788ee, 0xab9e7280b, 0xd9306e8d4, 0xa266d71b8, 0x45995737d, 0xea8f02adb, 0xb313918c4, 0x970f9be58, 0xaaf674ce6, 0xc7d00b910, 0xfa502e688, 0x3702f79ae, 0xd893b843d, 0x0f1e45ddb, 0x93c9617a8, 0xe14247733, 0x43f4cb24c, 0xf1b75980e, 0xcea5553fb, 0x4f4d89e4b, 0xd8bfdb958, 0xe231a41da, 0x60116696a, 0x12cdb2096, 0x6d0202075, 0xb75ae1a2a, 0x888d79ea8, 0xc7d80e5c6, 0x4f21633fd, 0x9375ea207, 0x84017c66b, 0x7ec585495, 0x5be0f7c5c, 0x14b106f8a, 0xba2feec25, 0xf12261575, 0xd87fc9c27, 0x7ffea3372, 0xfe6f6a5b2, 0x494a627df, 0x73c4f89f4, 0xb54156ddb, 0x14d501f4e, 0xbe50c2ad8, 0x76cfa8441, 0x2a6832d8f, 0x82ed6f577, 0x234ee72bd, 0x3fe939c14, 0xd9aa5f1bf, 0x436b7049e, 0xe939e6266, 0xcab65d44c, 0xc6b90201d, 0x9dd60ae8c, 0x975c2a441, 0x3eaa603e5, 0x67e5526b2, 0xdc57f5bea, 0xbca1f74ba, 0xc3472a0b3, 0x74fc1b243, 0x4011a3cad, 0x688f30527, 0x7cb1bd3b6, 0xc6172373d, 0x1e58a5d3b, 0x161e143f2, 0x69fecc526, 0xedc625028, 0x62386857c, 0xc65817d6e, 0x1c2907ace, 0x5f845976a, 0xc71a8dc11, 0x56431fdb7, 0x096c5d1c4, 0x7fa1f8582, 0x71e278b58, 0x50719d063, 0x9f166f178, 0x503ada677, 0x044953c8b, 0x3477a905c, 0xe18a293ad, 0x63eb0f954, 0x6504fe3f3, 0x207477edc, 0x45395da2e, 0x0d5d3fe02, 0xa8b671eab, 0x53b890c75, 0x21318478d, 0x84c15d0ff, 0x1163ede85, 0xa3d4784cf, 0x0e8d78cf3, 0x029b52b98, 0x31261cfa9, 0x8ce517f2f, 0xebc01b551, 0x55e719687, 0x14a334c3e, 0x7a18edcf6, 0xd2adc5527, 0xb9355ca29, 0x899223cf7, 0xcb97089c8, 0xc024cf877, 0xb705e424b, 0xa8e0142c5, 0xd60a133e3, 0xfbb712edc, 0x90ac40d24, 0x80b3aa7bc, 0xa0fa4a297, 0xa660659eb, 0x6270b5e01, 0x7875e8d73, 0x99b1c9fe5, 0x26147c55f, 0x494d6032a, 0x805c954b3, 0x4bc4dc338, 0x8d28838b6, 0x65f2934e9, 0xd2e0ba595, 0x2f63fd89c, 0x1d468e027, 0xae5c50ea9, 0x2754729f5, 0xb4821c6f9, 0x1e2deee48, 0x6fd833c89, 0xaf7e537b5, 0x0f96cbd90, 0xf82ef480b, 0x906fa3f87, 0x621287584, 0xf05c6358e, 0x5698e95c5, 0x105509992, 0x0762e2a0e, 0x6ffb64722, 0x64d6dccbd, 0x1b7f83d6b, 0x5518fcb18, 0x025ee2c96, 0x8e78ed132, 0xad93d4196, 0x8c8750aa2, 0x9e3c7b381, 0xe5148c631, 0x4b38f2617, 0x82b98bc77, 0x92dcc557c, 0x28dc57fd1, 0xf912e0c62, 0xaac55e599, 0x081984b5c, 0x93826e871, 0xce7abded7, 0x414db1e2d, 0xef68bda6b, 0x47da612d0, 0x07b99ba1e, 0x8b7872c39, 0x3390d271b, 0x32f6bc3ae, 0x77325c35d, 0xff2993b97, 0xd811caa67, 0xf6610ec51, 0xf61101d05, 0x9bdf143c8, 0x712a1da5f, 0x69edb2899, 0x918f4b5fd, 0x9b70b01ed, 0xd1d7c1bd4, 0x7455d932b, 0x53590c39a, 0x4021360a9, 0x1dc922b31, 0xe893c6a98, 0x7e274d451, 0xb3197bda3, 0xe0d039a4c, 0xb5bb78bf2, 0x3f453821e, 0x1ceea1703, 0x7e245e4fa, 0x43dfb0af8, 0x56a72aab3, 0x4cdc702f9, 0x7196ac417, 0x185c13ae6, 0x72a069055, 0xe3b657a99, 0xe54143be9, 0xb96b8d06a, 0xb917bc739, 0x075675126, 0x667eae736, 0xa24735968, 0x80cb15f06, 0x9084726fe, 0x9115fce0f, 0x4fd117067, 0x08ed4302b, 0x09d57f52e, 0x83b947bd2, 0x1b379cbc5, 0x6e4f6d6c3, 0xf3a45c9a2, 0xa6edec8ba, 0xbfe48b96d, 0xa316bb1f0, 0x4b02d5449, 0xb7c8d6f14, 0xf8aab8168, 0xbbd63e715, 0xff2e5262d, 0xe7ce4a45d, 0xe69ea1730, 0x83a416eb4, 0xd131294b9, 0x0cff9c21d, 0x51f972f8c, 0x8aeb661f1, 0x79db4388c, 0x38d94d7a3, 0x8035d996d, 0xcaf8d77c6, 0x6ccc390e7, 0x7510bb2de, 0x47570789c, 0xbb0f0b128, 0xe344866dc, 0xf8e8538c5, 0xa89fe5639, 0x30bf26d3a, 0x9903d49fc, 0x475e6c8f8, 0x7e3d98813, 0x5e6f1698d, 0xa1304eb9b, 0x8662da415, 0x5b84b9c39, 0x8759f87db, 0x9bc957f53, 0xcfafd522d, 0xf8fdaa82a, 0x3975f695c, 0xd9eabbf19, 0x054c9e489, 0xcebed9ba9, 0x3f29c0269, 0x280639ce6, 0x19a9698ec, 0x7e9965582, 0x23efea1b4, 0x5674b2e35, 0x28cfadfad, 0xd224628ae, 0x1a5857d9f, 0x1f2fb59cb, 0x45eeca839, 0xf57b0db20, 0x2cf4d5a09, 0x5898bb1b1, 0xdce4dd9fa, 0xb2fed21f2, 0x29fcd26a6, 0xff1ed7959, 0x4582dd7c6, 0x94d96dcbc, 0x08fcaf998, 0xc2150dc02, 0xcb725e6fe, 0x497bf9d00, 0x9a07aa199, 0x231cc756a, 0x8029024e4, 0x706c3b697, 0x21dab6df9, 0x9822ce6c1, 0xd9339f82b, 0x08588a50c, 0xfc592f12b, 0x5d0de92e1, 0x84cf29460, 0x17dd9463e, 0xd552a6e3f, 0x9921d4023, 0x511997b06, 0xa7db8d63b, 0x7628f7e02, 0xb5a70da67, 0xb78b26044, 0xcc757da90, 0xa372fe31f, 0xa6d0e7885, 0xfdd5c9958, 0x22d093093, 0xac02463cc, 0xb8dc89bef, 0x0c6ac81d2, 0x2453311fd, 0x2a4b37046, 0x1022902e5, 0x09b58f09f, 0xdca206ca4, 0x8c5443cfe, 0xd1bcfda67, 0x06156bcbb, 0x71826e127, 0xd8b00b0ea, 0x16d325e74, 0xf67b3e901, 0xe7d585092, 0xc1aa82c54, 0x020121d7a, 0x836756756, 0xed93b03e8, 0x25e1b4a2b, 0x94279c34f, 0xa6130a7fb, 0x0cf097151, 0x192bb41b7, 0x82650ff19, 0x222fe2d89, 0xf38d6658f, 0x0da70ff01, 0xd531e4109, 0x8fc408d99, 0x864f65e98, 0x0f552caea, 0xf07941d6e, 0x69520b2cc, 0x4e19bbdfb, 0x201ad85b4, 0xa24f492e0, 0xf577561a2, 0x3ac417bfd, 0x2c262d743, 0x1a57ae77d, 0x9cd8b411c, 0xd39c85983, 0x11b2afd51, 0x249ce5cfb, 0xd33548b8e, 0x5dd56d7c9, 0xa56ee9248, 0x425d68e8a, 0x10f87e0e9, 0xc6b7f55b9, 0x359462f78, 0xf68d21c1e, 0x7611706cd, 0x1252d7e37, 0xa8bfdb38c, 0xe86b4fbd2, 0x35a2f972f, 0xe3d6ec1c8, 0x1b4bc2a9c, 0x1daaaa19d, 0x2883e99fa, 0x0deb8b211, 0xa3779f2c6, 0xe9e6d10a7, 0x4ea5c2770, 0xec50b1009, 0x914f44e74, 0x42c94c52e, 0xddaeee892, 0x77cbea957, 0xa1c5404a3, 0xbb7add120, 0x3a28116d5, 0x862e8ec66, 0x4ecbec8b1, 0x86bbbeb7a, 0x09efcbc44, 0xa213bc2a8, 0xf18dee3d2, 0xcfabe895b, 0x62d502afd, 0xdee6d82c7, 0x72e120e31, 0xf40d09991, 0xdf823444b, 0x5265afe71, 0x30a0e4dfe, 0x5c5c0b7f4, 0x4996907d6, 0x600c53191, 0x01ac06c9a, 0x4a53707b6, 0xd16ea6a44, 0x60be6e211, 0x5edf96076, 0x6b2e67779, 0x93d96e2ee, 0x90846d495, 0x61eaedc80, 0x1e267b96c, 0x17530b57d, 0x64fa1dd35, 0xbbb4c69f5, 0xb6323afb6, 0xf8d4d766b, 0x25e356458, 0x53934ceed, 0x864225814, 0x1c36a7a0f, 0x778490a0c, 0x5cc616142, 0x636654005, 0x8f554e490, 0x2984db337, 0x02ac89bed, 0x09a93c224, 0xa4a194fe7, 0x9a75ab8d8, 0x26245c20a, 0xa64fd081d, 0xfa8cde28a, 0x975c3c712, 0x8b1ad0475, 0xcfa7b1de2, 0xf2bdad2ed, 0x071b918ba, 0x1eaea2ff4, 0x04838c15b, 0x599911ed2, 0x41ddcd721, 0xdb10e3fb5, 0x8bbadce41, 0xfb483af95, 0x919fc8b26, 0xe2414e967, 0x33632f41a, 0x8ef4feed2, 0x7288b6a3a, 0x8f0db5f29, 0x35429b088, 0x34b45572b, 0x5a4889ae3, 0x22ac2efa9, 0x49b0e4db7, 0x8fd129de6, 0x0aaddf60d, 0x164d7e181, 0xb4c6f0d55, 0x8a1d30ab1, 0xd69bcbc97, 0x84b118674, 0x83223f98f, 0xa7e49656e, 0xb2eaa12b5, 0xbbd1fc497, 0x8737c574e, 0x9c29ec54f, 0x48941910c, 0x7b5140011, 0x14d62b95a, 0x004a8bee9, 0x17d22cde5, 0x779768374, 0x41d9d481e, 0xdfc61088a, 0x8ae83d895, 0xefd5a6e97, 0x0e9142829, 0x684e1983d, 0xbd5acb77f, 0x2eb9f5998, 0x084ad2738, 0xca47a6db4, 0xb730d9221, 0xe1d02dae3, 0x1897bbeed, 0xae6460ece, 0x2ae10dcc2, 0x20b562229, 0xab5a5963e, 0x23f786b94, 0x7a1e0be5b, 0x0d416a4bd, 0xfda34600b, 0xea42e3913, 0x191c6acd2, 0x2cd0c0257, 0x3fa745285, 0x486a34308, 0xd5bc0fc16, 0x9c29c1970, 0xc748e4213, 0x7d894d16d, 0x462f9a307, 0x93e77fc9b, 0x2586ca766, 0x7f4843d74, 0xc59dfb603, 0xcc9f8a977, 0xfcd5dbdaa, 0xabd042620, 0x01e98ed52, 0x3723c0ed4, 0xbba7a3d47, 0x87191e9e5, 0x96f863d99, 0x52ff61749, 0xed5634dce, 0x29e089ed4, 0xc7840939c, 0x710fd2bd7, 0xa7bcde8ee, 0x6992f5b0e, 0x8e43638da, 0xa8f8bb730, 0xb3ac0121a, 0x9a39430a5, 0xb400f5406, 0xf1fed9cf4, 0xecb8eed3d, 0xf982961b8, 0xd2ca7f580, 0xc0ff82a1a, 0x472f86bfa, 0x6c7819a1a, 0xc5fb45b51, 0x1e8265bbc, 0x992ea46fb, 0xeae69326c, 0x5cf05b4b0, 0x4dba41e1b, 0x678b0c87b, 0x541dfe46d, 0x5c6805370, 0xa46d1f411, 0x20ca43c25, 0xb825728d0, 0x60e64b7c3, 0x158a87789, 0xec8327da8, 0x312f31d11, 0x44e751abd, 0xb86749801, 0xf1e21217d, 0x1df98766a, 0x3b82a6a92, 0x813e55a4a, 0x425a3e347, 0x23d2e0991, 0x125b5b7a8, 0x299f2386d, 0xae87ad90e, 0x88d6c80c2, 0x505d3e3ac, 0x8c08d9bf5, 0xbc74ec4c7, 0xb4b961f43, 0xeffd6e25b, 0xa34783dd4, 0x4b77e81ed, 0xdae14fb89, 0x652a40492, 0xb89ac1d1f, 0xc326835a3, 0x62377a03e, 0x073a0bde3, 0x63ab6d119, 0xa4516da9b, 0x7310b4716, 0x0eaa5bfd1, 0xb2e0c1b7a, 0x6b2d91842, 0xa71ee6024, 0xe96938770, 0x94bf95cc1, 0x13752cd22, 0x0212fadb3, 0xa6d81af51, 0xdf3594b4e, 0x74d16cfea, 0x1c7666313, 0xd4d2825d3, 0x32ef55c77, 0xb41709c57, 0x65496705f, 0x46c363baa, 0xe5d09d8b4, 0x4a092d2ad, 0x1c85dc273, 0xb7fd50ec1, 0x85898eb2f, 0x64e4c723d, 0x53d9f5ed1, 0x3a557ef3b, 0xbb1bf6342, 0x5a5ef851b, 0x47ad6c0ef, 0x8fb3984b8, 0xde8ad29aa, 0xce019b097, 0xa2e99fbda, 0x254954e30, 0x380afe9d3, 0x6ed87890f, 0x75c288fad, 0xfed4797b1, 0x1b19ca486, 0x2bddbba6b, 0xbda8398a9, 0x4b96c12d9, 0x74448a4d4, 0x84a06a048, 0x7be5eb6f5, 0xbf1429ebc, 0x317cbe9b3, 0xda1bfba51, 0xf19033d98, 0x6692ec390, 0x85de73668, 0x502e6e128, 0x6bf51b707, 0x858deeef7, 0x231f255c8, 0xdc5285120, 0x1f7499d35, 0x51e562dfb, 0xfd31d9e13, 0xf56f7abe5, 0xbfe2014b4, 0xae9e0b0ba, 0x04ab6818f, 0xfc5222cf4, 0xe479029b2, 0xedac0cbc2, 0x3dd056ec8, 0x2b3ab1bf3, 0x96090fde2, 0x7414985b2, 0x07c5f1053, 0xc912a2b86, 0x2238893ca, 0x0a047b8d4, 0x956a79db3, 0xc987e2e17, 0xa3c23d85a, 0x97129d3d4, 0x8602ebdf8, 0x0c1e5c94a, 0x728fa9af1, 0x6783b3466, 0xd03a47b3f, 0x577e66a97, 0x064ea8d8f, 0xf810556b3, 0x550d70ce2, 0xeaf8c9627, 0xe1c975366, 0xb0c0fb42a, 0x60b80b9c6, 0xe5c4caf80, 0x54c8d166b, 0xc8f6e29f8, 0xb0c391d73, 0xc5684f473, 0x0812877ca, 0xd98c3dc0f, 0xa530878c2, 0x83b26929f, 0x473ec8d20, 0xfb27d5064, 0x790c88e09, 0x4fad3f4a3, 0xde15f1749, 0xc2ba6e2ac, 0xe52a2cfb9, 0xc5797941c, 0x383593138, 0x7a025b10a, 0x92d15a83d, 0x3084af2a3, 0x6cfe2a38b, 0x66973a8f4, 0x265dd307b, 0x884284f79, 0xf04052eb4, 0x94b8aaade, 0x0bd36a298, 0xe22dd0993, 0x30a8178f2, 0xef40b3bad, 0x5fd9521de, 0xe323cbc56, 0x2dbd84334, 0xe7f732978, 0xc940d0d9e, 0x017e1db0d, 0xb30f2898d, 0x3a70d4c13, 0x6877cc2c7, 0xb29c26091, 0x86d1b6ba0, 0x34790d00a, 0xcea3d1c3a, 0x609555677, 0x47ae0cd43, 0x6bc9151d8, 0xcd08c96bf, 0x2dcf87f90, 0x5d38abc7a, 0xb53944398, 0x5aa36c2c2, 0x6dc1a9602, 0x3f78a849e, 0x9a75bd745, 0xcccae769f, 0x7bb8bd72b, 0x37c8f5b48, 0x63307f50e, 0xa16e04992, 0x461e6f322, 0x05c9b0b16, 0x125571ace, 0xd671fa72f, 0x1da08d7df, 0xf75a3b250, 0xc3e35da05, 0x9debf4cf5, 0x568893e81, 0x9f45f5a8f, 0xd28f36e5f, 0x39ed2c299, 0x7ec5b28bf, 0x726971dbd, 0x62a7e6608, 0x2465cc620, 0x54b82a639, 0x16f964b59, 0x18afd656a, 0xfa45a2401, 0xd63e74a3e, 0x85c8b9164, 0x01c5a5bfb, 0x7b406d02c, 0x1a6885eda, 0xea0f61089, 0x3356e4e19, 0x954d1c237, 0x73894ee02, 0x594d206b1, 0xa34df0652, 0x6627dfb9c, 0xe0a8d336f, 0xf76b0bf3e, 0xf4bcb8c6c, 0x9cfee3b2a, 0x727af778e, 0x2af80ac19, 0xa99353076, 0xbc1b3a11f, 0x055fa22ab, 0x5bc6b849e, 0xa7b5b3826, 0x1464c65f1, 0xb797e45fe, 0x06aa7641c, 0xd6402bea1, 0x69042dc7a, 0xc27a84b0f, 0xc3e40bc3e, 0x5188a9088, 0x9ca221e9f, 0x2eeb0cf45, 0x387326c49, 0xc192f116f, 0x5b4afe3f7, 0x1e2b7028b, 0xf315bf477, 0x1dfa88408, 0x82ede7a9f, 0x1daec4b02, 0x90b55c4fb, 0x1dfa5f446, 0x35d8744be, 0x9ed16f6c2, 0xbe5a98781, 0x057cf82b0, 0x62c4d6074, 0x0e524f153, 0x5ad102332, 0x5ce554139, 0x09b4882e4, 0x2f854512b, 0x42376f39f, 0xbd5b7cd06, 0x5f34b8fa2, 0xc8dd8867a, 0x26ff91deb, 0x24fc05cf4, 0x61e928d08, 0xe5ed22480, 0x7edcca236, 0xbf19c5c5a, 0xd876f6600, 0x18cc2a06e, 0x98f9a0f2d, 0x0e46da359, 0xf10ca127d, 0x4ea58d6c8, 0xc5d584fac, 0x4168b3771, 0xf7742c3ab, 0x3d9e01ab6, 0x749603675, 0x93d380e27, 0x935fbdf99, 0x8b004f544, 0xf21336ccb, 0x55be0a2d7, 0x31a272812, 0x9356f2104, 0x64cd11059, 0xb306fab7b, 0xc4b4bcecb, 0xa44ee754c, 0x9c5b95d4a, 0xafe82cb14, 0xd2802c70a, 0x9b067ca08, 0xa0d33eadf, 0xf82d374e8, 0x97608d4c1, 0x3c49f7262, 0x1f8b8b4b2, 0xd49171ea7, 0x9abe1e7f5, 0x127c694cc, 0xad02f7180, 0x48dcd2cc8, 0x781de93ca, 0x2593187ee, 0xdc2e3515f, 0x97535dc18, 0x3db5f0785, 0xcb73b619d, 0x76c0cae0f, 0x195f0526d, 0x4b0893b28, 0xca2151e27, 0x0e01526ba, 0x844d01096, 0x96ed3edd6, 0xfe1d07fad, 0x625d110ec, 0xd6e07dc43, 0xa0d531bbf, 0xed6e29fd3, 0x9aa5ff7e9, 0x2bf330b23, 0xaa905fb48, 0x575c3dd88, 0xc12a8ea3e, 0xa60ce7ea7, 0x36e3d46be, 0x84a1acf90, 0x99315f5ef, 0x23c5c149e, 0xe819f9d2a, 0x0327b7f85, 0x60878c9fc, 0xbbe1b425f, 0x5efb57d1a, 0xae81e06a3, 0xc683416e0, 0xa138a207b, 0x531a8805d, 0x3207cd72b, 0x1ffad4bab, 0xa05d08c41, 0xc4ffc6089, 0xf6ebda0bc, 0xf9c6b0a7b, 0x76ac7063f, 0xbd7b1a5b1, 0xf6e306a3f, 0x93f23d425, 0xc9834e422, 0x73088434a, 0xb618f4fe0, 0x7affb1ed0, 0x8de2b690d, 0xe7bbca4f9, 0x0e92d2cd5, 0xb572af3dd, 0xa32f50358, 0x97d0aca69, 0x4e02a1956, 0x489a38814, 0x16cde41bf, 0xf844bb35b, 0xb3cb5e287, 0x798ca35d5, 0xad78e6952, 0x74e3accf5, 0x2c2509397, 0x9ed3b6e0b, 0x382fd5392, 0x46b1753cc, 0x3f1a79503, 0xd511be53c, 0x2c0ad700b, 0x0c83dab06, 0x854c15d1c, 0xa27cbb3d7, 0xf178f1810, 0xaa69504f2, 0x619f3c356, 0x2a31f3e7c, 0xef900e61d, 0xdfe8751a9, 0x651358e73, 0xc825327af, 0xbc151fafa, 0x876051de6, 0x06729eb40, 0x75876a783, 0x8c76d5474, 0x39bd3dd20, 0xbbc32223b, 0xf8ae91f88, 0xe3bbca3d6, 0xa0a3ee436, 0xf993c8887, 0xde8781781, 0xc3d26acc2, 0xce1748eb0, 0x09c49b6ab, 0xe7ea808f1, 0x34d62cf99, 0xf0dcc0da8, 0x49ca61d07, 0x1b930880d, 0xdca578c15, 0xda7a6a1ce, 0x9c3294a82, 0xf0874721e, 0xa5dc060ed, 0x23a8939a5, 0x6f6c16f02, 0x42edd94dc, 0x5a74f1432, 0xe019cb4dd, 0xc2c5b533e, 0xecc894724, 0xa5cff9f11, 0x04a5864ab, 0xbf6b96bc9, 0xd7b3ded99, 0x7a9377d6f, 0x8a7f9cef2, 0xacf09eaad, 0x785f73185, 0x8904b414b, 0xbd5fa7379, 0x43ddabc60, 0x17f40d8fb, 0xcf6903101, 0x4cf434f98, 0xa97973ef7, 0xb3c4ac601, 0xc0aad8a1b, 0x2150bb64d, 0xed72e5ac5, 0x131cef825, 0x8659cecc4, 0xf30a8f072, 0x457c90fda, 0xc9df54666, 0x68743306f, 0x62021b53d, 0xf9d7ea28a, 0x844e5bcd0, 0xfb1a1a1dc, 0x1394fd8d2, 0xf744f941e, 0xc07e65afb, 0x84a9e17d6, 0x9cd3f1176, 0x332e89b30, 0xbb9140f2d, 0x941e8e334, 0x9439f6e24, 0x0b89c5739, 0x077975e23, 0x4317e76cb, 0x53f2c5011, 0x7826317f7, 0xfad95bff5, 0x053de8de6, 0x856bcf7ed, 0x77772201b, 0x1b15d0bb4, 0x42d5df9e2, 0xd9c5aea63, 0xb4980534a, 0x89c348f43, 0x3d7300d9b, 0x49440d5e1, 0xce4694114, 0x9e6c19bd7, 0xfa1294b28, 0xe2b6e790d, 0xe4891435c, 0x706bb090a, 0xc2f74169c, 0x9d669a64d, 0x4118daf4b, 0x5b118d504, 0x3f57b597f, 0x916e47de1, 0xe3b88c4fe, 0x2af4fd773, 0x74664c8df, 0xd66194717, 0x90a0baf41, 0xcf1f647fa, 0xea211f2d8, 0x75a1f220a, 0x9cb63c40d, 0x812805a51, 0xd5d503690, 0x532bc4026, 0x021a8d59f, 0x5150b9dd3, 0x0a2ee41ba, 0x846fade51, 0xc684ba60e, 0x3a8f6efd7, 0x03e17b682, 0x3927db859, 0x87b0b1480, 0x52536e422, 0x946ed17ec, 0xa214c62c5, 0x4342229d4, 0x7cd868ed0, 0xf19ba2ab2, 0xf8c1c41cc, 0x0cc7d69fb, 0x3c3911e61, 0x18fc07576, 0x0846ea988, 0x9f86addc8, 0xcacea817e, 0x975a047cb, 0xcc00a9d6c, 0x35b095cfd, 0x1032b2bd9, 0x839311750, 0xf61bbb4b8, 0xbeddf32a6, 0x5db253de6, 0xad1c79f1a, 0x0943a5b28, 0x8574f9b27, 0x6cb284742, 0x66a469a9a, 0x9c9e646b7, 0x15e3f3da7, 0xa7335e7c1, 0x81d5b8c23, 0xd3ce4adb1, 0xe6c2c0436, 0x0c422445a, 0x69efe9391, 0x6e494fb4b, 0x52938a7d8, 0x1538c045a, 0x86ffd6a31, 0x3a7a1eda4, 0x6a06881db, 0x0ee1f5cfe, 0x7dbd99f14, 0x2222f7d4f, 0xa092a9546, 0x4f6ea12ec, 0x786076e0d, 0x2025a3e06, 0x3f3c67e47, 0xeeb2ddb02, 0xb1997582f, 0x84774c908, 0xa94d9c44e, 0x687970da3, 0x4ac4aaace, 0xaa5b6afcd, 0x797cefd6e, 0x239edc6f7, 0xf6b54c197, 0x71141e85a, 0x22be2c02b, 0xb8343a746, 0xbb01b3487, 0x2fc5f873d, 0x80dbb9d8f, 0x749b8643d, 0x61163a4ef, 0x899b02afc, 0x6d1359b14, 0x0e87bed7e, 0x34e646200, 0xdb37c86d3, 0x4a0cf7e11, 0xe33dd1e6e, 0x3b788a101, 0x06a936d91, 0x1ddc58739, 0xc92051779, 0x838ce51ae, 0xa7a3ef32d, 0x9f7eb103a, 0x36b9802d8, 0x65da1e81c, 0xea1cf562f, 0xa8c63c0ce, 0xf6104a32a, 0x4c4cf0893, 0xd47da0be3, 0x80483d254, 0xdc6de57b1, 0x7fac92c49, 0xda1e5f16e, 0x4026949bf, 0x8e17a9d20, 0x12f3419d6, 0x4e9089cdf, 0xd8f5fc61e, 0xdc8f7325b, 0x61247ef19, 0x0c1d908c9, 0x69bd43b4c, 0x3f7f5c231, 0x91c41e9bd, 0xbf844084d, 0x05827c577, 0xc07d61e65, 0x7615c75b6, 0x62600d7bb, 0x82f62a3fa, 0x95f7fe291, 0x2ea50c1e5, 0xc90ae812c, 0xc85c79bf6, 0x0614cafda, 0x692bc66d5, 0x43cae4bbe, 0xcc4dd9e12, 0x02b1f9181, 0xd19a5261c, 0xd8e402b96, 0x08f730fc6, 0x159e9ba29, 0xb9413ddab, 0xbd296f2fe, 0x53ae2f38d, 0x42e6e15c5, 0x5efba4ecf, 0x764371efe, 0x8b665b2e1, 0x542432a00, 0xddd7e3c19, 0x195083f58, 0x7ed57c706, 0xb50bbbe8e, 0x203d18735, 0x2a4c69b07, 0xd72e90958, 0xcd3c5031b, 0x313e2ee85, 0xa12fd86c6, 0x9009383ea, 0xe550f2a4f, 0x49ae8c013, 0xeba56010a, 0xa7210786c, 0xfda4a611f, 0xcfe525fb0, 0xefcaf6ef6, 0x23c31fd13, 0x3847c5dcd, 0x166fd6693, 0x06f8ec087, 0xa531e0fb4, 0x76f9bc318, 0xe56c0cb7f, 0x51e2d02ba, 0xb3e8d6022, 0x9a20ad5fa, 0x73af547b7, 0x5e6134b2e, 0x8582b0e60, 0xc8ea6019d, 0x281e3763e, 0x647d83e97, 0x293634305, 0x6743c18c0, 0x2a01782f9, 0xbf49e9eb6, 0x05856f3b9, 0x634812ac0, 0x035cbb63e, 0x032540c2a, 0xaf358f5e0, 0x7826f829f, 0xb8c89448b, 0xebbe0239d, 0x905e5aa89, 0x310ddb064, 0xb762f118b, 0xc9b1a8e31, 0xff0661391, 0x8a66f999f, 0xb3593b7ce, 0x9f603a864, 0xa23a960ef, 0xaae9837ac, 0xc755afc59, 0x9c76f21c9, 0x39cd67a7f, 0x29f1dfa26, 0x01a253c9c, 0x1d3a11177, 0x7f60cd2dd, 0x5871af5dd, 0xa7d3d617c, 0xddbb2b303, 0x6c69147ba, 0x843954b47, 0x46cc229a9, 0x4eac19c20, 0xfb7b51ca4, 0x9b7015d5b, 0xf2051a917, 0xe701d5d53, 0x38fd5da8c, 0xd3f2acb84, 0xba7cb1ebe, 0x1f016ea57, 0xd63c1250f, 0x646f446ad, 0xc43b287cd, 0xdf676c468, 0x30f777359, 0xb8f10af87, 0x88c425335, 0x6c9f778ae, 0x50da4eeba, 0x0690f680a, 0xac101a310, 0xe603ce909, 0xef2918ebe, 0x3bb23758a, 0x409e4b934, 0x74f744bfc, 0x64e96d541, 0x271bc72c6, 0xba27f9ede, 0x782a145a1, 0x61f275072, 0x8c15dac40, 0x3431268fe, 0x9853d7243, 0x98ba31d02, 0x6d1b5e69c, 0xe67d3e6a8, 0x3afb9b2d3, 0x8aef7d109, 0x0e0d77de8, 0xdcbaa0356, 0x6bc718df0, 0x77d6f39fa, 0x1207d50be, 0x68758144a, 0x5600bd7f1, 0x99722a481, 0xbf673f8d1, 0x4bf1cce7e, 0xd3ee2609b, 0x31e9e4c73, 0x32a28985b, 0x9314656c1, 0xcf02f5fdc, 0x2748d2cbe, 0xeeaa65fca, 0xc9294684a, 0x706fb6725, 0x32f6c276b, 0xe030afe87, 0x912b88011, 0x2ab7ee1fe, 0xb04877110, 0x474b92b6d, 0xaccab7218, 0x04c6bb58a, 0x0d6777d7c, 0x6f6008813, 0x1d8da74ef, 0xd9d905134, 0x4ff1a2f68, 0x2861d5528, 0x4ed66d24d, 0x7ee0b92f3, 0x0f2979e98, 0x36291e9bb, 0x0635f0e0b, 0x6cf4ea059, 0xa20b467b1, 0x610cc1d4d, 0x2da5cb5fd, 0x07553968c, 0x844a86803, 0xb1d48ccc2, 0xbba3fe918, 0xae0d869f3, 0x7c6a7de9c, 0x91f8382f4, 0x3014094ca, 0x8c3a9a5d5, 0x69c3f2722, 0x8bb38f982, 0xb8efcdcda, 0xda51b2ff0, 0xcf8e8a44a, 0x8158ddc00, 0x643ecd9c0, 0x5e10383a9, 0x24a886e16, 0x4ba9db990, 0xc8b4e335f, 0x8b1c2c0b8, 0xfba632127, 0x77bb6e51e, 0x63142235c, 0x7906aa8d6, 0x0295334c5, 0x30e855681, 0x7cc4fc438, 0x1cba770b2, 0xeb67c65e9, 0xbf495ac78, 0x250ef8472, 0xe918df704, 0x9ae42835c, 0xba887badd, 0x0a9e3a8cd, 0x6b4efbb80, 0x47e50b225, 0x492ddb0bb, 0x58bc2506d, 0x52aedbb0e, 0x51eb43eb4, 0xea2d9d116, 0x278274efc, 0xc013733d6, 0xd371949d4, 0x8d49ee822, 0x30745b332, 0xafc18e441, 0x0cd9fb4d7, 0x582ae0f65, 0xcacbd79cb, 0x1fe675d20, 0xee7117735, 0xa7280378f, 0xbaf1b5a32, 0x0b5d5e9b3, 0x44196d9dd, 0xd8b6fdafc, 0x82450b356, 0x8e0a46aa9, 0x250b0460e, 0x44582149a, 0x18a09bc26, 0xb26286d64, 0xc9e4860ce, 0xadfc81dad, 0x16506214a, 0x038769b15, 0xc01b50928, 0x151ac514f, 0x5492593da, 0x5946d5c27, 0xab9aed4df, 0xc91cd1da7, 0xc3495b589, 0x2e962ae83, 0xeab920345, 0x155b3b617, 0x985edf48f, 0xe758d6ba3, 0x99660780e, 0x7b8a41acf, 0x6c4f8c59f, 0x970c219fa, 0x5fa614ff0, 0xa7b3adda7, 0x809edc138, 0xb4ee65663, 0x6b487e8ba, 0xa530f957e, 0x8a533c79b, 0x00d94ff5c, 0x9b709ef88, 0xd7c38826e, 0x0e7bcd688, 0x23668c8a0, 0x87244e859, 0xb1006de44, 0x15b37df10, 0x801e94f9d, 0xbce729ec0, 0x17ddf288b, 0x4bafecdbd, 0x8536977b1, 0x6f5ddbf9a, 0x23d5da865, 0x68e3a57c7, 0xfbb7bc650, 0xa412fceb2, 0x0cb978a6f, 0x30b6a7328, 0x167252f06, 0xe0df087e5, 0x022465eb6, 0xb580a4f2c, 0x0198d1533, 0x6e118afbe, 0xa3a697b20, 0x481fe6809, 0xc1cae26f0, 0xad006f34b, 0xdef609d40, 0x18a918f11, 0x68a4bf8df, 0x4f8f44a9a, 0x4311a21a3, 0x53d72ea12, 0x51e4bd4d4, 0xf2cda5994, 0xd575a8336, 0x41cf85c53, 0x30eda148a, 0x907fa024d, 0x6e3cf917b, 0x470d9c67d, 0x73dc15f58, 0x708ec5e31, 0x83e1f42e8, 0xb315ee8bb, 0xd6b511041, 0xea2405d10, 0x8f51802b0, 0xb2ab1513b, 0xf31e33ae6, 0x55a48d565, 0x57cd5d243, 0xe705530c5, 0xf0908bfd5, 0x37a4d3e77] + + TagFamilies = { 't16h5': (t16h5,16), + 't25h7': (t25h7,25), + 't25h9': (t25h9,25), + #'t36h9': (t36h9, 36), + 't36h11': (t36h11,36)} + + def __init__(self, chosenTagFamiliy): + try: + self.chosenTagFamiliy = chosenTagFamiliy + self.tagCodes = AprilTagCodes.TagFamilies[chosenTagFamiliy][0] + self.totalBits = AprilTagCodes.TagFamilies[chosenTagFamiliy][1] + except: + print("[ERROR]: Unknown tag familiy.") + sys.exit(0) + +#borderBits must be consitent with the variable "blackBorder" in the detector code in file ethz_apriltag2/src/TagFamily.cc +def generateAprilTag(canvas, position, metricSize, tagSpacing, tagID, tagFamililyData, rotation=2, symmCorners=True, borderBits=2, ccolor=color.rgb.black): + #get the tag code + try: + tagCode=tagFamililyData.tagCodes[tagID] + except: + print("[ERROR]: Requested tag ID of {0} not available in the {1} TagFamiliy".format(tagID, tagFamililyData.chosenTagFamiliy)) + + #calculate the bit size of the tag + sqrtBits = (math.sqrt(tagFamililyData.totalBits)) + bitSquareSize = metricSize / (sqrtBits+borderBits*2) + + #position of tag + xPos = position[0] + yPos = position[1] + + #borders (2x bit size) + borderSize = borderBits*bitSquareSize + + c.fill(path.rect(xPos, yPos, metricSize, borderSize),[ccolor]) #bottom + c.fill(path.rect(xPos, yPos+metricSize-borderSize, metricSize, borderSize),[ccolor]) #top + c.fill(path.rect(xPos+metricSize-borderSize, yPos, borderSize, metricSize),[ccolor]) #left + c.fill(path.rect(xPos, yPos, borderSize, metricSize),[ccolor]) #right + + #create numpy matrix of code + codeMatrix = np.zeros((int(sqrtBits), int(sqrtBits))) + for i in range(0, int(sqrtBits)): + for j in range(0, int(sqrtBits)): + if not tagCode & (1 << int(sqrtBits)*i+j): + codeMatrix[i,j] = 1 + + #rotation + codeMatrix = np.rot90(codeMatrix, rotation) + + #bits + for i in range(0, int(sqrtBits)): + for j in range(0, int(sqrtBits)): + if codeMatrix[i,j]: + c.fill(path.rect(xPos+(j+borderBits)*bitSquareSize, yPos+((borderBits-1)+sqrtBits-i)*bitSquareSize, bitSquareSize, bitSquareSize),[ccolor]) + + #add squares to make corners symmetric (decreases the effect of motion blur in the subpix refinement...) + if symmCorners: + print('drawing corners!') + metricSquareSize = tagSpacing*metricSize + + corners = [ + [xPos-metricSquareSize, yPos-metricSquareSize ], + [xPos+metricSize, yPos-metricSquareSize], + [xPos+metricSize, yPos+metricSize], + [xPos-metricSquareSize, yPos+metricSize] + ] + + for point in corners: + c.fill(path.rect(point[0], point[1], metricSquareSize, metricSquareSize),[ccolor]) + +#tagSpaceing in % of tagSize +def generateAprilBoard(canvas, n_cols, n_rows, margx, margy, tagSize, tagSpacing=0.25, tagFamily="t36h11", + acolor = "Black", startid = 0,borderBits=2, symmCorners=False): + if(tagSpacing<0 or tagSpacing>1.0): + print("[ERROR]: Invalid tagSpacing specified. [0-1.0] of tagSize") + sys.exit(0) + + #convert to cm + tagSize = tagSize*100.0 + + #get the tag familiy data + tagFamilyData = AprilTagCodes(tagFamily) + + #create one tag + numTags = n_cols*n_rows + + # draw margins + xmax = 2 * margx * 100 + n_cols * (1+tagSpacing)*tagSize + tagSpacing * tagSize; + ymax = 2 * margy * 100 + n_rows * (1+tagSpacing)*tagSize + tagSpacing * tagSize; + boundrect = path.rect(0,0, xmax, ymax) + ccolor = getattr(color.cmyk, acolor) + c.stroke(boundrect, [style.linewidth(0.000001*unit.w_cm), ccolor]) + + #draw tags + for y in range(0,n_rows): + for x in range(0,n_cols): + id = startid + n_cols * y + x + pos = ( margx*100 + x*(1+tagSpacing)*tagSize + tagSpacing*tagSize, margy*100 + y*(1+tagSpacing)*tagSize + tagSpacing*tagSize) + generateAprilTag(canvas, pos, tagSize, tagSpacing, id, tagFamilyData, rotation=2, borderBits=borderBits, ccolor=ccolor, symmCorners=symmCorners) + #c.text(pos[0]+0.45*tagSize, pos[1]-0.7*tagSize*tagSpacing, "{0}".format(id)) + + #draw axis + drawLegend = False + if drawLegend: + pos = ( -1.5*tagSpacing*tagSize, -1.5*tagSpacing*tagSize) + c.stroke(path.line(pos[0], pos[1], pos[0]+tagSize*0.3, pos[1]), + [color.rgb.red, + deco.earrow([deco.stroked([color.rgb.red, style.linejoin.round]), + deco.filled([color.rgb.red])], size=tagSize*0.10)]) + c.text(pos[0]+tagSize*0.3, pos[1], "x") + c.stroke(path.line(pos[0], pos[1], pos[0], pos[1]+tagSize*0.3), + [color.rgb.green, + deco.earrow([deco.stroked([color.rgb.green, style.linejoin.round]), + deco.filled([color.rgb.green])], size=tagSize*0.10)]) + c.text(pos[0], pos[1]+tagSize*0.3, "y") + + #text + caption = "{0}x{1} tags, size={2}cm and spacing={3}cm".format(n_cols,n_rows,tagSize,tagSpacing*tagSize) + c.text(pos[0]+0.6*tagSize, pos[0], caption) + + +if __name__ == "__main__": + + # This code was lifted from Kalibr at some point... + + usage=""" + make_tag.py --nx 6 --ny 6 --tsize 0.08 --tspace 0.3 + """ + + #setup the argument list + parser = argparse.ArgumentParser(description='Generate apriltag PDF.', usage=usage) + + outputOptions = parser.add_argument_group('Output options') + outputOptions.add_argument('output', nargs="?", default="target", help='Output filename') + + genericOptions = parser.add_argument_group('Generic grid options') + genericOptions.add_argument('--nx', type=int, default=6, dest='n_cols', help='The number of tags in x direction (default: %(default)s)\n') + genericOptions.add_argument('--ny', type=int, default=7, dest='n_rows', help='The number of tags in y direction (default: %(default)s)') + genericOptions.add_argument('--marginx', type=float, default=0, dest='marginx', help='Margin [m] in x direction (default: %(default)s)') + genericOptions.add_argument('--marginy', type=float, default=0, dest='marginy', help='Margin [m] in y direction (default: %(default)s)') + genericOptions.add_argument('--color', default="Black", dest='color', help='Color in cmyk space (default: %(default)s)') + + aprilOptions = parser.add_argument_group('Apriltag arguments') + aprilOptions.add_argument('--tsize', type=float, default=0.08, dest='tsize', help='The size of one tag [m] (default: %(default)s)') + aprilOptions.add_argument('--tspace', type=float, default=0.3, dest='tagspacing', help='The space between the tags in fraction of the edge size [0..1] (default: %(default)s)') + aprilOptions.add_argument('--tfam', default='t36h11', dest='tagfamiliy', help='Familiy of April tags {0} (default: %(default)s)'.format(AprilTagCodes.TagFamilies.keys())) + aprilOptions.add_argument('--startid', default=0, type=int, dest='startid', help='Start number for apriltag (default: %(default)s)') + aprilOptions.add_argument('--borderbits', default=2, type=int, dest='borderBits', help='number of bits used for black border (default: %(default)s)') + aprilOptions.add_argument('--symm_corners', default=False, dest='symmCorners', action='store_true', help='add black corner squares (default: %(default)s)') + + if len(sys.argv)==1: + parser.print_help() + sys.exit(0) + + #Parser the argument list + try: + parsed = parser.parse_args() + except: + sys.exit(0) + + #open a new canvas + c = canvas.canvas() + + generateAprilBoard(canvas, parsed.n_cols, parsed.n_rows, parsed.marginx, parsed.marginy, parsed.tsize, parsed.tagspacing, parsed.tagfamiliy, parsed.color, parsed.startid, borderBits=parsed.borderBits, symmCorners=parsed.symmCorners) + + #write to file + c.writePDFfile(parsed.output) \ No newline at end of file diff --git a/sitl_config/ugv/catvehicle/urdf/catvehicle1-3.xacro b/sitl_config/ugv/catvehicle/urdf/catvehicle1-3.xacro index bf9daf7..e43c13c 100644 --- a/sitl_config/ugv/catvehicle/urdf/catvehicle1-3.xacro +++ b/sitl_config/ugv/catvehicle/urdf/catvehicle1-3.xacro @@ -676,7 +676,7 @@ http://www.car-engineer.com/vehicle-inertia-calculation-tool/ - +